Browse Source

HAL_ChibiOS: added half-duplex protection for non-inverted

to prevent output bytes being seen as input bytes we disable half
duplex during transmit. This was previously only done for non-inverted
UARTs. This patch enables it whether we are inverted or not. This
greatly reduces the number of bad input bytes.
c415-sdk
Andrew Tridgell 5 years ago
parent
commit
fc0b2ef920
  1. 20
      libraries/AP_HAL_ChibiOS/UARTDriver.cpp

20
libraries/AP_HAL_ChibiOS/UARTDriver.cpp

@ -929,12 +929,10 @@ void UARTDriver::half_duplex_setup_tx(void)
if (!hd_tx_active) { if (!hd_tx_active) {
chEvtGetAndClearFlags(&hd_listener); chEvtGetAndClearFlags(&hd_listener);
hd_tx_active = true; hd_tx_active = true;
if (_last_options & (OPTION_RXINV | OPTION_TXINV)) { SerialDriver *sd = (SerialDriver*)(sdef.serial);
SerialDriver *sd = (SerialDriver*)(sdef.serial); sdStop(sd);
sdStop(sd); sercfg.cr3 &= ~USART_CR3_HDSEL;
sercfg.cr3 &= ~USART_CR3_HDSEL; sdStart(sd, &sercfg);
sdStart(sd, &sercfg);
}
} }
#endif #endif
} }
@ -955,12 +953,10 @@ void UARTDriver::_timer_tick(void)
half-duplex transmit has finished. We now re-enable the half-duplex transmit has finished. We now re-enable the
HDSEL bit for receive HDSEL bit for receive
*/ */
if (_last_options & (OPTION_RXINV | OPTION_TXINV)) { SerialDriver *sd = (SerialDriver*)(sdef.serial);
SerialDriver *sd = (SerialDriver*)(sdef.serial); sdStop(sd);
sdStop(sd); sercfg.cr3 |= USART_CR3_HDSEL;
sercfg.cr3 |= USART_CR3_HDSEL; sdStart(sd, &sercfg);
sdStart(sd, &sercfg);
}
hd_tx_active = false; hd_tx_active = false;
} }
#endif #endif

Loading…
Cancel
Save