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

This commit is contained in:
Andy Piper 2021-01-31 16:13:34 +00:00 committed by Andrew Tridgell
parent 5c32007cdf
commit 4c2cbdab8d
2 changed files with 21 additions and 13 deletions

View File

@ -1001,7 +1001,9 @@ void UARTDriver::half_duplex_setup_tx(void)
#ifdef HAVE_USB_SERIAL #ifdef HAVE_USB_SERIAL
if (!hd_tx_active) { if (!hd_tx_active) {
chEvtGetAndClearFlags(&hd_listener); 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); SerialDriver *sd = (SerialDriver*)(sdef.serial);
sdStop(sd); sdStop(sd);
sercfg.cr3 &= ~USART_CR3_HDSEL; sercfg.cr3 &= ~USART_CR3_HDSEL;
@ -1021,16 +1023,18 @@ void UARTDriver::_timer_tick(void)
if (!_initialised) return; if (!_initialised) return;
#ifdef HAVE_USB_SERIAL #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);
half-duplex transmit has finished. We now re-enable the if (!hd_tx_active) {
HDSEL bit for receive /*
*/ half-duplex transmit has finished. We now re-enable the
SerialDriver *sd = (SerialDriver*)(sdef.serial); HDSEL bit for receive
sdStop(sd); */
sercfg.cr3 |= USART_CR3_HDSEL; SerialDriver *sd = (SerialDriver*)(sdef.serial);
sdStart(sd, &sercfg); sdStop(sd);
hd_tx_active = false; sercfg.cr3 |= USART_CR3_HDSEL;
sdStart(sd, &sercfg);
}
} }
#endif #endif
@ -1427,6 +1431,7 @@ bool UARTDriver::set_options(uint16_t options)
} }
} else { } else {
cr2 &= ~USART_CR2_RXINV; cr2 &= ~USART_CR2_RXINV;
_cr2_options &= ~USART_CR2_RXINV;
if (rx_line != 0) { if (rx_line != 0) {
palLineSetPushPull(rx_line, PAL_PUSHPULL_PULLUP); palLineSetPushPull(rx_line, PAL_PUSHPULL_PULLUP);
} }
@ -1439,6 +1444,7 @@ bool UARTDriver::set_options(uint16_t options)
} }
} else { } else {
cr2 &= ~USART_CR2_TXINV; cr2 &= ~USART_CR2_TXINV;
_cr2_options &= ~USART_CR2_TXINV;
if (tx_line != 0) { if (tx_line != 0) {
palLineSetPushPull(tx_line, PAL_PUSHPULL_PULLUP); palLineSetPushPull(tx_line, PAL_PUSHPULL_PULLUP);
} }
@ -1449,6 +1455,7 @@ bool UARTDriver::set_options(uint16_t options)
_cr2_options |= USART_CR2_SWAP; _cr2_options |= USART_CR2_SWAP;
} else { } else {
cr2 &= ~USART_CR2_SWAP; cr2 &= ~USART_CR2_SWAP;
_cr2_options &= ~USART_CR2_SWAP;
} }
#else // STM32F4 #else // STM32F4
// F4 can do inversion by GPIO if enabled in hwdef.dat, using // F4 can do inversion by GPIO if enabled in hwdef.dat, using
@ -1480,7 +1487,7 @@ bool UARTDriver::set_options(uint16_t options)
chEvtRegisterMaskWithFlags(chnGetEventSource((SerialDriver*)sdef.serial), chEvtRegisterMaskWithFlags(chnGetEventSource((SerialDriver*)sdef.serial),
&hd_listener, &hd_listener,
EVT_TRANSMIT_END, EVT_TRANSMIT_END,
CHN_OUTPUT_EMPTY); CHN_OUTPUT_EMPTY | CHN_TRANSMISSION_END);
half_duplex = true; half_duplex = true;
} }
#ifndef HAL_UART_NODMA #ifndef HAL_UART_NODMA
@ -1493,6 +1500,7 @@ bool UARTDriver::set_options(uint16_t options)
rx_dma_enabled = tx_dma_enabled = false; rx_dma_enabled = tx_dma_enabled = false;
} else { } else {
cr3 &= ~USART_CR3_HDSEL; cr3 &= ~USART_CR3_HDSEL;
_cr3_options &= ~USART_CR3_HDSEL;
} }
set_pushpull(options); set_pushpull(options);

View File

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