From f5d81abb424c3a59aa59ba1fd7595f969468ac56 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Mon, 25 Nov 2024 11:05:09 +1100 Subject: [PATCH] AP_AHRS: return EAS from get_unconstrained_airspeed_EAS Co-authored-by: luweiagi --- libraries/AP_AHRS/AP_AHRS_DCM.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/AP_AHRS/AP_AHRS_DCM.cpp b/libraries/AP_AHRS/AP_AHRS_DCM.cpp index 23baa244ca..a9179502d3 100644 --- a/libraries/AP_AHRS/AP_AHRS_DCM.cpp +++ b/libraries/AP_AHRS/AP_AHRS_DCM.cpp @@ -1143,13 +1143,13 @@ bool AP_AHRS_DCM::get_unconstrained_airspeed_EAS(uint8_t airspeed_index, float & if (AP::ahrs().get_wind_estimation_enabled() && have_gps()) { // estimated via GPS speed and wind - airspeed_ret = _last_airspeed_TAS; + airspeed_ret = _last_airspeed_TAS * get_TAS2EAS(); return true; } // Else give the last estimate, but return false. // This is used by the dead-reckoning code - airspeed_ret = _last_airspeed_TAS; + airspeed_ret = _last_airspeed_TAS * get_TAS2EAS(); return false; }