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.
This commit is contained in:
priseborough 2016-07-17 14:27:37 +10:00 committed by Andrew Tridgell
parent fcc07b5560
commit e2b8807260
2 changed files with 3 additions and 1 deletions

View File

@ -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

View File

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