mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-02 22:18:29 -04:00
AP_NavEKF: Ensure filter doesn't try to use GPS after initialisation
This commit is contained in:
parent
bab1a69f1c
commit
40b02fc19a
@ -716,7 +716,7 @@ void NavEKF::UpdateFilter()
|
|||||||
heldVelNE.zero();
|
heldVelNE.zero();
|
||||||
// set various useage modes based on the condition at arming. These are then held until the vehicle is disarmed.
|
// set various useage modes based on the condition at arming. These are then held until the vehicle is disarmed.
|
||||||
if (!vehicleArmed) {
|
if (!vehicleArmed) {
|
||||||
gpsInhibitMode = 0; // When dis-arming, clear any GPS mode inhibits
|
gpsInhibitMode = 1; // When dis-armed, we only estimate orientation & height
|
||||||
} else if (_fusionModeGPS == 3) { // arming when GPS useage has been prohibited
|
} else if (_fusionModeGPS == 3) { // arming when GPS useage has been prohibited
|
||||||
if (optFlowDataPresent()) {
|
if (optFlowDataPresent()) {
|
||||||
gpsInhibitMode = 2; // we have optical flow data and can estimate all vehicle states
|
gpsInhibitMode = 2; // we have optical flow data and can estimate all vehicle states
|
||||||
@ -4421,10 +4421,11 @@ void NavEKF::ZeroVariables()
|
|||||||
flowGyroBias.y = 0;
|
flowGyroBias.y = 0;
|
||||||
velHoldMode = false;
|
velHoldMode = false;
|
||||||
heldVelNE.zero();
|
heldVelNE.zero();
|
||||||
gpsInhibitMode = 0;
|
gpsInhibitMode = 1;
|
||||||
gpsVelGlitchOffset.zero();
|
gpsVelGlitchOffset.zero();
|
||||||
vehicleArmed = false;
|
vehicleArmed = false;
|
||||||
prevVehicleArmed = false;
|
prevVehicleArmed = false;
|
||||||
|
posHoldMode = true;
|
||||||
}
|
}
|
||||||
|
|
||||||
// return true if we should use the airspeed sensor
|
// return true if we should use the airspeed sensor
|
||||||
|
Loading…
Reference in New Issue
Block a user