Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

HAL_ChibiOS: reduce the impact of UART DMA contention #18481

Merged
merged 2 commits into from
Aug 30, 2021
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Jump to
Jump to file
Failed to load files.
Diff view
Diff view
44 changes: 29 additions & 15 deletions libraries/AP_HAL_ChibiOS/UARTDriver.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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]),
Expand Down Expand Up @@ -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)) {
tridge marked this conversation as resolved.
Show resolved Hide resolved
Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

If the only thing you are sharing with is other UART TX's then I think this means that none of them get DMA. It would be good to make sure that the channel is at least used.

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

true, but fairly tricky to organise. I think this is a worthwhile step in the right direction

// avoid DMA on shared low-baudrate links
tx_dma_enabled = false;
}
#endif

#if defined(USART_CR1_FIFOEN)
Expand Down Expand Up @@ -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;

Expand Down Expand Up @@ -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
Expand Down
10 changes: 10 additions & 0 deletions libraries/AP_HAL_ChibiOS/hwdef/scripts/dma_resolver.py
Original file line number Diff line number Diff line change
Expand Up @@ -438,11 +438,15 @@ def order_by_streamid(key):
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)))
Expand Down Expand Up @@ -486,6 +490,12 @@ def order_by_streamid(key):
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):
Expand Down
8 changes: 8 additions & 0 deletions libraries/AP_HAL_ChibiOS/shared_dma.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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()
{
Expand Down
3 changes: 3 additions & 0 deletions libraries/AP_HAL_ChibiOS/shared_dma.h
Original file line number Diff line number Diff line change
Expand Up @@ -67,6 +67,9 @@ class ChibiOS::Shared_DMA
// 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;
Expand Down
2 changes: 1 addition & 1 deletion libraries/GCS_MAVLink/GCS_MAVLink.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -90,7 +90,7 @@ uint16_t comm_get_txspace(mavlink_channel_t chan)
*/
void comm_send_buffer(mavlink_channel_t chan, const uint8_t *buf, uint8_t len)
{
if (!valid_channel(chan)) {
if (!valid_channel(chan) || mavlink_comm_port[chan] == nullptr) {
return;
}
if (gcs_alternative_active[chan]) {
Expand Down