Browse Source

AP_NavEKF: Fix bug allowing takeoff in GPS modes without aiding

The legacy EKF switches GPs aiding on on arming, whereas the new EKF switches it on based on GPS data quality.
This means the decision to arm and therefore the predicted solution flags must now reflect the actual status of the navigation solution as it will no longer change when motor arming occurs.
master
Paul Riseborough 9 years ago
parent
commit
ab8c28a7cc
  1. 2
      libraries/AP_NavEKF2/AP_NavEKF2_Control.cpp
  2. 4
      libraries/AP_NavEKF2/AP_NavEKF2_Measurements.cpp
  3. 2
      libraries/AP_NavEKF2/AP_NavEKF2_Outputs.cpp
  4. 2
      libraries/AP_NavEKF2/AP_NavEKF2_core.cpp
  5. 4
      libraries/AP_NavEKF2/AP_NavEKF2_core.h

2
libraries/AP_NavEKF2/AP_NavEKF2_Control.cpp

@ -201,7 +201,7 @@ bool NavEKF2_core::optFlowDataPresent(void) const
// return true if the filter to be ready to use gps // return true if the filter to be ready to use gps
bool NavEKF2_core::readyToUseGPS(void) const bool NavEKF2_core::readyToUseGPS(void) const
{ {
return validOrigin && tiltAlignComplete && yawAlignComplete && gpsQualGood; return validOrigin && tiltAlignComplete && yawAlignComplete && gpsGoodToAlign;
} }
// return true if we should use the compass // return true if we should use the compass

4
libraries/AP_NavEKF2/AP_NavEKF2_Measurements.cpp

@ -490,7 +490,7 @@ void NavEKF2_core::readGpsData()
// Monitor quality of the GPS velocity data before and after alignment using separate checks // Monitor quality of the GPS velocity data before and after alignment using separate checks
if (PV_AidingMode != AID_ABSOLUTE) { if (PV_AidingMode != AID_ABSOLUTE) {
// Pre-alignment checks // Pre-alignment checks
gpsQualGood = calcGpsGoodToAlign(); gpsGoodToAlign = calcGpsGoodToAlign();
} else { } else {
// Post-alignment checks // Post-alignment checks
calcGpsGoodForFlight(); calcGpsGoodForFlight();
@ -501,7 +501,7 @@ void NavEKF2_core::readGpsData()
const struct Location &gpsloc = _ahrs->get_gps().location(); const struct Location &gpsloc = _ahrs->get_gps().location();
if (validOrigin) { if (validOrigin) {
gpsDataNew.pos = location_diff(EKF_origin, gpsloc); gpsDataNew.pos = location_diff(EKF_origin, gpsloc);
} else if (gpsQualGood) { } else if (gpsGoodToAlign) {
// Set the NE origin to the current GPS position // Set the NE origin to the current GPS position
setOrigin(); setOrigin();
// Now we know the location we have an estimate for the magnetic field declination and adjust the earth field accordingly // Now we know the location we have an estimate for the magnetic field declination and adjust the earth field accordingly

2
libraries/AP_NavEKF2/AP_NavEKF2_Outputs.cpp

@ -396,7 +396,7 @@ void NavEKF2_core::getFilterStatus(nav_filter_status &status) const
bool someVertRefData = (!velTimeout && useGpsVertVel) || !hgtTimeout; bool someVertRefData = (!velTimeout && useGpsVertVel) || !hgtTimeout;
bool someHorizRefData = !(velTimeout && posTimeout && tasTimeout) || doingFlowNav; bool someHorizRefData = !(velTimeout && posTimeout && tasTimeout) || doingFlowNav;
bool optFlowNavPossible = flowDataValid && (frontend._fusionModeGPS == 3); bool optFlowNavPossible = flowDataValid && (frontend._fusionModeGPS == 3);
bool gpsNavPossible = !gpsNotAvailable && (frontend._fusionModeGPS <= 2); bool gpsNavPossible = !gpsNotAvailable && (PV_AidingMode == AID_ABSOLUTE) && gpsGoodToAlign;
bool filterHealthy = healthy() && tiltAlignComplete && yawAlignComplete; bool filterHealthy = healthy() && tiltAlignComplete && yawAlignComplete;
// set individual flags // set individual flags

2
libraries/AP_NavEKF2/AP_NavEKF2_core.cpp

@ -167,7 +167,7 @@ void NavEKF2_core::InitialiseVariables()
delAngCorrection.zero(); delAngCorrection.zero();
delVelCorrection.zero(); delVelCorrection.zero();
velCorrection.zero(); velCorrection.zero();
gpsQualGood = false; gpsGoodToAlign = false;
gpsNotAvailable = true; gpsNotAvailable = true;
motorsArmed = false; motorsArmed = false;
prevMotorsArmed = false; prevMotorsArmed = false;

4
libraries/AP_NavEKF2/AP_NavEKF2_core.h

@ -753,8 +753,8 @@ private:
Vector3f delVelCorrection; // correction applied to earth frame delta velocities used by output observer to track the EKF Vector3f delVelCorrection; // correction applied to earth frame delta velocities used by output observer to track the EKF
Vector3f velCorrection; // correction applied to velocities used by the output observer to track the EKF Vector3f velCorrection; // correction applied to velocities used by the output observer to track the EKF
float innovYaw; // compass yaw angle innovation (rad) float innovYaw; // compass yaw angle innovation (rad)
uint32_t timeTasReceived_ms; // tie last TAS data was received (msec) uint32_t timeTasReceived_ms; // time last TAS data was received (msec)
bool gpsQualGood; // true when the GPS quality can be used to initialise the navigation system bool gpsGoodToAlign; // true when the GPS quality can be used to initialise the navigation system
uint32_t magYawResetTimer_ms; // timer in msec used to track how long good magnetometer data is failing innovation consistency checks uint32_t magYawResetTimer_ms; // timer in msec used to track how long good magnetometer data is failing innovation consistency checks
bool consistentMagData; // true when the magnetometers are passing consistency checks bool consistentMagData; // true when the magnetometers are passing consistency checks
bool motorsArmed; // true when the motors have been armed bool motorsArmed; // true when the motors have been armed

Loading…
Cancel
Save