mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 00:28:30 -04:00
AP_NavEKF3: Raise lower limit on del vel bias state variances
This is required to prevent co-variance matrix errors due to long periods without movement causing height divergence.
This commit is contained in:
parent
628d140319
commit
bf963f8b65
@ -1416,7 +1416,7 @@ void NavEKF3_core::ConstrainVariances()
|
||||
}
|
||||
|
||||
if (!inhibitDelVelBiasStates) {
|
||||
for (uint8_t i=13; i<=15; i++) P[i][i] = constrain_float(P[i][i],0.0f,sq(10.0f * dtEkfAvg));
|
||||
for (uint8_t i=13; i<=15; i++) P[i][i] = constrain_float(P[i][i],1e-9f,sq(10.0f * dtEkfAvg));
|
||||
} else {
|
||||
zeroCols(P,13,15);
|
||||
zeroRows(P,13,15);
|
||||
|
Loading…
Reference in New Issue
Block a user