AP_RPM: Add enabled() method to check if sensor is enabled

This commit is contained in:
Robert Lefebvre 2015-11-18 18:59:10 -05:00 committed by Andrew Tridgell
parent 1c1eea6119
commit a08fa50fda
2 changed files with 17 additions and 0 deletions

View File

@ -129,3 +129,18 @@ bool AP_RPM::healthy(uint8_t instance) const
}
return true;
}
/*
check if an instance is activated
*/
bool AP_RPM::enabled(uint8_t instance) const
{
if (instance >= num_instances) {
return false;
}
// if no sensor type is selected, the sensor is not activated.
if (_type[instance] == RPM_TYPE_NONE) {
return false;
}
return true;
}

View File

@ -77,6 +77,8 @@ public:
bool healthy(uint8_t instance) const;
bool enabled(uint8_t instance) const;
private:
RPM_State state[RPM_MAX_INSTANCES];
AP_RPM_Backend *drivers[RPM_MAX_INSTANCES];