From 47a5d78397865caa4fbbfcd3699522ce3333a018 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 16 Jun 2020 18:28:40 +1000 Subject: [PATCH] HAL_ChibiOS: disable DMA on high contention UARTs switch to interrupt driven when in high contention --- libraries/AP_HAL_ChibiOS/UARTDriver.cpp | 12 ++++++++++++ libraries/AP_HAL_ChibiOS/UARTDriver.h | 1 + 2 files changed, 13 insertions(+) diff --git a/libraries/AP_HAL_ChibiOS/UARTDriver.cpp b/libraries/AP_HAL_ChibiOS/UARTDriver.cpp index 1be107da63..d0bf1b7967 100644 --- a/libraries/AP_HAL_ChibiOS/UARTDriver.cpp +++ b/libraries/AP_HAL_ChibiOS/UARTDriver.cpp @@ -901,6 +901,16 @@ void UARTDriver::write_pending_bytes_DMA(uint32_t n) chEvtGetAndClearEvents(EVT_TRANSMIT_DMA_COMPLETE); if (dma_handle->has_contention()) { + if (_baudrate <= 115200) { + contention_counter += 3; + if (contention_counter > 1000) { + // more than 25% of attempts to use this DMA + // channel are getting contention and we have a + // low baudrate. Switch off DMA for future + // transmits on this low baudrate UART + tx_dma_enabled = false; + } + } /* someone else is using this same DMA channel. To reduce latency we will drop the TX size with DMA on this UART to @@ -911,6 +921,8 @@ void UARTDriver::write_pending_bytes_DMA(uint32_t n) if (tx_len > max_tx_bytes) { tx_len = max_tx_bytes; } + } else if (contention_counter > 0) { + contention_counter--; } chSysLock(); diff --git a/libraries/AP_HAL_ChibiOS/UARTDriver.h b/libraries/AP_HAL_ChibiOS/UARTDriver.h index 4d555ea875..c2c1348c41 100644 --- a/libraries/AP_HAL_ChibiOS/UARTDriver.h +++ b/libraries/AP_HAL_ChibiOS/UARTDriver.h @@ -178,6 +178,7 @@ private: volatile uint8_t rx_bounce_idx; uint8_t *rx_bounce_buf[2]; uint8_t *tx_bounce_buf; + uint16_t contention_counter; #endif ByteBuffer _readbuf{0}; ByteBuffer _writebuf{0};