mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-23 09:08:30 -04:00
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:
parent
fb1962b111
commit
ae6b85e63d
@ -4601,7 +4601,12 @@ void NavEKF::performArmingChecks()
|
||||
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) {
|
||||
constPosMode = true;
|
||||
constVelMode = false; // always clear constant velocity mode if constant position mode is active
|
||||
|
Loading…
Reference in New Issue
Block a user