AP_AHRS: return EAS from get_unconstrained_airspeed_EAS

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

View File

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