mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-12 01:23:56 -03:00
AP_AHRS: fixed build on boards without EKF2
This commit is contained in:
parent
ad582a90dd
commit
6d6ec44d59
@ -668,13 +668,16 @@ bool AP_AHRS_NavEKF::airspeed_estimate(float &airspeed_ret) const
|
|||||||
break;
|
break;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#if HAL_NAVEKF2_AVAILABLE
|
||||||
case EKFType::TWO:
|
case EKFType::TWO:
|
||||||
return AP_AHRS_DCM::airspeed_estimate(get_active_airspeed_index(), airspeed_ret);
|
return AP_AHRS_DCM::airspeed_estimate(get_active_airspeed_index(), airspeed_ret);
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if HAL_NAVEKF3_AVAILABLE
|
||||||
case EKFType::THREE:
|
case EKFType::THREE:
|
||||||
ret = EKF3.getWind(-1,wind_vel);
|
ret = EKF3.getWind(-1,wind_vel);
|
||||||
break;
|
break;
|
||||||
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
// estimate it via nav velocity and wind estimates
|
// estimate it via nav velocity and wind estimates
|
||||||
|
Loading…
Reference in New Issue
Block a user