Plane: always report the airspeed estimate being used in VFR hud

This commit is contained in:
Iampete1 2022-09-14 21:13:45 +01:00
parent 3fdcf5f940
commit 96c3e1a758
1 changed files with 2 additions and 2 deletions

View File

@ -248,8 +248,8 @@ float GCS_MAVLINK_Plane::vfr_hud_airspeed() const
// ground speed. When reporting we should send the true airspeed
// value if possible:
#if AP_AIRSPEED_ENABLED
if (plane.airspeed.enabled() && plane.airspeed.healthy()) {
return plane.airspeed.get_airspeed();
if (plane.ahrs.airspeed_sensor_enabled()) {
return plane.airspeed.get_airspeed(plane.ahrs.get_active_airspeed_index());
}
#endif