Plane: disable crash detection if no GPS and no airspeed

This commit is contained in:
Andrew Tridgell 2018-09-06 08:43:41 +10:00
parent b660022b20
commit 987b556299

View File

@ -278,6 +278,12 @@ void Plane::crash_detection_update(void)
crash_state.checkedHardLanding = false; crash_state.checkedHardLanding = false;
} }
// if we have no GPS lock and we don't have a functional airspeed
// sensor then don't do crash detection
if (gps.status() < AP_GPS::GPS_OK_FIX_3D && (!airspeed.use() || !airspeed.healthy())) {
crashed = false;
}
if (!crashed) { if (!crashed) {
// reset timer // reset timer
crash_state.debounce_timer_ms = 0; crash_state.debounce_timer_ms = 0;