diff --git a/libraries/AP_NavEKF/AP_NavEKF.cpp b/libraries/AP_NavEKF/AP_NavEKF.cpp index 48674ef6e8..53803dafed 100644 --- a/libraries/AP_NavEKF/AP_NavEKF.cpp +++ b/libraries/AP_NavEKF/AP_NavEKF.cpp @@ -4014,6 +4014,7 @@ void NavEKF::readGpsData() if (vehicleArmed && _fusionModeGPS != 3) { constPosMode = false; PV_AidingMode = AID_ABSOLUTE; + gpsNotAvailable = false; // Initialise EKF position and velocity states ResetPosition(); ResetVelocity();