mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 09:58:28 -04:00
AP_HAL_ChibiOS: ensure that DMA source is correct on DMA send for rcout
This commit is contained in:
parent
d8042a1325
commit
5ecf7ff1fe
@ -1582,7 +1582,9 @@ void RCOutput::send_pulses_DMAR(pwm_group &group, uint32_t buffer_length)
|
|||||||
up with this great method.
|
up with this great method.
|
||||||
*/
|
*/
|
||||||
TOGGLE_PIN_DEBUG(54);
|
TOGGLE_PIN_DEBUG(54);
|
||||||
|
#if STM32_DMA_SUPPORTS_DMAMUX
|
||||||
|
dmaSetRequestSource(group.dma, group.dma_up_channel);
|
||||||
|
#endif
|
||||||
dmaStreamSetPeripheral(group.dma, &(group.pwm_drv->tim->DMAR));
|
dmaStreamSetPeripheral(group.dma, &(group.pwm_drv->tim->DMAR));
|
||||||
stm32_cacheBufferFlush(group.dma_buffer, buffer_length);
|
stm32_cacheBufferFlush(group.dma_buffer, buffer_length);
|
||||||
dmaStreamSetMemory0(group.dma, group.dma_buffer);
|
dmaStreamSetMemory0(group.dma, group.dma_buffer);
|
||||||
|
Loading…
Reference in New Issue
Block a user