mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-23 09:08:30 -04:00
AP_HAL_ChibiOS:UARTDriver: allow re-defintion of RTS and CTS pins
This commit is contained in:
parent
eeb5dd3c96
commit
dc45a113f9
@ -924,8 +924,8 @@ void UARTDriver::write_pending_bytes_DMA(uint32_t n)
|
|||||||
|
|
||||||
while (n > 0) {
|
while (n > 0) {
|
||||||
if (_flow_control != FLOW_CONTROL_DISABLE &&
|
if (_flow_control != FLOW_CONTROL_DISABLE &&
|
||||||
sdef.cts_line != 0 &&
|
acts_line != 0 &&
|
||||||
palReadLine(sdef.cts_line)) {
|
palReadLine(acts_line)) {
|
||||||
// we are using hw flow control and the CTS line is high. We
|
// we are using hw flow control and the CTS line is high. We
|
||||||
// will hold off trying to transmit until the CTS line goes
|
// will hold off trying to transmit until the CTS line goes
|
||||||
// low to indicate the receiver has space. We do this before
|
// low to indicate the receiver has space. We do this before
|
||||||
@ -1349,7 +1349,7 @@ void UARTDriver::_tx_timer_tick(void)
|
|||||||
*/
|
*/
|
||||||
void UARTDriver::set_flow_control(enum flow_control flowcontrol)
|
void UARTDriver::set_flow_control(enum flow_control flowcontrol)
|
||||||
{
|
{
|
||||||
if (sdef.rts_line == 0 || sdef.is_usb) {
|
if (arts_line == 0 || sdef.is_usb) {
|
||||||
// no hw flow control available
|
// no hw flow control available
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
@ -1364,8 +1364,8 @@ void UARTDriver::set_flow_control(enum flow_control flowcontrol)
|
|||||||
|
|
||||||
case FLOW_CONTROL_DISABLE:
|
case FLOW_CONTROL_DISABLE:
|
||||||
// force RTS active when flow disabled
|
// force RTS active when flow disabled
|
||||||
palSetLineMode(sdef.rts_line, 1);
|
palSetLineMode(arts_line, 1);
|
||||||
palClearLine(sdef.rts_line);
|
palClearLine(arts_line);
|
||||||
_rts_is_active = true;
|
_rts_is_active = true;
|
||||||
// disable hardware CTS support
|
// disable hardware CTS support
|
||||||
chSysLock();
|
chSysLock();
|
||||||
@ -1386,8 +1386,8 @@ void UARTDriver::set_flow_control(enum flow_control flowcontrol)
|
|||||||
case FLOW_CONTROL_ENABLE:
|
case FLOW_CONTROL_ENABLE:
|
||||||
// we do RTS in software as STM32 hardware RTS support toggles
|
// we do RTS in software as STM32 hardware RTS support toggles
|
||||||
// the pin for every byte which loses a lot of bandwidth
|
// the pin for every byte which loses a lot of bandwidth
|
||||||
palSetLineMode(sdef.rts_line, 1);
|
palSetLineMode(arts_line, 1);
|
||||||
palClearLine(sdef.rts_line);
|
palClearLine(arts_line);
|
||||||
_rts_is_active = true;
|
_rts_is_active = true;
|
||||||
// enable hardware CTS support, disable RTS support as we do that in software
|
// enable hardware CTS support, disable RTS support as we do that in software
|
||||||
chSysLock();
|
chSysLock();
|
||||||
@ -1410,16 +1410,16 @@ void UARTDriver::set_flow_control(enum flow_control flowcontrol)
|
|||||||
*/
|
*/
|
||||||
void UARTDriver::update_rts_line(void)
|
void UARTDriver::update_rts_line(void)
|
||||||
{
|
{
|
||||||
if (sdef.rts_line == 0 || _flow_control == FLOW_CONTROL_DISABLE) {
|
if (arts_line == 0 || _flow_control == FLOW_CONTROL_DISABLE) {
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
uint16_t space = _readbuf.space();
|
uint16_t space = _readbuf.space();
|
||||||
if (_rts_is_active && space < 16) {
|
if (_rts_is_active && space < 16) {
|
||||||
_rts_is_active = false;
|
_rts_is_active = false;
|
||||||
palSetLine(sdef.rts_line);
|
palSetLine(arts_line);
|
||||||
} else if (!_rts_is_active && space > 32) {
|
} else if (!_rts_is_active && space > 32) {
|
||||||
_rts_is_active = true;
|
_rts_is_active = true;
|
||||||
palClearLine(sdef.rts_line);
|
palClearLine(arts_line);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -1605,13 +1605,17 @@ bool UARTDriver::set_options(uint16_t options)
|
|||||||
|
|
||||||
#ifdef HAL_PIN_ALT_CONFIG
|
#ifdef HAL_PIN_ALT_CONFIG
|
||||||
/*
|
/*
|
||||||
allow for RX and TX pins to be remapped via BRD_ALT_CONFIG
|
allow for RX, TX, RTS and CTS pins to be remapped via BRD_ALT_CONFIG
|
||||||
*/
|
*/
|
||||||
arx_line = GPIO::resolve_alt_config(sdef.rx_line, PERIPH_TYPE::UART_RX, sdef.instance);
|
arx_line = GPIO::resolve_alt_config(sdef.rx_line, PERIPH_TYPE::UART_RX, sdef.instance);
|
||||||
atx_line = GPIO::resolve_alt_config(sdef.tx_line, PERIPH_TYPE::UART_TX, sdef.instance);
|
atx_line = GPIO::resolve_alt_config(sdef.tx_line, PERIPH_TYPE::UART_TX, sdef.instance);
|
||||||
|
arts_line = GPIO::resolve_alt_config(sdef.rts_line, PERIPH_TYPE::OTHER, sdef.instance);
|
||||||
|
acts_line = GPIO::resolve_alt_config(sdef.cts_line, PERIPH_TYPE::OTHER, sdef.instance);
|
||||||
#else
|
#else
|
||||||
arx_line = sdef.rx_line;
|
arx_line = sdef.rx_line;
|
||||||
atx_line = sdef.tx_line;
|
atx_line = sdef.tx_line;
|
||||||
|
arts_line = sdef.rts_line;
|
||||||
|
acts_line = sdef.cts_line;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if defined(STM32F7) || defined(STM32H7) || defined(STM32F3) || defined(STM32G4) || defined(STM32L4)
|
#if defined(STM32F7) || defined(STM32H7) || defined(STM32F3) || defined(STM32G4) || defined(STM32L4)
|
||||||
@ -1765,12 +1769,12 @@ bool UARTDriver::set_CTS_pin(bool high)
|
|||||||
// CTS pin is being used
|
// CTS pin is being used
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
if (sdef.cts_line == 0) {
|
if (acts_line == 0) {
|
||||||
// we don't have a CTS pin on this UART
|
// we don't have a CTS pin on this UART
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
palSetLineMode(sdef.cts_line, 1);
|
palSetLineMode(acts_line, 1);
|
||||||
palWriteLine(sdef.cts_line, high?1:0);
|
palWriteLine(acts_line, high?1:0);
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -1784,12 +1788,12 @@ bool UARTDriver::set_RTS_pin(bool high)
|
|||||||
// RTS pin is being used
|
// RTS pin is being used
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
if (sdef.rts_line == 0) {
|
if (arts_line == 0) {
|
||||||
// we don't have a RTS pin on this UART
|
// we don't have a RTS pin on this UART
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
palSetLineMode(sdef.rts_line, 1);
|
palSetLineMode(arts_line, 1);
|
||||||
palWriteLine(sdef.rts_line, high?1:0);
|
palWriteLine(arts_line, high?1:0);
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -152,10 +152,12 @@ private:
|
|||||||
bool tx_dma_enabled;
|
bool tx_dma_enabled;
|
||||||
|
|
||||||
/*
|
/*
|
||||||
copy of rx_line and tx_line with alternative configs resolved
|
copy of rx_line, tx_line, rts_line and cts_line with alternative configs resolved
|
||||||
*/
|
*/
|
||||||
ioline_t atx_line;
|
ioline_t atx_line;
|
||||||
ioline_t arx_line;
|
ioline_t arx_line;
|
||||||
|
ioline_t arts_line;
|
||||||
|
ioline_t acts_line;
|
||||||
|
|
||||||
// thread used for all UARTs
|
// thread used for all UARTs
|
||||||
static thread_t* volatile uart_rx_thread_ctx;
|
static thread_t* volatile uart_rx_thread_ctx;
|
||||||
|
Loading…
Reference in New Issue
Block a user