diff --git a/libraries/AP_Airspeed/AP_Airspeed.cpp b/libraries/AP_Airspeed/AP_Airspeed.cpp index 9a08d5f8d6..f972d0861a 100644 --- a/libraries/AP_Airspeed/AP_Airspeed.cpp +++ b/libraries/AP_Airspeed/AP_Airspeed.cpp @@ -319,6 +319,10 @@ bool AP_Airspeed::get_temperature(uint8_t i, float &temperature) // least once before the get_airspeed() interface can be used void AP_Airspeed::calibrate(bool in_startup) { + if (hal.util->was_watchdog_reset()) { + gcs().send_text(MAV_SEVERITY_INFO,"Airspeed: skipping cal"); + return; + } for (uint8_t i=0; i