From d7ec1e7b0cc23451f73d59db0159cbaea374beb0 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Thu, 8 Dec 2022 17:47:13 +1100 Subject: [PATCH] AP_Airspeed: add support for mavlink in-progress message --- libraries/AP_Airspeed/AP_Airspeed.cpp | 20 ++++++++++++++++++++ libraries/AP_Airspeed/AP_Airspeed.h | 13 ++++++++++++- 2 files changed, 32 insertions(+), 1 deletion(-) diff --git a/libraries/AP_Airspeed/AP_Airspeed.cpp b/libraries/AP_Airspeed/AP_Airspeed.cpp index 9ab842cf46..3460ecc8c6 100644 --- a/libraries/AP_Airspeed/AP_Airspeed.cpp +++ b/libraries/AP_Airspeed/AP_Airspeed.cpp @@ -523,6 +523,7 @@ void AP_Airspeed::calibrate(bool in_startup) state[i].cal.count = 0; state[i].cal.sum = 0; state[i].cal.read_count = 0; + calibration_state[i] = CalibrationState::IN_PROGRESS; GCS_SEND_TEXT(MAV_SEVERITY_INFO,"Airspeed %u calibration started", i+1); } #endif // HAL_BUILD_AP_PERIPH @@ -544,6 +545,7 @@ void AP_Airspeed::update_calibration(uint8_t i, float raw_pressure) state[i].cal.read_count > 15) { if (state[i].cal.count == 0) { GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "Airspeed %u unhealthy", i + 1); + calibration_state[i] = CalibrationState::FAILED; } else { GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Airspeed %u calibrated", i + 1); float calibrated_offset = state[i].cal.sum / state[i].cal.count; @@ -557,6 +559,7 @@ void AP_Airspeed::update_calibration(uint8_t i, float raw_pressure) } } param[i].offset.set_and_save(calibrated_offset); + calibration_state[i] = CalibrationState::SUCCESS; } state[i].cal.start_ms = 0; return; @@ -570,6 +573,23 @@ void AP_Airspeed::update_calibration(uint8_t i, float raw_pressure) #endif // HAL_BUILD_AP_PERIPH } +// get aggregate calibration state for the Airspeed library: +AP_Airspeed::CalibrationState AP_Airspeed::get_calibration_state() const +{ + for (uint8_t i=0; i