Skip to content

Commit

Permalink
Check tx on MSP and GPS only
Browse files Browse the repository at this point in the history
  • Loading branch information
SteveCEvans committed Sep 29, 2023
1 parent 66bf029 commit 26522a7
Show file tree
Hide file tree
Showing 7 changed files with 15 additions and 5 deletions.
3 changes: 3 additions & 0 deletions src/main/drivers/serial.h
Original file line number Diff line number Diff line change
Expand Up @@ -55,6 +55,9 @@ typedef enum {
SERIAL_BIDIR_PP = 1 << 4,
SERIAL_BIDIR_NOPULL = 1 << 5, // disable pulls in BIDIR RX mode
SERIAL_BIDIR_PP_PD = 1 << 6, // PP mode, normall inverted, but with PullDowns, to fix SA after bidir issue fixed (#10220)

// If this option is set then switch the TX line to input when not in use to detect it being pulled low
SERIAL_CHECK_TX = 1 << 7,
} portOptions_e;

// Define known line control states which may be passed up by underlying serial driver callback
Expand Down
2 changes: 1 addition & 1 deletion src/main/drivers/stm32/serial_uart_stm32f4xx.c
Original file line number Diff line number Diff line change
Expand Up @@ -342,7 +342,7 @@ uartPort_t *serialUART(UARTDevice_e device, uint32_t baudRate, portMode_e mode,
if ((mode & MODE_TX) && txIO) {
IOInit(txIO, OWNER_SERIAL_TX, RESOURCE_INDEX(device));

if (((options & SERIAL_INVERTED) == SERIAL_NOT_INVERTED) && !(options & SERIAL_BIDIR_PP_PD)) {
if (options & SERIAL_CHECK_TX) {
uart->txPinState = TX_PIN_ACTIVE;
// Switch TX to an input with pullup so it's state can be monitored
uartTxMonitor(s);
Expand Down
2 changes: 1 addition & 1 deletion src/main/drivers/stm32/serial_uart_stm32f7xx.c
Original file line number Diff line number Diff line change
Expand Up @@ -376,7 +376,7 @@ uartPort_t *serialUART(UARTDevice_e device, uint32_t baudRate, portMode_e mode,
if ((mode & MODE_TX) && txIO) {
IOInit(txIO, OWNER_SERIAL_TX, RESOURCE_INDEX(device));

if (((options & SERIAL_INVERTED) == SERIAL_NOT_INVERTED) && !(options & SERIAL_BIDIR_PP_PD)) {
if (options & SERIAL_CHECK_TX) {
uartdev->txPinState = TX_PIN_MONITOR;
// Switch TX to UART output whilst UART sends idle preamble
checkUsartTxOutput(s);
Expand Down
2 changes: 1 addition & 1 deletion src/main/drivers/stm32/serial_uart_stm32g4xx.c
Original file line number Diff line number Diff line change
Expand Up @@ -309,7 +309,7 @@ uartPort_t *serialUART(UARTDevice_e device, uint32_t baudRate, portMode_e mode,
if ((mode & MODE_TX) && txIO) {
IOInit(txIO, OWNER_SERIAL_TX, RESOURCE_INDEX(device));

if (((options & SERIAL_INVERTED) == SERIAL_NOT_INVERTED) && !(options & SERIAL_BIDIR_PP_PD)) {
if (options & SERIAL_CHECK_TX) {
uartdev->txPinState = TX_PIN_ACTIVE;
// Switch TX to an input with pullup so it's state can be monitored
uartTxMonitor(s);
Expand Down
2 changes: 1 addition & 1 deletion src/main/drivers/stm32/serial_uart_stm32h7xx.c
Original file line number Diff line number Diff line change
Expand Up @@ -486,7 +486,7 @@ uartPort_t *serialUART(UARTDevice_e device, uint32_t baudRate, portMode_e mode,
if ((mode & MODE_TX) && txIO) {
IOInit(txIO, OWNER_SERIAL_TX, RESOURCE_INDEX(device));

if (((options & SERIAL_INVERTED) == SERIAL_NOT_INVERTED) && !(options & SERIAL_BIDIR_PP_PD)) {
if (options & SERIAL_CHECK_TX) {
uartdev->txPinState = TX_PIN_ACTIVE;
// Switch TX to an input with pullup so it's state can be monitored
uartTxMonitor(s);
Expand Down
7 changes: 6 additions & 1 deletion src/main/io/gps.c
Original file line number Diff line number Diff line change
Expand Up @@ -435,15 +435,20 @@ void gpsInit(void)
gpsData.tempBaudRateIndex = gpsData.userBaudRateIndex;

portMode_e mode = MODE_RXTX;
portOptions_e options = SERIAL_NOT_INVERTED;

#if defined(GPS_NMEA_TX_ONLY)
if (gpsConfig()->provider == GPS_NMEA) {
mode &= ~MODE_TX;
}
#endif

if ((gpsPortConfig->identifier >= SERIAL_PORT_USART1) && (gpsPortConfig->identifier <= SERIAL_PORT_USART_MAX)){
options |= SERIAL_CHECK_TX;
}

// no callback - buffer will be consumed in gpsUpdate()
gpsPort = openSerialPort(gpsPortConfig->identifier, FUNCTION_GPS, NULL, NULL, baudRates[gpsInitData[gpsData.userBaudRateIndex].baudrateIndex], mode, SERIAL_NOT_INVERTED);
gpsPort = openSerialPort(gpsPortConfig->identifier, FUNCTION_GPS, NULL, NULL, baudRates[gpsInitData[gpsData.userBaudRateIndex].baudrateIndex], mode, options);
if (!gpsPort) {
return;
}
Expand Down
2 changes: 2 additions & 0 deletions src/main/msp/msp_serial.c
Original file line number Diff line number Diff line change
Expand Up @@ -69,6 +69,8 @@ void mspSerialAllocatePorts(void)

if (mspConfig()->halfDuplex) {
options |= SERIAL_BIDIR;
} else if ((portConfig->identifier >= SERIAL_PORT_USART1) && (portConfig->identifier <= SERIAL_PORT_USART_MAX)){
options |= SERIAL_CHECK_TX;
}

serialPort_t *serialPort = openSerialPort(portConfig->identifier, FUNCTION_MSP, NULL, NULL, baudRates[portConfig->msp_baudrateIndex], MODE_RXTX, options);
Expand Down

0 comments on commit 26522a7

Please sign in to comment.