AP_Motors: add and use AP_RPM_ENABLED

... and backend-specific equivalents
This commit is contained in:
Peter Barker 2022-07-15 21:53:41 +10:00 committed by Andrew Tridgell
parent 7eedc88646
commit d21aa2a1ed
1 changed files with 4 additions and 0 deletions

View File

@ -234,6 +234,7 @@ void AP_MotorsHeli_RSC::set_throttle_curve()
void AP_MotorsHeli_RSC::output(RotorControlState state)
{
// _rotor_RPM available to the RSC output
#if AP_RPM_ENABLED
const AP_RPM *rpm = AP_RPM::get_singleton();
if (rpm != nullptr) {
if (!rpm->get_rpm(0, _rotor_rpm)) {
@ -244,6 +245,9 @@ void AP_MotorsHeli_RSC::output(RotorControlState state)
// No RPM because pointer is null
_rotor_rpm = -1;
}
#else
_rotor_rpm = -1;
#endif
float dt;
uint64_t now = AP_HAL::micros64();