Plane: Only send healthy airspeed reports

This commit is contained in:
Michael du Breuil 2018-05-31 15:31:50 -07:00 committed by Andrew Tridgell
parent 44f2a652f3
commit 749861f8ad
1 changed files with 1 additions and 1 deletions

View File

@ -243,7 +243,7 @@ float GCS_MAVLINK_Plane::vfr_hud_airspeed() const
// will use an airspeed sensor, that value is constrained by the // will use an airspeed sensor, that value is constrained by the
// ground speed. When reporting we should send the true airspeed // ground speed. When reporting we should send the true airspeed
// value if possible: // value if possible:
if (plane.airspeed.enabled()) { if (plane.airspeed.enabled() && plane.airspeed.healthy()) {
return plane.airspeed.get_airspeed(); return plane.airspeed.get_airspeed();
} }