mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-28 19:48:31 -04:00
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:
parent
fcc07b5560
commit
e2b8807260
@ -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
|
||||
|
@ -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…
Reference in New Issue
Block a user