AP_AHRS: use TAS in DCM drift correction code

Co-authored-by: luweiagi <luweiagi@163.com>
This commit is contained in:
Peter Barker 2024-11-25 11:01:25 +11:00 committed by Andrew Tridgell
parent 92241daef1
commit 46b9f06011
1 changed files with 1 additions and 1 deletions

View File

@ -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