Browse Source

AP_AHRS: constrain airspeed sensor airspeed using WIND_MAX

fixes regression from d1d790019c
c415-sdk
Peter Barker 4 years ago committed by Randy Mackay
parent
commit
52d58f0670
  1. 12
      libraries/AP_AHRS/AP_AHRS_NavEKF.cpp

12
libraries/AP_AHRS/AP_AHRS_NavEKF.cpp

@ -623,6 +623,18 @@ bool AP_AHRS_NavEKF::airspeed_estimate(float &airspeed_ret) const @@ -623,6 +623,18 @@ bool AP_AHRS_NavEKF::airspeed_estimate(float &airspeed_ret) const
bool ret = false;
if (airspeed_sensor_enabled()) {
airspeed_ret = AP::airspeed()->get_airspeed();
if (_wind_max > 0 && AP::gps().status() >= AP_GPS::GPS_OK_FIX_2D) {
// constrain the airspeed by the ground speed
// and AHRS_WIND_MAX
const float gnd_speed = AP::gps().ground_speed();
float true_airspeed = airspeed_ret * get_EAS2TAS();
true_airspeed = constrain_float(true_airspeed,
gnd_speed - _wind_max,
gnd_speed + _wind_max);
airspeed_ret = true_airspeed / get_EAS2TAS();
}
return true;
}

Loading…
Cancel
Save