diff --git a/ArduPlane/GCS_Mavlink.cpp b/ArduPlane/GCS_Mavlink.cpp index 3211c35bcc..005fca246e 100644 --- a/ArduPlane/GCS_Mavlink.cpp +++ b/ArduPlane/GCS_Mavlink.cpp @@ -243,7 +243,7 @@ float GCS_MAVLINK_Plane::vfr_hud_airspeed() const // will use an airspeed sensor, that value is constrained by the // ground speed. When reporting we should send the true airspeed // value if possible: - if (plane.airspeed.enabled()) { + if (plane.airspeed.enabled() && plane.airspeed.healthy()) { return plane.airspeed.get_airspeed(); }