AP_DAL: added healthy() method for airspeed

This commit is contained in:
Andrew Tridgell 2020-12-08 14:03:49 +11:00
parent ca41a19072
commit d16af5448b
1 changed files with 4 additions and 0 deletions

View File

@ -15,6 +15,10 @@ public:
bool healthy(uint8_t i) const { bool healthy(uint8_t i) const {
return _RASI[i].healthy; 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 // return true if airspeed is enabled, and airspeed use is set
bool use(uint8_t i) const { bool use(uint8_t i) const {