mirror of https://github.com/ArduPilot/ardupilot
HAL_ChibiOS: improve DShot timing accuracy
This commit is contained in:
parent
93111dc0b1
commit
26d279e165
|
@ -414,8 +414,8 @@ void RCOutput::set_output_mode(uint16_t mask, enum output_mode mode)
|
|||
const uint32_t bit_period = 19;
|
||||
// configure timer driver for DMAR at requested rate
|
||||
pwmStop(group.pwm_drv);
|
||||
group.pwm_cfg.frequency = rate * bit_period;
|
||||
group.pwm_cfg.period = bit_period;
|
||||
group.pwm_cfg.frequency = rate * bit_period * dshot_clockmul;
|
||||
group.pwm_cfg.period = bit_period * dshot_clockmul;
|
||||
group.pwm_cfg.dier = TIM_DIER_UDE;
|
||||
group.pwm_cfg.cr2 = 0;
|
||||
pwmStart(group.pwm_drv, &group.pwm_cfg);
|
||||
|
@ -623,8 +623,8 @@ uint16_t RCOutput::create_dshot_packet(const uint16_t value)
|
|||
*/
|
||||
void RCOutput::fill_DMA_buffer_dshot(uint32_t *buffer, uint8_t stride, uint16_t packet)
|
||||
{
|
||||
const uint8_t DSHOT_MOTOR_BIT_0 = 7;
|
||||
const uint8_t DSHOT_MOTOR_BIT_1 = 14;
|
||||
const uint8_t DSHOT_MOTOR_BIT_0 = 7 * dshot_clockmul;
|
||||
const uint8_t DSHOT_MOTOR_BIT_1 = 14 * dshot_clockmul;
|
||||
for (uint16_t i = 0; i < 16; i++) {
|
||||
buffer[i * stride] = (packet & 0x8000) ? DSHOT_MOTOR_BIT_1 : DSHOT_MOTOR_BIT_0;
|
||||
packet <<= 1;
|
||||
|
|
|
@ -134,6 +134,7 @@ private:
|
|||
DShot handling
|
||||
*/
|
||||
const uint8_t dshot_post = 2;
|
||||
const uint8_t dshot_clockmul = 2;
|
||||
const uint16_t dshot_bit_length = 16 + dshot_post;
|
||||
const uint16_t dshot_buffer_length = dshot_bit_length*4*sizeof(uint32_t);
|
||||
uint32_t dshot_pulse_time_us;
|
||||
|
|
Loading…
Reference in New Issue