HAL_ChibiOS: raise DMA contention threshold for H7

This commit is contained in:
Andrew Tridgell 2021-07-08 09:00:43 +10:00 committed by Randy Mackay
parent aab77f7046
commit 4218452475
1 changed files with 7 additions and 1 deletions

View File

@ -909,7 +909,13 @@ void UARTDriver::write_pending_bytes_DMA(uint32_t n)
chEvtGetAndClearEvents(EVT_TRANSMIT_DMA_COMPLETE);
if (dma_handle->has_contention()) {
if (_baudrate <= 115200) {
// on boards with a hw fifo we can use a higher threshold for disabling DMA
#if defined(USART_CR1_FIFOEN)
const uint32_t baud_threshold = 460800;
#else
const uint32_t baud_threshold = 115200;
#endif
if (_baudrate <= baud_threshold) {
contention_counter += 3;
if (contention_counter > 1000) {
// more than 25% of attempts to use this DMA