AP_NavEKF2: fill in gps_quality_good flag

This commit is contained in:
Andrew Tridgell 2018-07-14 10:10:10 +10:00
parent 103d1aea41
commit 3d31773fb4

View File

@ -521,6 +521,7 @@ void NavEKF2_core::updateFilterStatus(void)
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) && !extNavUsedForPos; // GPS glitching is affecting navigation accuracy
filterStatus.flags.gps_quality_good = gpsGoodToAlign;
}
#endif // HAL_CPU_CLASS