From 3f9bd65d2f0c77ce7b3a4a5e624efa9e8e7baa56 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell <tridge@samba.org> Date: Thu, 20 Sep 2012 08:00:54 +1000 Subject: [PATCH] APM: send airspeed sensor value, not estimate, when enabled this solves the problem of people reporting that airspeed is not shown when ARSPD_USE is zero. --- ArduPlane/GCS_Mavlink.pde | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ArduPlane/GCS_Mavlink.pde b/ArduPlane/GCS_Mavlink.pde index 15b80b37fa..61692bddd3 100644 --- a/ArduPlane/GCS_Mavlink.pde +++ b/ArduPlane/GCS_Mavlink.pde @@ -340,7 +340,7 @@ static void NOINLINE send_radio_out(mavlink_channel_t chan) static void NOINLINE send_vfr_hud(mavlink_channel_t chan) { float aspeed; - if (airspeed.use()) { + if (airspeed.enabled()) { aspeed = airspeed.get_airspeed(); } else if (!ahrs.airspeed_estimate(&aspeed)) { aspeed = 0;