AP_NavEKF: Predict covariance more often to prevent instability on startup
If the baro data and magnetometer data are interleaved (arriving every 100 msec and offset by 50 msec), then the filter will go unstable during startup and fail to complete checks.
This commit is contained in:
parent
63b42e0632
commit
6c017ffcb5
@ -434,7 +434,7 @@ NavEKF::NavEKF(const AP_AHRS *ahrs, AP_Baro &baro, const RangeFinder &rng) :
|
||||
msecBetaMax(200), // maximum number of msec between synthetic sideslip measurements
|
||||
msecFlowAvg(100), // average number of msec between optical flow measurements
|
||||
dtVelPos(0.2f), // number of seconds between position and velocity corrections. This should be a multiple of the imu update interval.
|
||||
covTimeStepMax(0.07f), // maximum time (sec) between covariance prediction updates
|
||||
covTimeStepMax(0.02f), // maximum time (sec) between covariance prediction updates
|
||||
covDelAngMax(0.05f), // maximum delta angle between covariance prediction updates
|
||||
TASmsecMax(200), // maximum allowed interval between airspeed measurement updates
|
||||
DCM33FlowMin(0.71f), // If Tbn(3,3) is less than this number, optical flow measurements will not be fused as tilt is too high.
|
||||
|
Loading…
Reference in New Issue
Block a user