mirror of https://github.com/ArduPilot/ardupilot
AP_AHRS: return EAS from get_unconstrained_airspeed_EAS
Co-authored-by: luweiagi <luweiagi@163.com>
This commit is contained in:
parent
46b9f06011
commit
f5d81abb42
|
@ -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;
|
||||
}
|
||||
|
||||
|
|
Loading…
Reference in New Issue