mirror of https://github.com/ArduPilot/ardupilot
Plane: Only send healthy airspeed reports
This commit is contained in:
parent
44f2a652f3
commit
749861f8ad
|
@ -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();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue