From 74813e7761ac14cc9ecdf14b15d9d75d4164c715 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 8 Dec 2020 14:04:53 +1100 Subject: [PATCH] AP_Periph: stop sending airspeed when unhealthy --- Tools/AP_Periph/msp.cpp | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/Tools/AP_Periph/msp.cpp b/Tools/AP_Periph/msp.cpp index 6fe7e75599..3d44680ba3 100644 --- a/Tools/AP_Periph/msp.cpp +++ b/Tools/AP_Periph/msp.cpp @@ -175,6 +175,11 @@ void AP_Periph_FW::send_msp_airspeed(void) if (msp.last_airspeed_ms == last_update_ms) { return; } + if (!airspeed.healthy()) { + // we don't report at all for an unhealthy sensor. This maps + // to unhealthy in the flight controller driver + return; + } msp.last_airspeed_ms = last_update_ms; p.instance = 0;