AP_NavEKF3: Clarify definition for gps_glitching flag

This commit is contained in:
priseborough 2018-03-26 20:17:45 +11:00 committed by Randy Mackay
parent d600a96809
commit 5785523a0d
1 changed files with 1 additions and 1 deletions

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); // The GPS is glitching
filterStatus.flags.gps_glitching = !gpsAccuracyGood && (PV_AidingMode == AID_ABSOLUTE); // GPS glitching is affecting navigation accuracy
}
#endif // HAL_CPU_CLASS