From 0f6f684baba6bbde225999132987336bfb759873 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Mon, 16 Mar 2020 16:09:10 +1100 Subject: [PATCH] AP_Airspeed: expose get_corrected_pressure() needed for AP_Periph --- libraries/AP_Airspeed/AP_Airspeed.h | 16 +++++++++------- 1 file changed, 9 insertions(+), 7 deletions(-) diff --git a/libraries/AP_Airspeed/AP_Airspeed.h b/libraries/AP_Airspeed/AP_Airspeed.h index b3638273be..d4b4335b5d 100644 --- a/libraries/AP_Airspeed/AP_Airspeed.h +++ b/libraries/AP_Airspeed/AP_Airspeed.h @@ -159,6 +159,14 @@ public: uint8_t get_primary(void) const { return primary; } static AP_Airspeed *get_singleton() { return _singleton; } + + // return the current corrected pressure, public for AP_Periph + float get_corrected_pressure(uint8_t i) const { + return state[i].corrected_pressure; + } + float get_corrected_pressure(void) const { + return get_corrected_pressure(primary); + } private: static AP_Airspeed *_singleton; @@ -220,13 +228,7 @@ private: // return the differential pressure in Pascal for the last airspeed reading for the requested instance // returns 0 if the sensor is not enabled float get_pressure(uint8_t i); - // return the current corrected pressure - float get_corrected_pressure(uint8_t i) const { - return state[i].corrected_pressure; - } - float get_corrected_pressure(void) const { - return get_corrected_pressure(primary); - } + // get the failure health probability float get_health_failure_probability(uint8_t i) const { return state[i].failures.health_probability;