Browse Source

AP_NavEKF2: Fix bug causing switching in and out of aiding

If the GPS receiver was disconnected and no data received, then then the gpsGoodToAlign check did not get a chance to run and becasue it was previously true the EKF would switch back into aiding.
This prevents this by ensuring that gpsGoodToAlign defaults to false when the check is not being performed.
An additional check has also been dded to ensure that there is GPS data to fuse before we declare ready to use GPS.
mission-4.1.18
priseborough 9 years ago committed by Andrew Tridgell
parent
commit
e2b8807260
  1. 2
      libraries/AP_NavEKF2/AP_NavEKF2_Control.cpp
  2. 2
      libraries/AP_NavEKF2/AP_NavEKF2_Measurements.cpp

2
libraries/AP_NavEKF2/AP_NavEKF2_Control.cpp

@ -313,7 +313,7 @@ bool NavEKF2_core::optFlowDataPresent(void) const @@ -313,7 +313,7 @@ bool NavEKF2_core::optFlowDataPresent(void) const
// return true if the filter to be ready to use gps
bool NavEKF2_core::readyToUseGPS(void) const
{
return validOrigin && tiltAlignComplete && yawAlignComplete && gpsGoodToAlign && (frontend->_fusionModeGPS != 3);
return validOrigin && tiltAlignComplete && yawAlignComplete && gpsGoodToAlign && (frontend->_fusionModeGPS != 3) && gpsDataToFuse;
}
// return true if we should use the compass

2
libraries/AP_NavEKF2/AP_NavEKF2_Measurements.cpp

@ -417,6 +417,8 @@ void NavEKF2_core::readGpsData() @@ -417,6 +417,8 @@ void NavEKF2_core::readGpsData()
if (PV_AidingMode != AID_ABSOLUTE) {
// Pre-alignment checks
gpsGoodToAlign = calcGpsGoodToAlign();
} else {
gpsGoodToAlign = false;
}
// Post-alignment checks

Loading…
Cancel
Save