mirror of https://github.com/ArduPilot/ardupilot
AP_DAL: added healthy() method for airspeed
This commit is contained in:
parent
ca41a19072
commit
d16af5448b
|
@ -15,6 +15,10 @@ public:
|
|||
bool healthy(uint8_t i) const {
|
||||
return _RASI[i].healthy;
|
||||
}
|
||||
// return health status of primary sensor
|
||||
bool healthy() const {
|
||||
return healthy(get_primary());
|
||||
}
|
||||
|
||||
// return true if airspeed is enabled, and airspeed use is set
|
||||
bool use(uint8_t i) const {
|
||||
|
|
Loading…
Reference in New Issue