mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 15:53:56 -04:00
AP_HAL_ChibiOS: explicitly set dshot rate when using iomcu
This commit is contained in:
parent
c4cfc5dbe4
commit
75c1ad6efa
@ -513,16 +513,15 @@ void RCOutput::set_default_rate(uint16_t freq_hz)
|
||||
*/
|
||||
void RCOutput::set_dshot_rate(uint8_t dshot_rate, uint16_t loop_rate_hz)
|
||||
{
|
||||
#if HAL_WITH_IO_MCU
|
||||
if (AP_BoardConfig::io_dshot()) {
|
||||
iomcu.set_dshot_period(1000UL, 0);
|
||||
}
|
||||
#endif
|
||||
|
||||
// for low loop rates simply output at 1Khz on a timer
|
||||
if (loop_rate_hz <= 100 || dshot_rate == 0) {
|
||||
_dshot_period_us = 1000UL;
|
||||
_dshot_rate = 0;
|
||||
#if HAL_WITH_IO_MCU
|
||||
if (AP_BoardConfig::io_dshot()) {
|
||||
iomcu.set_dshot_period(1000UL, 0);
|
||||
}
|
||||
#endif
|
||||
return;
|
||||
}
|
||||
// if there are non-dshot channels then do likewise
|
||||
@ -532,6 +531,13 @@ void RCOutput::set_dshot_rate(uint8_t dshot_rate, uint16_t loop_rate_hz)
|
||||
group.current_mode == MODE_PWM_BRUSHED) {
|
||||
_dshot_period_us = 1000UL;
|
||||
_dshot_rate = 0;
|
||||
#if HAL_WITH_IO_MCU
|
||||
// this is not strictly neccessary since the iomcu could run at a different rate,
|
||||
// but there is only one parameter to control this
|
||||
if (AP_BoardConfig::io_dshot()) {
|
||||
iomcu.set_dshot_period(1000UL, 0);
|
||||
}
|
||||
#endif
|
||||
return;
|
||||
}
|
||||
}
|
||||
|
@ -16,7 +16,7 @@ undef AP_HAL_SHARED_DMA_ENABLED
|
||||
define STM32_TIM_TIM2_UP_DMA_STREAM STM32_DMA_STREAM_ID(1, 2)
|
||||
define STM32_TIM_TIM2_UP_DMA_CHAN 1
|
||||
|
||||
# TIM4_UP (PWM 3/4) cannot be used with sharin as channels used by high speed USART2 RX/TX
|
||||
# TIM4_UP (PWM 3/4) cannot be used with sharing as channels used by high speed USART2 RX/TX
|
||||
define AP_HAL_SHARED_DMA_ENABLED 1
|
||||
define STM32_TIM_TIM4_UP_DMA_STREAM STM32_DMA_STREAM_ID(1, 7)
|
||||
define STM32_TIM_TIM4_UP_DMA_CHAN 1
|
||||
|
Loading…
Reference in New Issue
Block a user