From b161bdd6a9df666bf4e1d52838de23b658e137a8 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sun, 5 May 2024 06:52:53 +1000 Subject: [PATCH] AP_AHRS: prevent use of uninitialised EAS2TAS --- libraries/AP_AHRS/AP_AHRS.cpp | 11 +++++++++++ libraries/AP_AHRS/AP_AHRS.h | 4 +--- 2 files changed, 12 insertions(+), 3 deletions(-) diff --git a/libraries/AP_AHRS/AP_AHRS.cpp b/libraries/AP_AHRS/AP_AHRS.cpp index 69c14fc8cc..dfbf93e1b0 100644 --- a/libraries/AP_AHRS/AP_AHRS.cpp +++ b/libraries/AP_AHRS/AP_AHRS.cpp @@ -3559,6 +3559,17 @@ bool AP_AHRS::get_location_from_home_offset(Location &loc, const Vector3p &offse return true; } +/* + get EAS to TAS scaling + */ +float AP_AHRS::get_EAS2TAS(void) const +{ + if (is_positive(state.EAS2TAS)) { + return state.EAS2TAS; + } + return 1.0; +} + // singleton instance AP_AHRS *AP_AHRS::_singleton; diff --git a/libraries/AP_AHRS/AP_AHRS.h b/libraries/AP_AHRS/AP_AHRS.h index 3113003551..3376424cfc 100644 --- a/libraries/AP_AHRS/AP_AHRS.h +++ b/libraries/AP_AHRS/AP_AHRS.h @@ -141,9 +141,7 @@ public: */ // get apparent to true airspeed ratio - float get_EAS2TAS(void) const { - return state.EAS2TAS; - } + float get_EAS2TAS(void) const; // return an airspeed estimate if available. return true // if we have an estimate