AP_NavEKF2: Fix misleading pre-flight status reporting

This commit is contained in:
Paul Riseborough 2016-05-21 12:32:05 +10:00 committed by Andrew Tridgell
parent 38d61f5281
commit 16cb7078cd

View File

@ -478,8 +478,8 @@ void NavEKF2_core::getFilterStatus(nav_filter_status &status) const
status.flags.takeoff_detected = takeOffDetected; // takeoff for optical flow navigation has been detected
status.flags.takeoff = expectGndEffectTakeoff; // The EKF has been told to expect takeoff and is in a ground effect mitigation mode
status.flags.touchdown = expectGndEffectTouchdown; // The EKF has been told to detect touchdown and is in a ground effect mitigation mode
status.flags.using_gps = (imuSampleTime_ms - lastPosPassTime_ms) < 4000;
status.flags.gps_glitching = !gpsAccuracyGood; // The GPS is glitching
status.flags.using_gps = ((imuSampleTime_ms - lastPosPassTime_ms) < 4000) && (PV_AidingMode == AID_ABSOLUTE);
status.flags.gps_glitching = !gpsAccuracyGood && (PV_AidingMode == AID_ABSOLUTE); // The GPS is glitching
}
/*