From 3cb134b67ca2adcca75950172ab2e29386cad54b Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Thu, 11 Apr 2019 19:57:28 +1000 Subject: [PATCH] AP_Baro: skip cal on watchdog reset --- libraries/AP_Baro/AP_Baro.cpp | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/libraries/AP_Baro/AP_Baro.cpp b/libraries/AP_Baro/AP_Baro.cpp index a7b8dfec38..23752b129d 100644 --- a/libraries/AP_Baro/AP_Baro.cpp +++ b/libraries/AP_Baro/AP_Baro.cpp @@ -163,6 +163,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