AP_Airspeed: added healthy() API

This commit is contained in:
Andrew Tridgell 2013-10-30 09:03:35 +11:00
parent 1aa29df52d
commit 9d7f24f754

View File

@ -125,6 +125,9 @@ public:
// log data to MAVLink
void log_mavlink_send(mavlink_channel_t chan, const Vector3f &vground);
// return health status of sensor
bool healthy(void) const { return _healthy; }
static const struct AP_Param::GroupInfo var_info[];