HAL_ChibiOS: limit RX timeout to 100ms

this prevents a very long timeout in begin(), replacement with a mutex
will happen in a separate PR
This commit is contained in:
Andrew Tridgell 2024-09-24 20:49:19 +10:00 committed by Randy Mackay
parent 7264d7e16d
commit 06e3b2051d
1 changed files with 3 additions and 0 deletions

View File

@ -877,6 +877,9 @@ 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;
// prevent very long timeouts at low baudrates which could cause another thread
// using begin() to block
timeout_us = MIN(timeout_us, 100000UL);
chSysUnlock(); chSysUnlock();
// wait for the completion or timeout handlers to signal that we are done // wait for the completion or timeout handlers to signal that we are done
eventmask_t mask = chEvtWaitAnyTimeout(EVT_TRANSMIT_DMA_COMPLETE, chTimeUS2I(timeout_us)); eventmask_t mask = chEvtWaitAnyTimeout(EVT_TRANSMIT_DMA_COMPLETE, chTimeUS2I(timeout_us));