mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 09:58:28 -04:00
AP_NavEKF: Always explicitly set required const pos or vel mode when arming
This additional explicit setting of the constPosMode and constVelMode reduces the likelihood of logic errors being introduced in the future as it places the intended setting of these parameters at arming in the one place. the constVelmode and constPosMode only have one set of conditions each that can trigger these modes in flight, so if these modes are true after arming it will be clear that it was the in-flight condition that triggered.
This commit is contained in:
parent
9c6dabe1cc
commit
073b8e7c43
@ -4579,19 +4579,26 @@ void NavEKF::performArmingChecks()
|
|||||||
PV_AidingMode = AID_RELATIVE; // we have optical flow data and can estimate all vehicle states
|
PV_AidingMode = AID_RELATIVE; // we have optical flow data and can estimate all vehicle states
|
||||||
posTimeout = true;
|
posTimeout = true;
|
||||||
velTimeout = true;
|
velTimeout = true;
|
||||||
|
constPosMode = false;
|
||||||
|
constVelMode = false;
|
||||||
} else {
|
} else {
|
||||||
PV_AidingMode = AID_NONE; // we don't have optical flow data and will only be able to estimate orientation and height
|
PV_AidingMode = AID_NONE; // we don't have optical flow data and will only be able to estimate orientation and height
|
||||||
posTimeout = true;
|
posTimeout = true;
|
||||||
velTimeout = true;
|
velTimeout = true;
|
||||||
|
constPosMode = true;
|
||||||
|
constVelMode = false; // always clear constant velocity mode if constant position mode is active
|
||||||
}
|
}
|
||||||
} else { // arming when GPS useage is allowed
|
} else { // arming when GPS useage is allowed
|
||||||
if (gpsNotAvailable) {
|
if (gpsNotAvailable) {
|
||||||
PV_AidingMode = AID_NONE; // we don't have have GPS data and will only be able to estimate orientation and height
|
PV_AidingMode = AID_NONE; // we don't have have GPS data and will only be able to estimate orientation and height
|
||||||
posTimeout = true;
|
posTimeout = true;
|
||||||
velTimeout = true;
|
velTimeout = true;
|
||||||
|
constPosMode = true;
|
||||||
|
constVelMode = false; // always clear constant velocity mode if constant position mode is active
|
||||||
} else {
|
} else {
|
||||||
PV_AidingMode = AID_ABSOLUTE; // we have GPS data and can estimate all vehicle states
|
PV_AidingMode = AID_ABSOLUTE; // we have GPS data and can estimate all vehicle states
|
||||||
constPosMode = false;
|
constPosMode = false;
|
||||||
|
constVelMode = false;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
// Reset filter positon, height and velocity states on arming or disarming
|
// Reset filter positon, height and velocity states on arming or disarming
|
||||||
|
Loading…
Reference in New Issue
Block a user