AP_Airspeed: make it possible to tell if a airspeed sensor is unhealthy

we need use() to reflect if the user wants to use the sensor, so the
arming checks can tell if it is not working as expected
This commit is contained in:
Andrew Tridgell 2015-01-20 11:26:20 +11:00
parent b3ce56d34d
commit 2235d18d67

View File

@ -96,7 +96,7 @@ public:
// return true if airspeed is enabled, and airspeed use is set
bool use(void) const {
return _enable && _use && fabsf(_offset) > 0 && _healthy;
return _enable && _use;
}
// return true if airspeed is enabled
@ -147,7 +147,7 @@ public:
void log_mavlink_send(mavlink_channel_t chan, const Vector3f &vground);
// return health status of sensor
bool healthy(void) const { return _healthy; }
bool healthy(void) const { return _healthy && fabsf(_offset) > 0; }
void setHIL(float pressure) { _healthy=_hil_set=true; _hil_pressure=pressure; };