HAL_ChibiOS: fixed delay for OneShot125 channels

we were delaying output for OneShot125 by 8x as much as we need to,
which reduced our max loop rate
This commit is contained in:
Andrew Tridgell 2019-09-22 18:31:16 +10:00
parent b07e95aab0
commit f6b28f3013

View File

@ -387,7 +387,9 @@ void RCOutput::push_local(void)
} else if (group.current_mode == MODE_PWM_ONESHOT125) {
// this gives us a width in 125 ns increments, giving 1000 steps over the 125 to 250 range
uint32_t width = ((group.pwm_cfg.frequency/1000000U) * period_us) / 8U;
pwmEnableChannel(group.pwm_drv, j, width);
pwmEnableChannel(group.pwm_drv, j, width);
// scale the period down so we don't delay for longer than we need to
period_us /= 8;
}
else if (group.current_mode < MODE_PWM_DSHOT150) {
uint32_t width = (group.pwm_cfg.frequency/1000000U) * period_us;