diff --git a/libraries/AP_Airspeed/AP_Airspeed.h b/libraries/AP_Airspeed/AP_Airspeed.h index b1a0c74980..3fa4758614 100644 --- a/libraries/AP_Airspeed/AP_Airspeed.h +++ b/libraries/AP_Airspeed/AP_Airspeed.h @@ -125,6 +125,12 @@ public: } float get_EAS2TAS(void) const { return get_EAS2TAS(primary); } + // get the failure health probability + float get_health_failure_probability(uint8_t i) const { + return state[i].failures.health_probability; + } + float get_health_failure_probability(void) const { return get_health_failure_probability(primary); } + // update airspeed ratio calibration void update_calibration(const Vector3f &vground, int16_t max_airspeed_allowed_during_cal); diff --git a/libraries/AP_Airspeed/AP_Airspeed_Health.cpp b/libraries/AP_Airspeed/AP_Airspeed_Health.cpp index 456b175511..4ca461f988 100644 --- a/libraries/AP_Airspeed/AP_Airspeed_Health.cpp +++ b/libraries/AP_Airspeed/AP_Airspeed_Health.cpp @@ -6,9 +6,7 @@ void AP_Airspeed::check_sensor_failures() { for (uint8_t i=0; i