mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-04 23:18:29 -04:00
Plane: disable crash detection if no GPS and no airspeed
This commit is contained in:
parent
b660022b20
commit
987b556299
@ -278,6 +278,12 @@ void Plane::crash_detection_update(void)
|
||||
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) {
|
||||
// reset timer
|
||||
crash_state.debounce_timer_ms = 0;
|
||||
|
Loading…
Reference in New Issue
Block a user