mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-05 15:38:29 -04:00
AP_NavEKF : Clear compass fail on transition between armed and disarmed
This allows a compass that has been declared failed, possibly because of external disturbances (eg movement of hatches, proximity of tools, etc) to be given a second chance when the vehicle is armed.
This commit is contained in:
parent
e34b0847d7
commit
0f62dbf6ed
@ -608,6 +608,9 @@ void NavEKF::UpdateFilter()
|
|||||||
ResetPosition();
|
ResetPosition();
|
||||||
ResetHeight();
|
ResetHeight();
|
||||||
StoreStatesReset();
|
StoreStatesReset();
|
||||||
|
// clear the magnetometer failed status as the failure may have been
|
||||||
|
// caused by external field disturbances associated with pre-flight activities
|
||||||
|
magFailed = false;
|
||||||
calcQuatAndFieldStates(_ahrs->roll, _ahrs->pitch);
|
calcQuatAndFieldStates(_ahrs->roll, _ahrs->pitch);
|
||||||
prevStaticMode = staticMode;
|
prevStaticMode = staticMode;
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user