mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 09:58:28 -04:00
AP_NavEKF: Extend definition of GPS availability to include user inhibit
This commit is contained in:
parent
d0d49065e7
commit
8bc8d1444a
@ -3946,8 +3946,8 @@ void NavEKF::readGpsData()
|
||||
// calculate a position offset which is applied to NE position and velocity wherever it is used throughout code to allow GPS position jumps to be accommodated gradually
|
||||
decayGpsOffset();
|
||||
}
|
||||
// If too long since last fix time, we declare no GPS present
|
||||
if (imuSampleTime_ms - lastFixTime_ms < 1000) {
|
||||
// If too long since last fix time or we are not allowed to use GPS, we declare no GPS available for use
|
||||
if ((imuSampleTime_ms - lastFixTime_ms < 1000) || _fusionModeGPS == 3) {
|
||||
gpsNotAvailable = false;
|
||||
} else {
|
||||
gpsNotAvailable = true;
|
||||
|
Loading…
Reference in New Issue
Block a user