mirror of https://github.com/ArduPilot/ardupilot
AP_NavEKF3: Fix bug preventing learning of XY IMU dvel bias in flight
This commit is contained in:
parent
aa13e86ac9
commit
827d871c85
|
@ -1143,7 +1143,7 @@ void NavEKF3_core::CovariancePrediction(Vector3F *rotVarVecPtr)
|
|||
const uint8_t index = stateIndex - 13;
|
||||
|
||||
// Don't attempt learning of IMU delta velocty bias if on ground and not aligned with the gravity vector
|
||||
const bool is_bias_observable = (fabsF(prevTnb[index][2]) > 0.8f) && onGround;
|
||||
const bool is_bias_observable = (fabsF(prevTnb[index][2]) > 0.8f) || !onGround;
|
||||
|
||||
if (!is_bias_observable && !dvelBiasAxisInhibit[index]) {
|
||||
// store variances to be reinstated wben learning can commence later
|
||||
|
|
Loading…
Reference in New Issue