Skip to content

Commit

Permalink
HAL_ChibiOS: raise DMA contention threshold for H7
Browse files Browse the repository at this point in the history
  • Loading branch information
tridge committed Jul 7, 2021
1 parent 696993e commit 34aaa5e
Showing 1 changed file with 7 additions and 1 deletion.
8 changes: 7 additions & 1 deletion libraries/AP_HAL_ChibiOS/UARTDriver.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down

0 comments on commit 34aaa5e

Please sign in to comment.