From 46b9f0601166952fa702ae2bda27196a42b7b89d Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Mon, 25 Nov 2024 11:01:25 +1100 Subject: [PATCH] AP_AHRS: use TAS in DCM drift correction code Co-authored-by: luweiagi --- libraries/AP_AHRS/AP_AHRS_DCM.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_AHRS/AP_AHRS_DCM.cpp b/libraries/AP_AHRS/AP_AHRS_DCM.cpp index a64821c145..23baa244ca 100644 --- a/libraries/AP_AHRS/AP_AHRS_DCM.cpp +++ b/libraries/AP_AHRS/AP_AHRS_DCM.cpp @@ -727,7 +727,7 @@ AP_AHRS_DCM::drift_correction(float deltat) float airspeed_TAS = _last_airspeed_TAS; #if AP_AIRSPEED_ENABLED if (airspeed_sensor_enabled()) { - airspeed_TAS = AP::airspeed()->get_airspeed(); + airspeed_TAS = AP::airspeed()->get_airspeed() * get_EAS2TAS(); } #endif