From 879f250fac7787204759db8e2da9a5841f063b0e Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Wed, 23 May 2018 12:31:09 +1000 Subject: [PATCH] GCS_Common: return airspeed sensor value in vfr_hud_airspeed --- libraries/GCS_MAVLink/GCS_Common.cpp | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/libraries/GCS_MAVLink/GCS_Common.cpp b/libraries/GCS_MAVLink/GCS_Common.cpp index 27c82d5ecb..6ef9f131c0 100644 --- a/libraries/GCS_MAVLink/GCS_Common.cpp +++ b/libraries/GCS_MAVLink/GCS_Common.cpp @@ -1730,6 +1730,10 @@ void GCS_MAVLINK::send_accelcal_vehicle_position(uint32_t position) float GCS_MAVLINK::vfr_hud_airspeed() const { + AP_Airspeed *airspeed = AP_Airspeed::get_singleton(); + if (airspeed != nullptr && airspeed->healthy()) { + return airspeed->get_airspeed(); + } // because most vehicles don't have airspeed sensors, we return a // different sort of speed estimate in the relevant field for // comparison's sake.