From 989f8c5d419a80ed74c84ea217eab5afeb806576 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Wed, 7 Oct 2020 17:41:13 +1100 Subject: [PATCH] HAL_ChibiOS: fixed a race condition in UART DMA transmit this fixes an issue seen on one board which caused a watchdog on high uart DMA load. We have reproduced the issue on another board by forcing a very high DMA transfer rate on the same DMA channel while also requesting very high transfer rates on the UART. The likely race is in the DMA transmit timeout code, and the simplest fix is to lock out interrupts during the DMA setup to ensure the tx timeout cannot trigger during the setup --- libraries/AP_HAL_ChibiOS/UARTDriver.cpp | 7 +++++-- libraries/AP_HAL_ChibiOS/UARTDriver.h | 4 ++-- 2 files changed, 7 insertions(+), 4 deletions(-) diff --git a/libraries/AP_HAL_ChibiOS/UARTDriver.cpp b/libraries/AP_HAL_ChibiOS/UARTDriver.cpp index 1cfed5c348..d9c6c5bf44 100644 --- a/libraries/AP_HAL_ChibiOS/UARTDriver.cpp +++ b/libraries/AP_HAL_ChibiOS/UARTDriver.cpp @@ -802,7 +802,8 @@ void UARTDriver::handle_tx_timeout(void *arg) chSysLockFromISR(); if (!uart_drv->tx_bounce_buf_ready) { dmaStreamDisable(uart_drv->txdma); - uart_drv->tx_len -= dmaStreamGetTransactionSize(uart_drv->txdma); + const uint32_t tx_size = dmaStreamGetTransactionSize(uart_drv->txdma); + uart_drv->tx_len -= MIN(uart_drv->tx_len, tx_size); uart_drv->tx_bounce_buf_ready = true; uart_drv->dma_handle->unlock_from_IRQ(); } @@ -845,6 +846,7 @@ void UARTDriver::write_pending_bytes_DMA(uint32_t n) } } + chSysLock(); dmaStreamDisable(txdma); tx_bounce_buf_ready = false; osalDbgAssert(txdma != nullptr, "UART TX DMA allocation failed"); @@ -858,7 +860,8 @@ void UARTDriver::write_pending_bytes_DMA(uint32_t n) STM32_DMA_CR_MINC | STM32_DMA_CR_TCIE); dmaStreamEnable(txdma); uint32_t timeout_us = ((1000000UL * (tx_len+2) * 10) / _baudrate) + 500; - chVTSet(&tx_timeout, chTimeUS2I(timeout_us), handle_tx_timeout, this); + chVTSetI(&tx_timeout, chTimeUS2I(timeout_us), handle_tx_timeout, this); + chSysUnlock(); } #endif // HAL_UART_NODMA diff --git a/libraries/AP_HAL_ChibiOS/UARTDriver.h b/libraries/AP_HAL_ChibiOS/UARTDriver.h index ab2b51aa4d..1deb4201b2 100644 --- a/libraries/AP_HAL_ChibiOS/UARTDriver.h +++ b/libraries/AP_HAL_ChibiOS/UARTDriver.h @@ -141,7 +141,7 @@ private: uint32_t lock_read_key; uint32_t _baudrate; - uint16_t tx_len; + volatile uint16_t tx_len; #if HAL_USE_SERIAL == TRUE SerialConfig sercfg; #endif @@ -157,7 +157,7 @@ private: // we use in-task ring buffers to reduce the system call cost // of ::read() and ::write() in the main loop #ifndef HAL_UART_NODMA - bool tx_bounce_buf_ready; + volatile bool tx_bounce_buf_ready; volatile uint8_t rx_bounce_idx; uint8_t *rx_bounce_buf[2]; uint8_t *tx_bounce_buf;