diff --git a/ArduPlane/GCS_Mavlink.cpp b/ArduPlane/GCS_Mavlink.cpp index 2e37f74e54..115ca4634c 100644 --- a/ArduPlane/GCS_Mavlink.cpp +++ b/ArduPlane/GCS_Mavlink.cpp @@ -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