mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 16:48:29 -04:00
HAL_ChibiOS: produce more accurate clocks for DShot and PWM
This commit is contained in:
parent
b7672cde69
commit
53b5564466
@ -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;
|
uint32_t clock_hz = group.pwm_drv->clock;
|
||||||
target_frequency = bitrate * bit_width;
|
target_frequency = bitrate * bit_width;
|
||||||
uint32_t prescaler = clock_hz / target_frequency;
|
uint32_t prescaler = clock_hz / target_frequency;
|
||||||
while ((clock_hz / prescaler) * prescaler != clock_hz && prescaler <= 0x8000) {
|
|
||||||
prescaler++;
|
|
||||||
}
|
|
||||||
freq = clock_hz / 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) {
|
if (prescaler > 0x8000) {
|
||||||
group.dma_handle->unlock();
|
group.dma_handle->unlock();
|
||||||
return false;
|
return false;
|
||||||
|
Loading…
Reference in New Issue
Block a user