mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
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
This commit is contained in:
parent
a10392d5e3
commit
cbfc505003
@ -747,7 +747,8 @@ void UARTDriver::handle_tx_timeout(void *arg)
|
|||||||
chSysLockFromISR();
|
chSysLockFromISR();
|
||||||
if (!uart_drv->tx_bounce_buf_ready) {
|
if (!uart_drv->tx_bounce_buf_ready) {
|
||||||
dmaStreamDisable(uart_drv->txdma);
|
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->tx_bounce_buf_ready = true;
|
||||||
uart_drv->dma_handle->unlock_from_IRQ();
|
uart_drv->dma_handle->unlock_from_IRQ();
|
||||||
}
|
}
|
||||||
@ -790,6 +791,7 @@ void UARTDriver::write_pending_bytes_DMA(uint32_t n)
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
chSysLock();
|
||||||
dmaStreamDisable(txdma);
|
dmaStreamDisable(txdma);
|
||||||
tx_bounce_buf_ready = false;
|
tx_bounce_buf_ready = false;
|
||||||
osalDbgAssert(txdma != nullptr, "UART TX DMA allocation failed");
|
osalDbgAssert(txdma != nullptr, "UART TX DMA allocation failed");
|
||||||
@ -803,7 +805,8 @@ void UARTDriver::write_pending_bytes_DMA(uint32_t n)
|
|||||||
STM32_DMA_CR_MINC | STM32_DMA_CR_TCIE);
|
STM32_DMA_CR_MINC | STM32_DMA_CR_TCIE);
|
||||||
dmaStreamEnable(txdma);
|
dmaStreamEnable(txdma);
|
||||||
uint32_t timeout_us = ((1000000UL * (tx_len+2) * 10) / _baudrate) + 500;
|
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
|
#endif // HAL_UART_NODMA
|
||||||
|
|
||||||
|
@ -136,7 +136,7 @@ private:
|
|||||||
uint32_t lock_read_key;
|
uint32_t lock_read_key;
|
||||||
|
|
||||||
uint32_t _baudrate;
|
uint32_t _baudrate;
|
||||||
uint16_t tx_len;
|
volatile uint16_t tx_len;
|
||||||
#if HAL_USE_SERIAL == TRUE
|
#if HAL_USE_SERIAL == TRUE
|
||||||
SerialConfig sercfg;
|
SerialConfig sercfg;
|
||||||
#endif
|
#endif
|
||||||
@ -152,7 +152,7 @@ private:
|
|||||||
// we use in-task ring buffers to reduce the system call cost
|
// we use in-task ring buffers to reduce the system call cost
|
||||||
// of ::read() and ::write() in the main loop
|
// of ::read() and ::write() in the main loop
|
||||||
#ifndef HAL_UART_NODMA
|
#ifndef HAL_UART_NODMA
|
||||||
bool tx_bounce_buf_ready;
|
volatile bool tx_bounce_buf_ready;
|
||||||
volatile uint8_t rx_bounce_idx;
|
volatile uint8_t rx_bounce_idx;
|
||||||
uint8_t *rx_bounce_buf[2];
|
uint8_t *rx_bounce_buf[2];
|
||||||
uint8_t *tx_bounce_buf;
|
uint8_t *tx_bounce_buf;
|
||||||
|
Loading…
Reference in New Issue
Block a user