From 1de68b78dc9ef6373bedb93e8a5c3595a8cb6ef2 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Sun, 18 Mar 2018 15:13:37 +1100 Subject: [PATCH] AP_Barometer: tidy handling of barometer calibrations --- 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 370f28bbcb..5f25d98a80 100644 --- a/libraries/AP_Baro/AP_Baro.cpp +++ b/libraries/AP_Baro/AP_Baro.cpp @@ -21,6 +21,7 @@ #include +#include #include #include #include @@ -156,6 +157,8 @@ AP_Baro::AP_Baro() // the altitude() or climb_rate() interfaces can be used void AP_Baro::calibrate(bool save) { + gcs().send_text(MAV_SEVERITY_INFO, "Calibrating barometer"); + // reset the altitude offset when we calibrate. The altitude // offset is supposed to be for within a flight _alt_offset.set_and_save(0); @@ -222,6 +225,7 @@ void AP_Baro::calibrate(bool save) // panic if all sensors are not calibrated for (uint8_t i=0; i<_num_sensors; i++) { if (sensors[i].calibrated) { + gcs().send_text(MAV_SEVERITY_INFO, "Barometer calibration complete"); return; } }