mirror of https://github.com/ArduPilot/ardupilot
AP_Motors: add and use AP_RPM_ENABLED
... and backend-specific equivalents
This commit is contained in:
parent
7eedc88646
commit
d21aa2a1ed
|
@ -234,6 +234,7 @@ void AP_MotorsHeli_RSC::set_throttle_curve()
|
||||||
void AP_MotorsHeli_RSC::output(RotorControlState state)
|
void AP_MotorsHeli_RSC::output(RotorControlState state)
|
||||||
{
|
{
|
||||||
// _rotor_RPM available to the RSC output
|
// _rotor_RPM available to the RSC output
|
||||||
|
#if AP_RPM_ENABLED
|
||||||
const AP_RPM *rpm = AP_RPM::get_singleton();
|
const AP_RPM *rpm = AP_RPM::get_singleton();
|
||||||
if (rpm != nullptr) {
|
if (rpm != nullptr) {
|
||||||
if (!rpm->get_rpm(0, _rotor_rpm)) {
|
if (!rpm->get_rpm(0, _rotor_rpm)) {
|
||||||
|
@ -244,6 +245,9 @@ void AP_MotorsHeli_RSC::output(RotorControlState state)
|
||||||
// No RPM because pointer is null
|
// No RPM because pointer is null
|
||||||
_rotor_rpm = -1;
|
_rotor_rpm = -1;
|
||||||
}
|
}
|
||||||
|
#else
|
||||||
|
_rotor_rpm = -1;
|
||||||
|
#endif
|
||||||
|
|
||||||
float dt;
|
float dt;
|
||||||
uint64_t now = AP_HAL::micros64();
|
uint64_t now = AP_HAL::micros64();
|
||||||
|
|
Loading…
Reference in New Issue