AP_NavEKF: Continually turn off aiding whilst the vehicle is disarmed

This prevents the possibility of any logic errors turning aiding back on.

AP_NavEKF: Fix bug in logic
This commit is contained in:
priseborough 2015-01-09 23:34:34 +11:00 committed by Randy Mackay
parent 81ee339e25
commit 8aeec82846
1 changed files with 2 additions and 6 deletions

View File

@ -4587,6 +4587,7 @@ void NavEKF::performArmingChecks()
velTimeout = true;
} else {
PV_AidingMode = AID_ABSOLUTE; // we have GPS data and can estimate all vehicle states
constPosMode = false;
}
}
// Reset filter positon, height and velocity states on arming or disarming
@ -4604,15 +4605,10 @@ void NavEKF::performArmingChecks()
// 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) {
// set constant position mode if aiding is inhibited
constPosMode = true;
constVelMode = false; // always clear constant velocity mode if constant position mode is active
lastConstVelMode = false;
} else {
constPosMode = false;
}
}