AP_Airspeed: added healthy() API
This commit is contained in:
parent
b62ad0d5fb
commit
0c5caac632
@ -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[];
|
||||
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user