mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 09:58:28 -04:00
HAL_ChibiOS: added a timeout to DMA UART TX
this prevents a shared DMA channel being held for a long time if a CTS pin is held either by not being connected or by a radio
This commit is contained in:
parent
cad7f9d9c0
commit
8431a677d9
@ -169,6 +169,7 @@ void UARTDriver::begin(uint32_t b, uint16_t rxS, uint16_t txS)
|
||||
}
|
||||
if (tx_bounce_buf == nullptr) {
|
||||
tx_bounce_buf = (uint8_t *)hal.util->malloc_type(TX_BOUNCE_BUFSIZE, AP_HAL::Util::MEM_DMA_SAFE);
|
||||
chVTObjectInit(&tx_timeout);
|
||||
tx_bounce_buf_ready = true;
|
||||
}
|
||||
|
||||
@ -324,6 +325,11 @@ void UARTDriver::tx_complete(void* self, uint32_t flags)
|
||||
{
|
||||
UARTDriver* uart_drv = (UARTDriver*)self;
|
||||
if (!uart_drv->tx_bounce_buf_ready) {
|
||||
// reset timeout
|
||||
chSysLockFromISR();
|
||||
chVTResetI(&uart_drv->tx_timeout);
|
||||
chSysUnlockFromISR();
|
||||
|
||||
uart_drv->_last_write_completed_us = AP_HAL::micros();
|
||||
uart_drv->tx_bounce_buf_ready = true;
|
||||
if (uart_drv->unbuffered_writes && uart_drv->_writebuf.available()) {
|
||||
@ -602,6 +608,7 @@ void UARTDriver::check_dma_tx_completion(void)
|
||||
if (txdma->stream->NDTR == 0) {
|
||||
tx_bounce_buf_ready = true;
|
||||
_last_write_completed_us = AP_HAL::micros();
|
||||
chVTResetI(&tx_timeout);
|
||||
dma_handle->unlock_from_lockzone();
|
||||
}
|
||||
}
|
||||
@ -609,6 +616,21 @@ void UARTDriver::check_dma_tx_completion(void)
|
||||
chSysUnlock();
|
||||
}
|
||||
|
||||
/*
|
||||
handle a TX timeout. This can happen with using hardware flow
|
||||
control if CTS pin blocks transmit
|
||||
*/
|
||||
void UARTDriver::handle_tx_timeout(void *arg)
|
||||
{
|
||||
UARTDriver* uart_drv = (UARTDriver*)arg;
|
||||
if (!uart_drv->tx_bounce_buf_ready) {
|
||||
uart_drv->tx_len = 0; // fix for n sent
|
||||
dmaStreamDisable(uart_drv->txdma);
|
||||
uart_drv->tx_bounce_buf_ready = true;
|
||||
uart_drv->dma_handle->unlock_from_IRQ();
|
||||
}
|
||||
}
|
||||
|
||||
/*
|
||||
write out pending bytes with DMA
|
||||
*/
|
||||
@ -653,6 +675,8 @@ void UARTDriver::write_pending_bytes_DMA(uint32_t n)
|
||||
dmaStreamSetMode(txdma, dmamode | STM32_DMA_CR_DIR_M2P |
|
||||
STM32_DMA_CR_MINC | STM32_DMA_CR_TCIE);
|
||||
dmaStreamEnable(txdma);
|
||||
uint32_t timeout_us = ((1000000UL * (tx_len+2) * 10) / _baudrate) + 500;
|
||||
chVTSet(&tx_timeout, US2ST(timeout_us), handle_tx_timeout, this);
|
||||
}
|
||||
|
||||
/*
|
||||
|
@ -138,6 +138,7 @@ private:
|
||||
Semaphore _write_mutex;
|
||||
const stm32_dma_stream_t* rxdma;
|
||||
const stm32_dma_stream_t* txdma;
|
||||
virtual_timer_t tx_timeout;
|
||||
bool _in_timer;
|
||||
bool _blocking_writes;
|
||||
bool _initialised;
|
||||
@ -162,6 +163,7 @@ private:
|
||||
static void rx_irq_cb(void* sd);
|
||||
static void rxbuff_full_irq(void* self, uint32_t flags);
|
||||
static void tx_complete(void* self, uint32_t flags);
|
||||
static void handle_tx_timeout(void *arg);
|
||||
|
||||
void dma_tx_allocate(Shared_DMA *ctx);
|
||||
void dma_tx_deallocate(Shared_DMA *ctx);
|
||||
|
Loading…
Reference in New Issue
Block a user