diff --git a/src/main/blackbox/blackbox_io.c b/src/main/blackbox/blackbox_io.c index ddf9c5905..ffc1df7f6 100644 --- a/src/main/blackbox/blackbox_io.c +++ b/src/main/blackbox/blackbox_io.c @@ -62,6 +62,8 @@ #ifdef BLACKBOX +#define BLACKBOX_SERIAL_PORT_MODE MODE_TX + // How many bytes should we transmit per loop iteration? uint8_t blackboxWriteChunkSize = 16; @@ -446,7 +448,7 @@ bool blackboxDeviceOpen(void) { serialPortConfig_t *portConfig = findSerialPortConfig(FUNCTION_BLACKBOX); baudRate_e baudRateIndex; - portMode_t portMode; + portOptions_t portOptions = SERIAL_PARITY_NO | SERIAL_NOT_INVERTED; if (!portConfig) { return false; @@ -455,18 +457,18 @@ bool blackboxDeviceOpen(void) blackboxPortSharing = determinePortSharing(portConfig, FUNCTION_BLACKBOX); baudRateIndex = portConfig->blackbox_baudrateIndex; - portMode = MODE_TX; - if (baudRates[baudRateIndex] == 230400) { /* * OpenLog's 230400 baud rate is very inaccurate, so it requires a larger inter-character gap in * order to maintain synchronization. */ - portMode |= MODE_STOPBITS2; + portOptions |= SERIAL_STOPBITS_2; + } else { + portOptions |= SERIAL_STOPBITS_1; } blackboxPort = openSerialPort(portConfig->identifier, FUNCTION_BLACKBOX, NULL, baudRates[baudRateIndex], - portMode, SERIAL_NOT_INVERTED); + BLACKBOX_SERIAL_PORT_MODE, portOptions); return blackboxPort != NULL; } diff --git a/src/main/config/config.c b/src/main/config/config.c index 50f02873b..90a8b9fd3 100644 --- a/src/main/config/config.c +++ b/src/main/config/config.c @@ -220,7 +220,7 @@ void resetFlight3DConfig(flight3DConfig_t *flight3DConfig) void resetTelemetryConfig(telemetryConfig_t *telemetryConfig) { - telemetryConfig->telemetry_inversion = SERIAL_NOT_INVERTED; + telemetryConfig->telemetry_inversion = 0; telemetryConfig->telemetry_switch = 0; telemetryConfig->gpsNoFixLatitude = 0; telemetryConfig->gpsNoFixLongitude = 0; diff --git a/src/main/drivers/serial.h b/src/main/drivers/serial.h index a6d6836ab..925fb3804 100644 --- a/src/main/drivers/serial.h +++ b/src/main/drivers/serial.h @@ -17,20 +17,22 @@ #pragma once -typedef enum { - SERIAL_NOT_INVERTED = 0, - SERIAL_INVERTED -} serialInversion_e; - typedef enum portMode_t { MODE_RX = 1 << 0, MODE_TX = 1 << 1, MODE_RXTX = MODE_RX | MODE_TX, - MODE_SBUS = 1 << 2, - MODE_BIDIR = 1 << 3, - MODE_STOPBITS2 = 1 << 4, + MODE_BIDIR = 1 << 3 } portMode_t; +typedef enum portOptions_t { + SERIAL_NOT_INVERTED = 0 << 0, + SERIAL_INVERTED = 1 << 0, + SERIAL_STOPBITS_1 = 0 << 1, + SERIAL_STOPBITS_2 = 1 << 1, + SERIAL_PARITY_NO = 0 << 2, + SERIAL_PARITY_EVEN = 1 << 2, +} portOptions_t; + typedef void (*serialReceiveCallbackPtr)(uint16_t data); // used by serial drivers to return frames to app typedef struct serialPort { @@ -39,7 +41,8 @@ typedef struct serialPort { uint8_t identifier; portMode_t mode; - serialInversion_e inversion; + portOptions_t options; + uint32_t baudRate; uint32_t rxBufferSize; diff --git a/src/main/drivers/serial_softserial.c b/src/main/drivers/serial_softserial.c index 82a0eb468..e24d76589 100644 --- a/src/main/drivers/serial_softserial.c +++ b/src/main/drivers/serial_softserial.c @@ -52,7 +52,7 @@ void onSerialRxPinChange(timerCCHandlerRec_t *cbRec, captureCompare_t capture); void setTxSignal(softSerial_t *softSerial, uint8_t state) { - if (softSerial->port.inversion == SERIAL_INVERTED) { + if ((softSerial->port.options & SERIAL_INVERTED) == SERIAL_INVERTED) { state = !state; } @@ -119,10 +119,10 @@ static void serialICConfig(TIM_TypeDef *tim, uint8_t channel, uint16_t polarity) TIM_ICInit(tim, &TIM_ICInitStructure); } -static void serialTimerRxConfig(const timerHardware_t *timerHardwarePtr, uint8_t reference, serialInversion_e inversion) +static void serialTimerRxConfig(const timerHardware_t *timerHardwarePtr, uint8_t reference, portOptions_t options) { // start bit is usually a FALLING signal - serialICConfig(timerHardwarePtr->tim, timerHardwarePtr->channel, inversion == SERIAL_INVERTED ? TIM_ICPolarity_Rising : TIM_ICPolarity_Falling); + serialICConfig(timerHardwarePtr->tim, timerHardwarePtr->channel, (options & SERIAL_INVERTED) == SERIAL_INVERTED ? TIM_ICPolarity_Rising : TIM_ICPolarity_Falling); timerChCCHandlerInit(&softSerialPorts[reference].edgeCb, onSerialRxPinChange); timerChConfigCallbacks(timerHardwarePtr, &softSerialPorts[reference].edgeCb, NULL); } @@ -145,7 +145,7 @@ static void resetBuffers(softSerial_t *softSerial) softSerial->port.txBufferHead = 0; } -serialPort_t *openSoftSerial(softSerialPortIndex_e portIndex, serialReceiveCallbackPtr callback, uint32_t baud, serialInversion_e inversion) +serialPort_t *openSoftSerial(softSerialPortIndex_e portIndex, serialReceiveCallbackPtr callback, uint32_t baud, portOptions_t options) { softSerial_t *softSerial = &(softSerialPorts[portIndex]); @@ -166,7 +166,7 @@ serialPort_t *openSoftSerial(softSerialPortIndex_e portIndex, serialReceiveCallb softSerial->port.vTable = softSerialVTable; softSerial->port.baudRate = baud; softSerial->port.mode = MODE_RXTX; - softSerial->port.inversion = inversion; + softSerial->port.options = options; softSerial->port.callback = callback; resetBuffers(softSerial); @@ -188,7 +188,7 @@ serialPort_t *openSoftSerial(softSerialPortIndex_e portIndex, serialReceiveCallb delay(50); serialTimerTxConfig(softSerial->txTimerHardware, portIndex, baud); - serialTimerRxConfig(softSerial->rxTimerHardware, portIndex, inversion); + serialTimerRxConfig(softSerial->rxTimerHardware, portIndex, options); return &softSerial->port; } @@ -258,7 +258,7 @@ void prepareForNextRxByte(softSerial_t *softSerial) serialICConfig( softSerial->rxTimerHardware->tim, softSerial->rxTimerHardware->channel, - softSerial->port.inversion == SERIAL_INVERTED ? TIM_ICPolarity_Rising : TIM_ICPolarity_Falling + (softSerial->port.options & SERIAL_INVERTED) == SERIAL_INVERTED ? TIM_ICPolarity_Rising : TIM_ICPolarity_Falling ); } } @@ -328,6 +328,7 @@ void onSerialRxPinChange(timerCCHandlerRec_t *cbRec, captureCompare_t capture) UNUSED(capture); softSerial_t *softSerial = container_of(cbRec, softSerial_t, edgeCb); + bool inverted = (softSerial->port.options & SERIAL_INVERTED) == SERIAL_INVERTED; if ((softSerial->port.mode & MODE_RX) == 0) { return; @@ -342,7 +343,7 @@ void onSerialRxPinChange(timerCCHandlerRec_t *cbRec, captureCompare_t capture) softSerial->transmissionErrors++; } - serialICConfig(softSerial->rxTimerHardware->tim, softSerial->rxTimerHardware->channel, softSerial->port.inversion == SERIAL_INVERTED ? TIM_ICPolarity_Falling : TIM_ICPolarity_Rising); + serialICConfig(softSerial->rxTimerHardware->tim, softSerial->rxTimerHardware->channel, inverted ? TIM_ICPolarity_Falling : TIM_ICPolarity_Rising); softSerial->rxEdge = LEADING; softSerial->rxBitIndex = 0; @@ -360,10 +361,10 @@ void onSerialRxPinChange(timerCCHandlerRec_t *cbRec, captureCompare_t capture) if (softSerial->rxEdge == TRAILING) { softSerial->rxEdge = LEADING; - serialICConfig(softSerial->rxTimerHardware->tim, softSerial->rxTimerHardware->channel, softSerial->port.inversion == SERIAL_INVERTED ? TIM_ICPolarity_Falling : TIM_ICPolarity_Rising); + serialICConfig(softSerial->rxTimerHardware->tim, softSerial->rxTimerHardware->channel, inverted ? TIM_ICPolarity_Falling : TIM_ICPolarity_Rising); } else { softSerial->rxEdge = TRAILING; - serialICConfig(softSerial->rxTimerHardware->tim, softSerial->rxTimerHardware->channel, softSerial->port.inversion == SERIAL_INVERTED ? TIM_ICPolarity_Rising : TIM_ICPolarity_Falling); + serialICConfig(softSerial->rxTimerHardware->tim, softSerial->rxTimerHardware->channel, inverted ? TIM_ICPolarity_Rising : TIM_ICPolarity_Falling); } } @@ -408,7 +409,7 @@ void softSerialWriteByte(serialPort_t *s, uint8_t ch) void softSerialSetBaudRate(serialPort_t *s, uint32_t baudRate) { softSerial_t *softSerial = (softSerial_t *)s; - openSoftSerial(softSerial->softSerialPortIndex, s->callback, baudRate, softSerial->port.inversion); + openSoftSerial(softSerial->softSerialPortIndex, s->callback, baudRate, softSerial->port.options); } void softSerialSetMode(serialPort_t *instance, portMode_t mode) diff --git a/src/main/drivers/serial_softserial.h b/src/main/drivers/serial_softserial.h index 89eda56c3..17df635df 100644 --- a/src/main/drivers/serial_softserial.h +++ b/src/main/drivers/serial_softserial.h @@ -58,7 +58,7 @@ extern softSerial_t softSerialPorts[]; extern const struct serialPortVTable softSerialVTable[]; -serialPort_t *openSoftSerial(softSerialPortIndex_e portIndex, serialReceiveCallbackPtr callback, uint32_t baud, serialInversion_e inversion); +serialPort_t *openSoftSerial(softSerialPortIndex_e portIndex, serialReceiveCallbackPtr callback, uint32_t baud, portOptions_t options); // serialPort API void softSerialWriteByte(serialPort_t *instance, uint8_t ch); diff --git a/src/main/drivers/serial_uart.c b/src/main/drivers/serial_uart.c index c7b8bc4d6..885460ea6 100644 --- a/src/main/drivers/serial_uart.c +++ b/src/main/drivers/serial_uart.c @@ -39,10 +39,11 @@ static void usartConfigurePinInversion(uartPort_t *uartPort) { #if !defined(INVERTER) && !defined(STM32F303xC) UNUSED(uartPort); -#endif +#else + bool inverted = (uartPort->port.options & SERIAL_INVERTED) == SERIAL_INVERTED; #ifdef INVERTER - if (uartPort->port.inversion == SERIAL_INVERTED && uartPort->USARTx == INVERTER_USART) { + if (inverted && uartPort->USARTx == INVERTER_USART) { // Enable hardware inverter if available. INVERTER_ON; } @@ -60,9 +61,9 @@ static void usartConfigurePinInversion(uartPort_t *uartPort) { // Note: inversion when using MODE_BIDIR not supported yet. - USART_InvPinCmd(uartPort->USARTx, inversionPins, uartPort->port.inversion == SERIAL_INVERTED ? ENABLE : DISABLE); + USART_InvPinCmd(uartPort->USARTx, inversionPins, inverted ? ENABLE : DISABLE); +#endif #endif - } static void uartReconfigure(uartPort_t *uartPort) @@ -72,17 +73,10 @@ static void uartReconfigure(uartPort_t *uartPort) USART_InitStructure.USART_BaudRate = uartPort->port.baudRate; USART_InitStructure.USART_WordLength = USART_WordLength_8b; - if (uartPort->port.mode & MODE_SBUS) { - USART_InitStructure.USART_StopBits = USART_StopBits_2; - USART_InitStructure.USART_Parity = USART_Parity_Even; - } else { - if (uartPort->port.mode & MODE_STOPBITS2) - USART_InitStructure.USART_StopBits = USART_StopBits_2; - else - USART_InitStructure.USART_StopBits = USART_StopBits_1; - USART_InitStructure.USART_Parity = USART_Parity_No; - } + USART_InitStructure.USART_StopBits = (uartPort->port.options & SERIAL_STOPBITS_2) ? USART_StopBits_2 : USART_StopBits_1; + USART_InitStructure.USART_Parity = (uartPort->port.options & SERIAL_PARITY_EVEN) ? USART_Parity_Even : USART_Parity_No; + USART_InitStructure.USART_HardwareFlowControl = USART_HardwareFlowControl_None; USART_InitStructure.USART_Mode = 0; if (uartPort->port.mode & MODE_RX) @@ -99,7 +93,7 @@ static void uartReconfigure(uartPort_t *uartPort) USART_Cmd(uartPort->USARTx, ENABLE); } -serialPort_t *uartOpen(USART_TypeDef *USARTx, serialReceiveCallbackPtr callback, uint32_t baudRate, portMode_t mode, serialInversion_e inversion) +serialPort_t *uartOpen(USART_TypeDef *USARTx, serialReceiveCallbackPtr callback, uint32_t baudRate, portMode_t mode, portOptions_t options) { uartPort_t *s = NULL; @@ -125,7 +119,7 @@ serialPort_t *uartOpen(USART_TypeDef *USARTx, serialReceiveCallbackPtr callback, s->port.callback = callback; s->port.mode = mode; s->port.baudRate = baudRate; - s->port.inversion = inversion; + s->port.options = options; uartReconfigure(s); diff --git a/src/main/drivers/serial_uart.h b/src/main/drivers/serial_uart.h index 6a7357d26..6b2757f4a 100644 --- a/src/main/drivers/serial_uart.h +++ b/src/main/drivers/serial_uart.h @@ -44,7 +44,7 @@ typedef struct { USART_TypeDef *USARTx; } uartPort_t; -serialPort_t *uartOpen(USART_TypeDef *USARTx, serialReceiveCallbackPtr callback, uint32_t baudRate, portMode_t mode, serialInversion_e inversion); +serialPort_t *uartOpen(USART_TypeDef *USARTx, serialReceiveCallbackPtr callback, uint32_t baudRate, portMode_t mode, portOptions_t options); // serialPort API void uartWrite(serialPort_t *instance, uint8_t ch); diff --git a/src/main/io/serial.c b/src/main/io/serial.c index 4f0ab6eea..377d32622 100644 --- a/src/main/io/serial.c +++ b/src/main/io/serial.c @@ -238,7 +238,7 @@ serialPort_t *openSerialPort( serialReceiveCallbackPtr callback, uint32_t baudRate, portMode_t mode, - serialInversion_e inversion) + portOptions_t options) { serialPortUsage_t *serialPortUsage = findSerialPortUsageByIdentifier(identifier); if (serialPortUsage->function != FUNCTION_NONE) { @@ -256,28 +256,28 @@ serialPort_t *openSerialPort( #endif #ifdef USE_USART1 case SERIAL_PORT_USART1: - serialPort = uartOpen(USART1, callback, baudRate, mode, inversion); + serialPort = uartOpen(USART1, callback, baudRate, mode, options); break; #endif #ifdef USE_USART2 case SERIAL_PORT_USART2: - serialPort = uartOpen(USART2, callback, baudRate, mode, inversion); + serialPort = uartOpen(USART2, callback, baudRate, mode, options); break; #endif #ifdef USE_USART3 case SERIAL_PORT_USART3: - serialPort = uartOpen(USART3, callback, baudRate, mode, inversion); + serialPort = uartOpen(USART3, callback, baudRate, mode, options); break; #endif #ifdef USE_SOFTSERIAL1 case SERIAL_PORT_SOFTSERIAL1: - serialPort = openSoftSerial(SOFTSERIAL1, callback, baudRate, inversion); + serialPort = openSoftSerial(SOFTSERIAL1, callback, baudRate, options); serialSetMode(serialPort, mode); break; #endif #ifdef USE_SOFTSERIAL2 case SERIAL_PORT_SOFTSERIAL2: - serialPort = openSoftSerial(SOFTSERIAL2, callback, baudRate, inversion); + serialPort = openSoftSerial(SOFTSERIAL2, callback, baudRate, options); serialSetMode(serialPort, mode); break; #endif diff --git a/src/main/io/serial.h b/src/main/io/serial.h index 385849a25..e02bf8318 100644 --- a/src/main/io/serial.h +++ b/src/main/io/serial.h @@ -114,7 +114,7 @@ serialPort_t *openSerialPort( serialReceiveCallbackPtr callback, uint32_t baudrate, portMode_t mode, - serialInversion_e inversion + portOptions_t options ); void closeSerialPort(serialPort_t *serialPort); diff --git a/src/main/rx/sbus.c b/src/main/rx/sbus.c index 53e9bf272..cad62c9c8 100644 --- a/src/main/rx/sbus.c +++ b/src/main/rx/sbus.c @@ -68,6 +68,7 @@ static uint16_t sbusStateFlags = 0; #define SBUS_FRAME_END_BYTE 0x00 #define SBUS_BAUDRATE 100000 +#define SBUS_PORT_OPTIONS (SERIAL_STOPBITS_2 | SERIAL_PARITY_EVEN | SERIAL_INVERTED) #define SBUS_DIGITAL_CHANNEL_MIN 173 #define SBUS_DIGITAL_CHANNEL_MAX 1812 @@ -92,7 +93,7 @@ bool sbusInit(rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig, rcReadRa return false; } - serialPort_t *sBusPort = openSerialPort(portConfig->identifier, FUNCTION_RX_SERIAL, sbusDataReceive, SBUS_BAUDRATE, (portMode_t)(MODE_RX | MODE_SBUS), SERIAL_INVERTED); + serialPort_t *sBusPort = openSerialPort(portConfig->identifier, FUNCTION_RX_SERIAL, sbusDataReceive, SBUS_BAUDRATE, MODE_RX, SBUS_PORT_OPTIONS); return sBusPort != NULL; } diff --git a/src/main/telemetry/frsky.c b/src/main/telemetry/frsky.c index 5a6bca3ae..0813d0e8c 100644 --- a/src/main/telemetry/frsky.c +++ b/src/main/telemetry/frsky.c @@ -433,7 +433,7 @@ void configureFrSkyTelemetryPort(void) return; } - frskyPort = openSerialPort(portConfig->identifier, FUNCTION_TELEMETRY_FRSKY, NULL, FRSKY_BAUDRATE, FRSKY_INITIAL_PORT_MODE, telemetryConfig->telemetry_inversion); + frskyPort = openSerialPort(portConfig->identifier, FUNCTION_TELEMETRY_FRSKY, NULL, FRSKY_BAUDRATE, FRSKY_INITIAL_PORT_MODE, telemetryConfig->telemetry_inversion ? SERIAL_INVERTED : SERIAL_NOT_INVERTED); if (!frskyPort) { return; } diff --git a/src/main/telemetry/smartport.c b/src/main/telemetry/smartport.c index 58d855645..d2e30c330 100644 --- a/src/main/telemetry/smartport.c +++ b/src/main/telemetry/smartport.c @@ -233,7 +233,7 @@ void configureSmartPortTelemetryPort(void) return; } - smartPortSerialPort = openSerialPort(portConfig->identifier, FUNCTION_TELEMETRY_SMARTPORT, NULL, SMARTPORT_BAUD, SMARTPORT_UART_MODE, telemetryConfig->telemetry_inversion); + smartPortSerialPort = openSerialPort(portConfig->identifier, FUNCTION_TELEMETRY_SMARTPORT, NULL, SMARTPORT_BAUD, SMARTPORT_UART_MODE, telemetryConfig->telemetry_inversion ? SERIAL_INVERTED : SERIAL_NOT_INVERTED); if (!smartPortSerialPort) { return; diff --git a/src/main/telemetry/telemetry.h b/src/main/telemetry/telemetry.h index 010331ac2..96b91713b 100644 --- a/src/main/telemetry/telemetry.h +++ b/src/main/telemetry/telemetry.h @@ -37,7 +37,7 @@ typedef enum { typedef struct telemetryConfig_s { uint8_t telemetry_switch; // Use aux channel to change serial output & baudrate( MSP / Telemetry ). It disables automatic switching to Telemetry when armed. - serialInversion_e telemetry_inversion; // also shared with smartport inversion + uint8_t telemetry_inversion; // also shared with smartport inversion float gpsNoFixLatitude; float gpsNoFixLongitude; frskyGpsCoordFormat_e frsky_coordinate_format; diff --git a/src/test/unit/telemetry_hott_unittest.cc b/src/test/unit/telemetry_hott_unittest.cc index 85edf2a3b..27247f9ba 100644 --- a/src/test/unit/telemetry_hott_unittest.cc +++ b/src/test/unit/telemetry_hott_unittest.cc @@ -187,13 +187,13 @@ void serialSetMode(serialPort_t *instance, portMode_t mode) { } -serialPort_t *openSerialPort(serialPortIdentifier_e identifier, serialPortFunction_e functionMask, serialReceiveCallbackPtr callback, uint32_t baudRate, portMode_t mode, serialInversion_e inversion) { +serialPort_t *openSerialPort(serialPortIdentifier_e identifier, serialPortFunction_e functionMask, serialReceiveCallbackPtr callback, uint32_t baudRate, portMode_t mode, portOptions_t options) { UNUSED(identifier); UNUSED(functionMask); UNUSED(baudRate); UNUSED(callback); UNUSED(mode); - UNUSED(inversion); + UNUSED(options); return NULL; }