diff --git a/libraries/AP_Baro/AP_Baro.cpp b/libraries/AP_Baro/AP_Baro.cpp index 13c5994290..007873f40e 100644 --- a/libraries/AP_Baro/AP_Baro.cpp +++ b/libraries/AP_Baro/AP_Baro.cpp @@ -183,6 +183,10 @@ AP_Baro::AP_Baro() // the altitude() or climb_rate() interfaces can be used void AP_Baro::calibrate(bool save) { + if (hal.util->was_watchdog_reset()) { + gcs().send_text(MAV_SEVERITY_INFO, "Baro: skipping calibration"); + return; + } gcs().send_text(MAV_SEVERITY_INFO, "Calibrating barometer"); // reset the altitude offset when we calibrate. The altitude