mirror of https://github.com/ArduPilot/ardupilot
AP_RPM: Add enabled() method to check if sensor is enabled
This commit is contained in:
parent
1c1eea6119
commit
a08fa50fda
|
@ -129,3 +129,18 @@ bool AP_RPM::healthy(uint8_t instance) const
|
||||||
}
|
}
|
||||||
return true;
|
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;
|
||||||
|
}
|
||||||
|
|
|
@ -77,6 +77,8 @@ public:
|
||||||
|
|
||||||
bool healthy(uint8_t instance) const;
|
bool healthy(uint8_t instance) const;
|
||||||
|
|
||||||
|
bool enabled(uint8_t instance) const;
|
||||||
|
|
||||||
private:
|
private:
|
||||||
RPM_State state[RPM_MAX_INSTANCES];
|
RPM_State state[RPM_MAX_INSTANCES];
|
||||||
AP_RPM_Backend *drivers[RPM_MAX_INSTANCES];
|
AP_RPM_Backend *drivers[RPM_MAX_INSTANCES];
|
||||||
|
|
Loading…
Reference in New Issue