mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 08:38:36 -04:00
AP_HAL_ChibiOS: fix compilation when HAL_WITH_ESC_TELEM == 0
This commit is contained in:
parent
2d5ac0009a
commit
8593672f4c
@ -1356,12 +1356,12 @@ void RCOutput::dshot_send(pwm_group &group, uint32_t time_out_us)
|
||||
#ifdef HAL_WITH_BIDIR_DSHOT
|
||||
// retrieve the last erpm values
|
||||
const uint16_t erpm = group.bdshot.erpm[i];
|
||||
|
||||
#if HAL_WITH_ESC_TELEM
|
||||
// update the ESC telemetry data
|
||||
if (erpm < 0xFFFF && group.bdshot.enabled) {
|
||||
update_rpm(chan, erpm * 200 / _bdshot.motor_poles, get_erpm_error_rate(chan));
|
||||
}
|
||||
|
||||
#endif
|
||||
_bdshot.erpm[chan] = erpm;
|
||||
#endif
|
||||
uint16_t pwm = period[chan];
|
||||
|
Loading…
Reference in New Issue
Block a user