mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-12 10:58:30 -04:00
AP_NavEKF3: Use large accel process noise when IMU data is bad
This commit is contained in:
parent
eb5a82dd38
commit
8b16d8dc4c
@ -1135,7 +1135,7 @@ void NavEKF3_core::CovariancePrediction(Vector3F *rotVarVecPtr)
|
||||
ftype _gyrNoise = constrain_ftype(frontend->_gyrNoise, 0.0f, 1.0f);
|
||||
daxVar = dayVar = dazVar = sq(dt*_gyrNoise);
|
||||
}
|
||||
ftype _accNoise = constrain_ftype(frontend->_accNoise, 0.0f, 10.0f);
|
||||
ftype _accNoise = badIMUdata ? BAD_IMU_DATA_ACC_P_NSE : constrain_ftype(frontend->_accNoise, 0.0f, 10.0f);
|
||||
dvxVar = dvyVar = dvzVar = sq(dt*_accNoise);
|
||||
|
||||
if (!inhibitDelVelBiasStates) {
|
||||
|
@ -96,6 +96,8 @@
|
||||
#define EK3_POSXY_STATE_LIMIT 1.0e6
|
||||
#endif
|
||||
|
||||
#define BAD_IMU_DATA_ACC_P_NSE 5.0f
|
||||
|
||||
class NavEKF3_core : public NavEKF_core_common
|
||||
{
|
||||
public:
|
||||
|
Loading…
Reference in New Issue
Block a user