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.
This commit is contained in:
Andrew Tridgell 2012-09-20 08:00:54 +10:00
parent a84a08d2a4
commit 3f9bd65d2f

View File

@ -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;