AP_NavEKF3: fill in gps_quality_good flag

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

View File

@ -562,6 +562,7 @@ void NavEKF3_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) && (frontend->_fusionModeGPS != 3); // GPS glitching is affecting navigation accuracy
filterStatus.flags.gps_quality_good = gpsGoodToAlign;
}
#endif // HAL_CPU_CLASS