Browse Source

AP_HAL_ChibiOS: only setup half-duplex for receive when transmit is fully over

c415-sdk
Andy Piper 4 years ago committed by Andrew Tridgell
parent
commit
4c2cbdab8d
  1. 16
      libraries/AP_HAL_ChibiOS/UARTDriver.cpp
  2. 2
      libraries/AP_HAL_ChibiOS/UARTDriver.h

16
libraries/AP_HAL_ChibiOS/UARTDriver.cpp

@ -1001,7 +1001,9 @@ void UARTDriver::half_duplex_setup_tx(void) @@ -1001,7 +1001,9 @@ void UARTDriver::half_duplex_setup_tx(void)
#ifdef HAVE_USB_SERIAL
if (!hd_tx_active) {
chEvtGetAndClearFlags(&hd_listener);
hd_tx_active = true;
// half-duplex transmission is done when both the output is empty and the transmission is ended
// if we only wait for empty output the line can be setup for receive too soon losing data bits
hd_tx_active = CHN_TRANSMISSION_END | CHN_OUTPUT_EMPTY;
SerialDriver *sd = (SerialDriver*)(sdef.serial);
sdStop(sd);
sercfg.cr3 &= ~USART_CR3_HDSEL;
@ -1021,7 +1023,9 @@ void UARTDriver::_timer_tick(void) @@ -1021,7 +1023,9 @@ void UARTDriver::_timer_tick(void)
if (!_initialised) return;
#ifdef HAVE_USB_SERIAL
if (hd_tx_active && (chEvtGetAndClearFlags(&hd_listener) & CHN_OUTPUT_EMPTY) != 0) {
if (hd_tx_active) {
hd_tx_active &= ~chEvtGetAndClearFlags(&hd_listener);
if (!hd_tx_active) {
/*
half-duplex transmit has finished. We now re-enable the
HDSEL bit for receive
@ -1030,7 +1034,7 @@ void UARTDriver::_timer_tick(void) @@ -1030,7 +1034,7 @@ void UARTDriver::_timer_tick(void)
sdStop(sd);
sercfg.cr3 |= USART_CR3_HDSEL;
sdStart(sd, &sercfg);
hd_tx_active = false;
}
}
#endif
@ -1427,6 +1431,7 @@ bool UARTDriver::set_options(uint16_t options) @@ -1427,6 +1431,7 @@ bool UARTDriver::set_options(uint16_t options)
}
} else {
cr2 &= ~USART_CR2_RXINV;
_cr2_options &= ~USART_CR2_RXINV;
if (rx_line != 0) {
palLineSetPushPull(rx_line, PAL_PUSHPULL_PULLUP);
}
@ -1439,6 +1444,7 @@ bool UARTDriver::set_options(uint16_t options) @@ -1439,6 +1444,7 @@ bool UARTDriver::set_options(uint16_t options)
}
} else {
cr2 &= ~USART_CR2_TXINV;
_cr2_options &= ~USART_CR2_TXINV;
if (tx_line != 0) {
palLineSetPushPull(tx_line, PAL_PUSHPULL_PULLUP);
}
@ -1449,6 +1455,7 @@ bool UARTDriver::set_options(uint16_t options) @@ -1449,6 +1455,7 @@ bool UARTDriver::set_options(uint16_t options)
_cr2_options |= USART_CR2_SWAP;
} else {
cr2 &= ~USART_CR2_SWAP;
_cr2_options &= ~USART_CR2_SWAP;
}
#else // STM32F4
// F4 can do inversion by GPIO if enabled in hwdef.dat, using
@ -1480,7 +1487,7 @@ bool UARTDriver::set_options(uint16_t options) @@ -1480,7 +1487,7 @@ bool UARTDriver::set_options(uint16_t options)
chEvtRegisterMaskWithFlags(chnGetEventSource((SerialDriver*)sdef.serial),
&hd_listener,
EVT_TRANSMIT_END,
CHN_OUTPUT_EMPTY);
CHN_OUTPUT_EMPTY | CHN_TRANSMISSION_END);
half_duplex = true;
}
#ifndef HAL_UART_NODMA
@ -1493,6 +1500,7 @@ bool UARTDriver::set_options(uint16_t options) @@ -1493,6 +1500,7 @@ bool UARTDriver::set_options(uint16_t options)
rx_dma_enabled = tx_dma_enabled = false;
} else {
cr3 &= ~USART_CR3_HDSEL;
_cr3_options &= ~USART_CR3_HDSEL;
}
set_pushpull(options);

2
libraries/AP_HAL_ChibiOS/UARTDriver.h

@ -209,7 +209,7 @@ private: @@ -209,7 +209,7 @@ private:
#if CH_CFG_USE_EVENTS == TRUE
bool half_duplex;
event_listener_t hd_listener;
bool hd_tx_active;
eventflags_t hd_tx_active;
void half_duplex_setup_tx(void);
#endif

Loading…
Cancel
Save