From dad17743305eb9f121362deb05731337fed7ac5d Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Mon, 18 Feb 2019 10:11:35 +1100 Subject: [PATCH] HAL_ChibiOS: fixed channel selection for F4/F7 uart driver --- libraries/AP_HAL_ChibiOS/UARTDriver.cpp | 6 ++---- 1 file changed, 2 insertions(+), 4 deletions(-) diff --git a/libraries/AP_HAL_ChibiOS/UARTDriver.cpp b/libraries/AP_HAL_ChibiOS/UARTDriver.cpp index 2581d0918d..47525ce533 100644 --- a/libraries/AP_HAL_ChibiOS/UARTDriver.cpp +++ b/libraries/AP_HAL_ChibiOS/UARTDriver.cpp @@ -284,8 +284,7 @@ void UARTDriver::begin(uint32_t b, uint16_t rxS, uint16_t txS) //Start DMA if(!was_initialised) { uint32_t dmamode = STM32_DMA_CR_DMEIE | STM32_DMA_CR_TEIE; - dmamode |= STM32_DMA_CR_CHSEL(STM32_DMA_GETCHANNEL(sdef.dma_rx_stream_id, - sdef.dma_rx_channel_id)); + dmamode |= STM32_DMA_CR_CHSEL(sdef.dma_rx_channel_id); dmamode |= STM32_DMA_CR_PL(0); dmaStreamSetMemory0(rxdma, rx_bounce_buf); dmaStreamSetTransactionSize(rxdma, RX_BOUNCE_BUFSIZE); @@ -734,8 +733,7 @@ void UARTDriver::write_pending_bytes_DMA(uint32_t n) dmaStreamSetMemory0(txdma, tx_bounce_buf); dmaStreamSetTransactionSize(txdma, tx_len); uint32_t dmamode = STM32_DMA_CR_DMEIE | STM32_DMA_CR_TEIE; - dmamode |= STM32_DMA_CR_CHSEL(STM32_DMA_GETCHANNEL(sdef.dma_tx_stream_id, - sdef.dma_tx_channel_id)); + dmamode |= STM32_DMA_CR_CHSEL(sdef.dma_tx_channel_id); dmamode |= STM32_DMA_CR_PL(0); dmaStreamSetMode(txdma, dmamode | STM32_DMA_CR_DIR_M2P | STM32_DMA_CR_MINC | STM32_DMA_CR_TCIE);