mirror of https://github.com/ArduPilot/ardupilot
AP_RPM: correct compilation when AP_RPM_ESC_TELEM_ENABLED is disabled
This commit is contained in:
parent
f3e56cc7a0
commit
83cecdd229
|
@ -24,7 +24,7 @@
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifndef AP_RPM_ESC_TELEM_ENABLED
|
#ifndef AP_RPM_ESC_TELEM_ENABLED
|
||||||
#define AP_RPM_ESC_TELEM_ENABLED AP_RPM_BACKEND_DEFAULT_ENABLED
|
#define AP_RPM_ESC_TELEM_ENABLED AP_RPM_BACKEND_DEFAULT_ENABLED && HAL_WITH_ESC_TELEM
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifndef AP_RPM_HARMONICNOTCH_ENABLED
|
#ifndef AP_RPM_HARMONICNOTCH_ENABLED
|
||||||
|
|
|
@ -33,13 +33,11 @@ AP_RPM_ESC_Telem::AP_RPM_ESC_Telem(AP_RPM &_ap_rpm, uint8_t _instance, AP_RPM::R
|
||||||
|
|
||||||
void AP_RPM_ESC_Telem::update(void)
|
void AP_RPM_ESC_Telem::update(void)
|
||||||
{
|
{
|
||||||
#if HAL_WITH_ESC_TELEM
|
|
||||||
AP_ESC_Telem &esc_telem = AP::esc_telem();
|
AP_ESC_Telem &esc_telem = AP::esc_telem();
|
||||||
float esc_rpm = esc_telem.get_average_motor_rpm(ap_rpm._params[state.instance].esc_mask);
|
float esc_rpm = esc_telem.get_average_motor_rpm(ap_rpm._params[state.instance].esc_mask);
|
||||||
state.rate_rpm = esc_rpm * ap_rpm._params[state.instance].scaling;
|
state.rate_rpm = esc_rpm * ap_rpm._params[state.instance].scaling;
|
||||||
state.signal_quality = 0.5f;
|
state.signal_quality = 0.5f;
|
||||||
state.last_reading_ms = AP_HAL::millis();
|
state.last_reading_ms = AP_HAL::millis();
|
||||||
#endif
|
|
||||||
}
|
}
|
||||||
|
|
||||||
#endif // AP_RPM_ESC_TELEM_ENABLED
|
#endif // AP_RPM_ESC_TELEM_ENABLED
|
||||||
|
|
Loading…
Reference in New Issue