mirror of https://github.com/ArduPilot/ardupilot
AP_NavEKF3: reset inhibitMagStates on in-flight yaw reset
this is needed to prevent the next ConstrainVariances() from zeroing the variances, which leads to very slow learning of mag states
This commit is contained in:
parent
71ad90819e
commit
fae2e44eac
|
@ -127,6 +127,9 @@ void NavEKF3_core::controlMagYawReset()
|
||||||
gcs().send_text(MAV_SEVERITY_WARNING, "EKF3 IMU%u ground mag anomaly, yaw re-aligned",(unsigned)imu_index);
|
gcs().send_text(MAV_SEVERITY_WARNING, "EKF3 IMU%u ground mag anomaly, yaw re-aligned",(unsigned)imu_index);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// prevent reset of variances in ConstrainVariances()
|
||||||
|
inhibitMagStates = false;
|
||||||
|
|
||||||
// update the yaw reset completed status
|
// update the yaw reset completed status
|
||||||
recordYawReset();
|
recordYawReset();
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue