mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_Periph: stop sending airspeed when unhealthy
This commit is contained in:
parent
2d75ef4f60
commit
74813e7761
@ -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;
|
||||
|
Loading…
Reference in New Issue
Block a user