mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-07 00:13:59 -04:00
AP_AHRS: return perfect airspeed estimate for EKF-type 10
... rather than the EKF3 estimate
This commit is contained in:
parent
29b13ff98a
commit
a933652950
@ -822,16 +822,11 @@ bool AP_AHRS::airspeed_estimate(float &airspeed_ret) const
|
||||
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
||||
case EKFType::SIM:
|
||||
#if HAL_NAVEKF3_AVAILABLE
|
||||
if (EKF3.getWind(-1,wind_vel)) {
|
||||
ret = true;
|
||||
} else {
|
||||
ret = false;
|
||||
if (!_sitl) {
|
||||
return false;
|
||||
}
|
||||
#else
|
||||
ret = false;
|
||||
#endif
|
||||
break;
|
||||
airspeed_ret = _sitl->state.airspeed;
|
||||
return true;
|
||||
#endif
|
||||
|
||||
#if HAL_NAVEKF2_AVAILABLE
|
||||
|
Loading…
Reference in New Issue
Block a user