mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-21 16:18:29 -04:00
HAL_ChibiOS: prevent hw flow control from hogging a DMA channel
When hw flow control is enabled check the CTS pin before we grab the DMA channel to prevent a long timeout trying to send to a blocked port from holding a DMA channel against another device this fixes issue #16587
This commit is contained in:
parent
ee8e9e3289
commit
9de1519928
@ -829,6 +829,19 @@ void UARTDriver::write_pending_bytes_DMA(uint32_t n)
|
||||
if (tx_len == 0) {
|
||||
return;
|
||||
}
|
||||
|
||||
if (_flow_control != FLOW_CONTROL_DISABLE &&
|
||||
sdef.cts_line != 0 &&
|
||||
palReadLine(sdef.cts_line)) {
|
||||
// we are using hw flow control and the CTS line is high. We
|
||||
// will hold off trying to transmit until the CTS line goes
|
||||
// low to indicate the receiver has space. We do this before
|
||||
// we take the DMA lock to prevent a high CTS line holding a
|
||||
// DMA channel that may be needed by another device
|
||||
tx_len = 0;
|
||||
return;
|
||||
}
|
||||
|
||||
if (!dma_handle->lock_nonblock()) {
|
||||
tx_len = 0;
|
||||
return;
|
||||
|
@ -81,6 +81,7 @@ public:
|
||||
ioline_t tx_line;
|
||||
ioline_t rx_line;
|
||||
ioline_t rts_line;
|
||||
ioline_t cts_line;
|
||||
int8_t rxinv_gpio;
|
||||
uint8_t rxinv_polarity;
|
||||
int8_t txinv_gpio;
|
||||
|
@ -1214,6 +1214,7 @@ def write_UART_config(f):
|
||||
tx_line = make_line(dev + '_TX')
|
||||
rx_line = make_line(dev + '_RX')
|
||||
rts_line = make_line(dev + '_RTS')
|
||||
cts_line = make_line(dev + '_CTS')
|
||||
if rts_line != "0":
|
||||
have_rts_cts = True
|
||||
f.write('#define HAL_HAVE_RTSCTS_SERIAL%u\n' % uart_serial_num[dev])
|
||||
@ -1234,10 +1235,10 @@ def write_UART_config(f):
|
||||
"#define HAL_%s_CONFIG { (BaseSequentialStream*) &SD%u, %u, false, "
|
||||
% (dev, n, n))
|
||||
if mcu_series.startswith("STM32F1"):
|
||||
f.write("%s, %s, %s, " % (tx_line, rx_line, rts_line))
|
||||
f.write("%s, %s, %s, %s, " % (tx_line, rx_line, rts_line, cts_line))
|
||||
else:
|
||||
f.write("STM32_%s_RX_DMA_CONFIG, STM32_%s_TX_DMA_CONFIG, %s, %s, %s, " %
|
||||
(dev, dev, tx_line, rx_line, rts_line))
|
||||
f.write("STM32_%s_RX_DMA_CONFIG, STM32_%s_TX_DMA_CONFIG, %s, %s, %s, %s, " %
|
||||
(dev, dev, tx_line, rx_line, rts_line, cts_line))
|
||||
|
||||
# add inversion pins, if any
|
||||
f.write("%d, " % get_gpio_bylabel(dev + "_RXINV"))
|
||||
|
Loading…
Reference in New Issue
Block a user