Skip to content

Commit

Permalink
AP_AHRS: return EAS from get_unconstrained_airspeed_EAS
Browse files Browse the repository at this point in the history
Co-authored-by: luweiagi <[email protected]>
  • Loading branch information
peterbarker and luweiagi committed Dec 17, 2024
1 parent 98c2cfd commit 7e97eba
Showing 1 changed file with 2 additions and 2 deletions.
4 changes: 2 additions & 2 deletions libraries/AP_AHRS/AP_AHRS_DCM.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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;
}

Expand Down

0 comments on commit 7e97eba

Please sign in to comment.