HAL_ChibiOS: produce more accurate clocks for DShot and PWM

This commit is contained in:
Andrew Tridgell 2020-02-05 15:47:08 +11:00
parent 3757adfdc6
commit a0fe1a7598
1 changed files with 1 additions and 4 deletions

View File

@ -540,11 +540,8 @@ bool RCOutput::setup_group_DMA(pwm_group &group, uint32_t bitrate, uint32_t bit_
uint32_t clock_hz = group.pwm_drv->clock;
target_frequency = bitrate * bit_width;
uint32_t prescaler = clock_hz / target_frequency;
while ((clock_hz / prescaler) * prescaler != clock_hz && prescaler <= 0x8000) {
prescaler++;
}
freq = clock_hz / prescaler;
// hal.console->printf("CLOCK=%u FREQ=%u PRE=%u BR=%u\n", clock_hz, freq/bit_width, prescaler, bitrate);
// hal.console->printf("CLOCK=%u BW=%u FREQ=%u PRE=%u BR=%u\n", clock_hz, bit_width, freq/bit_width, prescaler, bitrate);
if (prescaler > 0x8000) {
group.dma_handle->unlock();
return false;