HAL_ChibiOS: disable DMA on high contention UARTs

switch to interrupt driven when in high contention
This commit is contained in:
Andrew Tridgell 2020-06-16 18:28:40 +10:00
parent f7da853adb
commit 47a5d78397
2 changed files with 13 additions and 0 deletions

View File

@ -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();

View File

@ -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};