mirror of https://github.com/ArduPilot/ardupilot
HAL_ChibiOS: enable DShot on G4
This commit is contained in:
parent
f57b1b9c4b
commit
f2ac61f6ba
|
@ -1333,7 +1333,9 @@ void RCOutput::send_pulses_DMAR(pwm_group &group, uint32_t buffer_length)
|
||||||
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);
|
||||||
dmaStreamSetTransactionSize(group.dma, buffer_length/sizeof(uint32_t));
|
dmaStreamSetTransactionSize(group.dma, buffer_length/sizeof(uint32_t));
|
||||||
|
#ifdef STM32_DMA_FCR_FTH_FULL
|
||||||
dmaStreamSetFIFO(group.dma, STM32_DMA_FCR_DMDIS | STM32_DMA_FCR_FTH_FULL);
|
dmaStreamSetFIFO(group.dma, STM32_DMA_FCR_DMDIS | STM32_DMA_FCR_FTH_FULL);
|
||||||
|
#endif
|
||||||
dmaStreamSetMode(group.dma,
|
dmaStreamSetMode(group.dma,
|
||||||
STM32_DMA_CR_CHSEL(group.dma_up_channel) |
|
STM32_DMA_CR_CHSEL(group.dma_up_channel) |
|
||||||
STM32_DMA_CR_DIR_M2P | STM32_DMA_CR_PSIZE_WORD | STM32_DMA_CR_MSIZE_WORD |
|
STM32_DMA_CR_DIR_M2P | STM32_DMA_CR_PSIZE_WORD | STM32_DMA_CR_MSIZE_WORD |
|
||||||
|
|
|
@ -24,7 +24,7 @@
|
||||||
|
|
||||||
#if HAL_USE_PWM == TRUE
|
#if HAL_USE_PWM == TRUE
|
||||||
|
|
||||||
#if !STM32_DMA_ADVANCED
|
#if !STM32_DMA_ADVANCED && !defined(STM32G4)
|
||||||
#define DISABLE_DSHOT
|
#define DISABLE_DSHOT
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue