From 7ced9b0d32278cc2947d439c7d95ce95f4676137 Mon Sep 17 00:00:00 2001 From: Iampete1 Date: Tue, 1 Mar 2022 17:44:43 +0000 Subject: [PATCH] AP_Airspeed: rename get_health_failure_probability to get_health_probability --- libraries/AP_Airspeed/AP_Airspeed.cpp | 2 +- libraries/AP_Airspeed/AP_Airspeed.h | 8 ++++---- 2 files changed, 5 insertions(+), 5 deletions(-) diff --git a/libraries/AP_Airspeed/AP_Airspeed.cpp b/libraries/AP_Airspeed/AP_Airspeed.cpp index 11a5c1528a..12a03c4720 100644 --- a/libraries/AP_Airspeed/AP_Airspeed.cpp +++ b/libraries/AP_Airspeed/AP_Airspeed.cpp @@ -689,7 +689,7 @@ void AP_Airspeed::Log_Airspeed() offset : get_offset(i), use : use(i), healthy : healthy(i), - health_prob : get_health_failure_probability(i), + health_prob : get_health_probability(i), primary : get_primary() }; AP::logger().WriteBlock(&pkt, sizeof(pkt)); diff --git a/libraries/AP_Airspeed/AP_Airspeed.h b/libraries/AP_Airspeed/AP_Airspeed.h index a4790d484b..6bdd86f65c 100644 --- a/libraries/AP_Airspeed/AP_Airspeed.h +++ b/libraries/AP_Airspeed/AP_Airspeed.h @@ -266,12 +266,12 @@ private: // returns 0 if the sensor is not enabled float get_pressure(uint8_t i); - // get the failure health probability - float get_health_failure_probability(uint8_t i) const { + // get the health probability + float get_health_probability(uint8_t i) const { return state[i].failures.health_probability; } - float get_health_failure_probability(void) const { - return get_health_failure_probability(primary); + float get_health_probability(void) const { + return get_health_probability(primary); } void update_calibration(uint8_t i, float raw_pressure);