diff --git a/libraries/AP_HAL_ChibiOS/UARTDriver.cpp b/libraries/AP_HAL_ChibiOS/UARTDriver.cpp index 9df9e0eb0b..9308abc568 100644 --- a/libraries/AP_HAL_ChibiOS/UARTDriver.cpp +++ b/libraries/AP_HAL_ChibiOS/UARTDriver.cpp @@ -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,16 +1023,18 @@ void UARTDriver::_timer_tick(void) if (!_initialised) return; #ifdef HAVE_USB_SERIAL - if (hd_tx_active && (chEvtGetAndClearFlags(&hd_listener) & CHN_OUTPUT_EMPTY) != 0) { - /* - half-duplex transmit has finished. We now re-enable the - HDSEL bit for receive - */ - SerialDriver *sd = (SerialDriver*)(sdef.serial); - sdStop(sd); - sercfg.cr3 |= USART_CR3_HDSEL; - sdStart(sd, &sercfg); - hd_tx_active = false; + 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 + */ + SerialDriver *sd = (SerialDriver*)(sdef.serial); + sdStop(sd); + sercfg.cr3 |= USART_CR3_HDSEL; + sdStart(sd, &sercfg); + } } #endif @@ -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) } } 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) _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) 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) rx_dma_enabled = tx_dma_enabled = false; } else { cr3 &= ~USART_CR3_HDSEL; + _cr3_options &= ~USART_CR3_HDSEL; } set_pushpull(options); diff --git a/libraries/AP_HAL_ChibiOS/UARTDriver.h b/libraries/AP_HAL_ChibiOS/UARTDriver.h index 6c05725c95..e6d08a5a50 100644 --- a/libraries/AP_HAL_ChibiOS/UARTDriver.h +++ b/libraries/AP_HAL_ChibiOS/UARTDriver.h @@ -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