mirror of https://github.com/ArduPilot/ardupilot
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
f1bdb1dffc
commit
acee3f7594
|
@ -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));
|
||||||
|
|
Loading…
Reference in New Issue