mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-18 06:38:29 -04:00
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:
parent
25e77a5d9f
commit
070363e453
@ -911,6 +911,9 @@ 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;
|
||||
// prevent very long timeouts at low baudrates which could cause another thread
|
||||
// using begin() to block
|
||||
timeout_us = MIN(timeout_us, 100000UL);
|
||||
chSysUnlock();
|
||||
// wait for the completion or timeout handlers to signal that we are done
|
||||
eventmask_t mask = chEvtWaitAnyTimeout(EVT_TRANSMIT_DMA_COMPLETE, chTimeUS2I(timeout_us));
|
||||
|
Loading…
Reference in New Issue
Block a user