AP_NavEKF2: Reduce allowance for magnetometer timing errors
The previous gain from rate to magnetometer error was excessive. The revised value is equivalent to a magnetic field length of 0.5 with a timing uncertainty of 0.01 sec
mission-4.1.18
Paul Riseborough9 years agocommitted byAndrew Tridgell
hgtRetryTimeMode12_ms(5000),// Height retry time without vertical velocity measurement (msec)
hgtRetryTimeMode12_ms(5000),// Height retry time without vertical velocity measurement (msec)
tasRetryTime_ms(5000),// True airspeed timeout and retry interval (msec)
tasRetryTime_ms(5000),// True airspeed timeout and retry interval (msec)
magFailTimeLimit_ms(10000),// number of msec before a magnetometer failing innovation consistency checks is declared failed (msec)
magFailTimeLimit_ms(10000),// number of msec before a magnetometer failing innovation consistency checks is declared failed (msec)
magVarRateScale(0.05f),// scale factor applied to magnetometer variance due to angular rate
magVarRateScale(0.005f),// scale factor applied to magnetometer variance due to angular rate and measurement timing jitter. Assume timing jitter of 10msec
gyroBiasNoiseScaler(2.0f),// scale factor applied to imu gyro bias learning before the vehicle is armed
gyroBiasNoiseScaler(2.0f),// scale factor applied to imu gyro bias learning before the vehicle is armed
hgtAvg_ms(100),// average number of msec between height measurements
hgtAvg_ms(100),// average number of msec between height measurements
betaAvg_ms(100),// average number of msec between synthetic sideslip measurements
betaAvg_ms(100),// average number of msec between synthetic sideslip measurements