mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 09:28:31 -04:00
AP_NavEKF2: Don't return ready to use GPS true if user has inhibited GPS
This commit is contained in:
parent
d6f7156f4e
commit
f99dbc70f9
@ -205,7 +205,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;
|
||||
return validOrigin && tiltAlignComplete && yawAlignComplete && gpsGoodToAlign && (frontend->_fusionModeGPS != 3);
|
||||
}
|
||||
|
||||
// return true if we should use the compass
|
||||
|
Loading…
Reference in New Issue
Block a user