AP_NavEKF3: correct flag in case of GPS disable

This commit is contained in:
Pierre Kancir 2018-02-12 12:47:44 +01:00 committed by Randy Mackay
parent b9e32d1f44
commit 4d2f2a2aad

View File

@ -561,7 +561,7 @@ void NavEKF3_core::updateFilterStatus(void)
filterStatus.flags.takeoff = expectGndEffectTakeoff; // The EKF has been told to expect takeoff and is in a ground effect mitigation mode
filterStatus.flags.touchdown = expectGndEffectTouchdown; // The EKF has been told to detect touchdown and is in a ground effect mitigation mode
filterStatus.flags.using_gps = ((imuSampleTime_ms - lastPosPassTime_ms) < 4000) && (PV_AidingMode == AID_ABSOLUTE);
filterStatus.flags.gps_glitching = !gpsAccuracyGood && (PV_AidingMode == AID_ABSOLUTE); // GPS glitching is affecting navigation accuracy
filterStatus.flags.gps_glitching = !gpsAccuracyGood && (PV_AidingMode == AID_ABSOLUTE) && (frontend->_fusionModeGPS != 3); // GPS glitching is affecting navigation accuracy
}
#endif // HAL_CPU_CLASS