From 6ed8b2aad90aff79eade5f7375ceb8f6f50d0fa4 Mon Sep 17 00:00:00 2001 From: Jaaaky <43599380+Jaaaky@users.noreply.github.com> Date: Thu, 2 May 2019 11:56:41 +0300 Subject: [PATCH] AP_Baro: Fix not healthy by watchdog reset --- libraries/AP_Baro/AP_Baro.cpp | 12 ++++++------ 1 file changed, 6 insertions(+), 6 deletions(-) diff --git a/libraries/AP_Baro/AP_Baro.cpp b/libraries/AP_Baro/AP_Baro.cpp index 007873f40e..9bde67d04c 100644 --- a/libraries/AP_Baro/AP_Baro.cpp +++ b/libraries/AP_Baro/AP_Baro.cpp @@ -183,6 +183,12 @@ AP_Baro::AP_Baro() // the altitude() or climb_rate() interfaces can be used void AP_Baro::calibrate(bool save) { + // start by assuming all sensors are calibrated (for healthy() test) + for (uint8_t i=0; i<_num_sensors; i++) { + sensors[i].calibrated = true; + sensors[i].alt_ok = true; + } + if (hal.util->was_watchdog_reset()) { gcs().send_text(MAV_SEVERITY_INFO, "Baro: skipping calibration"); return; @@ -193,12 +199,6 @@ void AP_Baro::calibrate(bool save) // offset is supposed to be for within a flight _alt_offset.set_and_save(0); - // start by assuming all sensors are calibrated (for healthy() test) - for (uint8_t i=0; i<_num_sensors; i++) { - sensors[i].calibrated = true; - sensors[i].alt_ok = true; - } - // let the barometer settle for a full second after startup // the MS5611 reads quite a long way off for the first second, // leading to about 1m of error if we don't wait