AP_NavEKF: Explicitly set aiding to off when disarmed

This fixes a bug that could cause the AHRS to drift whilst the vehicle was disarmed depending sensor combinations at startup.
This commit is contained in:
priseborough 2015-01-09 21:13:04 +11:00 committed by Randy Mackay
parent fb1962b111
commit ae6b85e63d

View File

@ -4601,7 +4601,12 @@ void NavEKF::performArmingChecks()
finalMagYawInit = true; finalMagYawInit = true;
} }
// set constant position mode if gps is inhibited and we are not trying to use optical flow data // Always turn aiding off when the vehicle is disarmed
if (!vehicleArmed) {
PV_AidingMode = AID_NONE;
}
// set constant position mode if aiding is inhibited
if (PV_AidingMode == AID_NONE) { if (PV_AidingMode == AID_NONE) {
constPosMode = true; constPosMode = true;
constVelMode = false; // always clear constant velocity mode if constant position mode is active constVelMode = false; // always clear constant velocity mode if constant position mode is active