Browse Source

HAL_ChibiOS: reduce the impact of UART DMA contention

this changes the heuristics for UART TX DMA allocation to greatly
reduce the chances of DMA contention causing long delays on other
devices

This fixes issues with FETTec driver output and gimbal status messages
as reported by Amilcar and OlliW. The problem is particularly bad when
no GPS is connected to GPS1 on fmuv3 and derived boards (such as
CubeBlack)

key changes:

 - remember the contention_counter across begin() calls, as the GPS
   calls begin with new baudrates regularly

 - added a is_shared() API to Shared_DMA, allowing the UART driver to
   avoid TX DMA on shared streams when at low baudrates.
gps-1.3.1
Andrew Tridgell 4 years ago
parent
commit
39f44147b8
  1. 44
      libraries/AP_HAL_ChibiOS/UARTDriver.cpp
  2. 10
      libraries/AP_HAL_ChibiOS/hwdef/scripts/dma_resolver.py
  3. 8
      libraries/AP_HAL_ChibiOS/shared_dma.cpp
  4. 3
      libraries/AP_HAL_ChibiOS/shared_dma.h

44
libraries/AP_HAL_ChibiOS/UARTDriver.cpp

@ -80,6 +80,13 @@ static const eventmask_t EVT_TRANSMIT_UNBUFFERED = EVENT_MASK(3); @@ -80,6 +80,13 @@ static const eventmask_t EVT_TRANSMIT_UNBUFFERED = EVENT_MASK(3);
#define HAL_UART_RX_STACK_SIZE 768
#endif
// threshold for disabling TX DMA due to contention
#if defined(USART_CR1_FIFOEN)
#define CONTENTION_BAUD_THRESHOLD 460800
#else
#define CONTENTION_BAUD_THRESHOLD 115200
#endif
UARTDriver::UARTDriver(uint8_t _serial_num) :
serial_num(_serial_num),
sdef(_serial_tab[_serial_num]),
@ -306,6 +313,15 @@ void UARTDriver::begin(uint32_t b, uint16_t rxS, uint16_t txS) @@ -306,6 +313,15 @@ void UARTDriver::begin(uint32_t b, uint16_t rxS, uint16_t txS)
rx_dma_enabled = rx_bounce_buf[0] != nullptr && rx_bounce_buf[1] != nullptr;
tx_dma_enabled = tx_bounce_buf != nullptr;
}
if (contention_counter > 1000 && _baudrate <= CONTENTION_BAUD_THRESHOLD) {
// we've previously disabled TX DMA due to contention, don't
// re-enable on a new begin() unless high baudrate
tx_dma_enabled = false;
}
if (_baudrate <= 115200 && sdef.dma_tx && Shared_DMA::is_shared(sdef.dma_tx_stream_id)) {
// avoid DMA on shared low-baudrate links
tx_dma_enabled = false;
}
#endif
#if defined(USART_CR1_FIFOEN)
@ -374,17 +390,20 @@ void UARTDriver::begin(uint32_t b, uint16_t rxS, uint16_t txS) @@ -374,17 +390,20 @@ void UARTDriver::begin(uint32_t b, uint16_t rxS, uint16_t txS)
dmaSetRequestSource(rxdma, sdef.dma_rx_channel_id);
#endif
}
if (tx_dma_enabled) {
// we only allow for sharing of the TX DMA channel, not the RX
// DMA channel, as the RX side is active all the time, so
// cannot be shared
dma_handle = new Shared_DMA(sdef.dma_tx_stream_id,
SHARED_DMA_NONE,
FUNCTOR_BIND_MEMBER(&UARTDriver::dma_tx_allocate, void, Shared_DMA *),
FUNCTOR_BIND_MEMBER(&UARTDriver::dma_tx_deallocate, void, Shared_DMA *));
}
_device_initialised = true;
}
if (tx_dma_enabled && dma_handle == nullptr) {
// we only allow for sharing of the TX DMA channel, not the RX
// DMA channel, as the RX side is active all the time, so
// cannot be shared
dma_handle = new Shared_DMA(sdef.dma_tx_stream_id,
SHARED_DMA_NONE,
FUNCTOR_BIND_MEMBER(&UARTDriver::dma_tx_allocate, void, Shared_DMA *),
FUNCTOR_BIND_MEMBER(&UARTDriver::dma_tx_deallocate, void, Shared_DMA *));
if (dma_handle == nullptr) {
tx_dma_enabled = false;
}
}
#endif // HAL_UART_NODMA
sercfg.speed = _baudrate;
@ -935,12 +954,7 @@ void UARTDriver::write_pending_bytes_DMA(uint32_t n) @@ -935,12 +954,7 @@ void UARTDriver::write_pending_bytes_DMA(uint32_t n)
if (dma_handle->has_contention()) {
// 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) {
if (_baudrate <= CONTENTION_BAUD_THRESHOLD) {
contention_counter += 3;
if (contention_counter > 1000) {
// more than 25% of attempts to use this DMA

10
libraries/AP_HAL_ChibiOS/hwdef/scripts/dma_resolver.py

@ -438,11 +438,15 @@ def write_dma_header(f, peripheral_list, mcu_type, dma_exclude=[], @@ -438,11 +438,15 @@ def write_dma_header(f, peripheral_list, mcu_type, dma_exclude=[],
for key in ordered_up_channels:
ordered_timers.append(key[0:-3])
shared_set = set()
for key in sorted(curr_dict.keys()):
stream = curr_dict[key]
shared = ''
if len(stream_assign[stream]) > 1:
shared = ' // shared %s' % ','.join(stream_assign[stream])
if stream[0] in [1,2]:
shared_set.add("(1U<<STM32_DMA_STREAM_ID(%u,%u))" % (stream[0],stream[1]))
if curr_dict[key] == "STM32_DMA_STREAM_ID_ANY":
f.write("#define %-30s STM32_DMA_STREAM_ID_ANY\n" % (chibios_dma_define_name(key)+'STREAM'))
f.write("#define %-30s %s\n" % (chibios_dma_define_name(key)+'CHAN', dmamux_channel(key)))
@ -486,6 +490,12 @@ def write_dma_header(f, peripheral_list, mcu_type, dma_exclude=[], @@ -486,6 +490,12 @@ def write_dma_header(f, peripheral_list, mcu_type, dma_exclude=[],
chan.replace('_UP', '_CH{}'.format(ch))))
break
f.write("\n// Mask of DMA streams which are shared\n")
if len(shared_set) == 0:
f.write("#define SHARED_DMA_MASK 0\n")
else:
f.write("#define SHARED_DMA_MASK (%s)\n" % '|'.join(list(shared_set)))
# now generate UARTDriver.cpp DMA config lines
f.write("\n\n// generated UART DMA configuration lines\n")
for u in range(1, 9):

8
libraries/AP_HAL_ChibiOS/shared_dma.cpp

@ -53,6 +53,14 @@ Shared_DMA::Shared_DMA(uint8_t _stream_id1, @@ -53,6 +53,14 @@ Shared_DMA::Shared_DMA(uint8_t _stream_id1,
deallocate = _deallocate;
}
/*
return true if a stream ID is shared between two peripherals
*/
bool Shared_DMA::is_shared(uint8_t stream_id)
{
return (stream_id < SHARED_DMA_MAX_STREAM_ID) && ((1U<<stream_id) & SHARED_DMA_MASK) != 0;
}
//remove any assigned deallocator or allocator
void Shared_DMA::unregister()
{

3
libraries/AP_HAL_ChibiOS/shared_dma.h

@ -67,6 +67,9 @@ public: @@ -67,6 +67,9 @@ public:
// display dma contention statistics as text buffer for @SYS/dma.txt
static void dma_info(ExpandingString &str);
// return true if a stream ID is shared between two peripherals
static bool is_shared(uint8_t stream_id);
private:
dma_allocate_fn_t allocate;
dma_allocate_fn_t deallocate;

Loading…
Cancel
Save