Add new serial port options field (inversion, stop bits, etc)

This commit is contained in:
Nicholas Sherlock 2015-03-15 17:39:22 +13:00
parent 84c7c985ab
commit 159f57f583
14 changed files with 58 additions and 57 deletions

View File

@ -62,6 +62,8 @@
#ifdef BLACKBOX #ifdef BLACKBOX
#define BLACKBOX_SERIAL_PORT_MODE MODE_TX
// How many bytes should we transmit per loop iteration? // How many bytes should we transmit per loop iteration?
uint8_t blackboxWriteChunkSize = 16; uint8_t blackboxWriteChunkSize = 16;
@ -446,7 +448,7 @@ bool blackboxDeviceOpen(void)
{ {
serialPortConfig_t *portConfig = findSerialPortConfig(FUNCTION_BLACKBOX); serialPortConfig_t *portConfig = findSerialPortConfig(FUNCTION_BLACKBOX);
baudRate_e baudRateIndex; baudRate_e baudRateIndex;
portMode_t portMode; portOptions_t portOptions = SERIAL_PARITY_NO | SERIAL_NOT_INVERTED;
if (!portConfig) { if (!portConfig) {
return false; return false;
@ -455,18 +457,18 @@ bool blackboxDeviceOpen(void)
blackboxPortSharing = determinePortSharing(portConfig, FUNCTION_BLACKBOX); blackboxPortSharing = determinePortSharing(portConfig, FUNCTION_BLACKBOX);
baudRateIndex = portConfig->blackbox_baudrateIndex; baudRateIndex = portConfig->blackbox_baudrateIndex;
portMode = MODE_TX;
if (baudRates[baudRateIndex] == 230400) { if (baudRates[baudRateIndex] == 230400) {
/* /*
* OpenLog's 230400 baud rate is very inaccurate, so it requires a larger inter-character gap in * OpenLog's 230400 baud rate is very inaccurate, so it requires a larger inter-character gap in
* order to maintain synchronization. * 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], blackboxPort = openSerialPort(portConfig->identifier, FUNCTION_BLACKBOX, NULL, baudRates[baudRateIndex],
portMode, SERIAL_NOT_INVERTED); BLACKBOX_SERIAL_PORT_MODE, portOptions);
return blackboxPort != NULL; return blackboxPort != NULL;
} }

View File

@ -220,7 +220,7 @@ void resetFlight3DConfig(flight3DConfig_t *flight3DConfig)
void resetTelemetryConfig(telemetryConfig_t *telemetryConfig) void resetTelemetryConfig(telemetryConfig_t *telemetryConfig)
{ {
telemetryConfig->telemetry_inversion = SERIAL_NOT_INVERTED; telemetryConfig->telemetry_inversion = 0;
telemetryConfig->telemetry_switch = 0; telemetryConfig->telemetry_switch = 0;
telemetryConfig->gpsNoFixLatitude = 0; telemetryConfig->gpsNoFixLatitude = 0;
telemetryConfig->gpsNoFixLongitude = 0; telemetryConfig->gpsNoFixLongitude = 0;

View File

@ -17,20 +17,22 @@
#pragma once #pragma once
typedef enum {
SERIAL_NOT_INVERTED = 0,
SERIAL_INVERTED
} serialInversion_e;
typedef enum portMode_t { typedef enum portMode_t {
MODE_RX = 1 << 0, MODE_RX = 1 << 0,
MODE_TX = 1 << 1, MODE_TX = 1 << 1,
MODE_RXTX = MODE_RX | MODE_TX, MODE_RXTX = MODE_RX | MODE_TX,
MODE_SBUS = 1 << 2, MODE_BIDIR = 1 << 3
MODE_BIDIR = 1 << 3,
MODE_STOPBITS2 = 1 << 4,
} portMode_t; } 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 void (*serialReceiveCallbackPtr)(uint16_t data); // used by serial drivers to return frames to app
typedef struct serialPort { typedef struct serialPort {
@ -39,7 +41,8 @@ typedef struct serialPort {
uint8_t identifier; uint8_t identifier;
portMode_t mode; portMode_t mode;
serialInversion_e inversion; portOptions_t options;
uint32_t baudRate; uint32_t baudRate;
uint32_t rxBufferSize; uint32_t rxBufferSize;

View File

@ -52,7 +52,7 @@ void onSerialRxPinChange(timerCCHandlerRec_t *cbRec, captureCompare_t capture);
void setTxSignal(softSerial_t *softSerial, uint8_t state) void setTxSignal(softSerial_t *softSerial, uint8_t state)
{ {
if (softSerial->port.inversion == SERIAL_INVERTED) { if ((softSerial->port.options & SERIAL_INVERTED) == SERIAL_INVERTED) {
state = !state; state = !state;
} }
@ -119,10 +119,10 @@ static void serialICConfig(TIM_TypeDef *tim, uint8_t channel, uint16_t polarity)
TIM_ICInit(tim, &TIM_ICInitStructure); 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 // 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); timerChCCHandlerInit(&softSerialPorts[reference].edgeCb, onSerialRxPinChange);
timerChConfigCallbacks(timerHardwarePtr, &softSerialPorts[reference].edgeCb, NULL); timerChConfigCallbacks(timerHardwarePtr, &softSerialPorts[reference].edgeCb, NULL);
} }
@ -145,7 +145,7 @@ static void resetBuffers(softSerial_t *softSerial)
softSerial->port.txBufferHead = 0; 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]); softSerial_t *softSerial = &(softSerialPorts[portIndex]);
@ -166,7 +166,7 @@ serialPort_t *openSoftSerial(softSerialPortIndex_e portIndex, serialReceiveCallb
softSerial->port.vTable = softSerialVTable; softSerial->port.vTable = softSerialVTable;
softSerial->port.baudRate = baud; softSerial->port.baudRate = baud;
softSerial->port.mode = MODE_RXTX; softSerial->port.mode = MODE_RXTX;
softSerial->port.inversion = inversion; softSerial->port.options = options;
softSerial->port.callback = callback; softSerial->port.callback = callback;
resetBuffers(softSerial); resetBuffers(softSerial);
@ -188,7 +188,7 @@ serialPort_t *openSoftSerial(softSerialPortIndex_e portIndex, serialReceiveCallb
delay(50); delay(50);
serialTimerTxConfig(softSerial->txTimerHardware, portIndex, baud); serialTimerTxConfig(softSerial->txTimerHardware, portIndex, baud);
serialTimerRxConfig(softSerial->rxTimerHardware, portIndex, inversion); serialTimerRxConfig(softSerial->rxTimerHardware, portIndex, options);
return &softSerial->port; return &softSerial->port;
} }
@ -258,7 +258,7 @@ void prepareForNextRxByte(softSerial_t *softSerial)
serialICConfig( serialICConfig(
softSerial->rxTimerHardware->tim, softSerial->rxTimerHardware->tim,
softSerial->rxTimerHardware->channel, 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); UNUSED(capture);
softSerial_t *softSerial = container_of(cbRec, softSerial_t, edgeCb); 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) { if ((softSerial->port.mode & MODE_RX) == 0) {
return; return;
@ -342,7 +343,7 @@ void onSerialRxPinChange(timerCCHandlerRec_t *cbRec, captureCompare_t capture)
softSerial->transmissionErrors++; 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->rxEdge = LEADING;
softSerial->rxBitIndex = 0; softSerial->rxBitIndex = 0;
@ -360,10 +361,10 @@ void onSerialRxPinChange(timerCCHandlerRec_t *cbRec, captureCompare_t capture)
if (softSerial->rxEdge == TRAILING) { if (softSerial->rxEdge == TRAILING) {
softSerial->rxEdge = LEADING; 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 { } else {
softSerial->rxEdge = TRAILING; 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) void softSerialSetBaudRate(serialPort_t *s, uint32_t baudRate)
{ {
softSerial_t *softSerial = (softSerial_t *)s; 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) void softSerialSetMode(serialPort_t *instance, portMode_t mode)

View File

@ -58,7 +58,7 @@ extern softSerial_t softSerialPorts[];
extern const struct serialPortVTable softSerialVTable[]; 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 // serialPort API
void softSerialWriteByte(serialPort_t *instance, uint8_t ch); void softSerialWriteByte(serialPort_t *instance, uint8_t ch);

View File

@ -39,10 +39,11 @@
static void usartConfigurePinInversion(uartPort_t *uartPort) { static void usartConfigurePinInversion(uartPort_t *uartPort) {
#if !defined(INVERTER) && !defined(STM32F303xC) #if !defined(INVERTER) && !defined(STM32F303xC)
UNUSED(uartPort); UNUSED(uartPort);
#endif #else
bool inverted = (uartPort->port.options & SERIAL_INVERTED) == SERIAL_INVERTED;
#ifdef INVERTER #ifdef INVERTER
if (uartPort->port.inversion == SERIAL_INVERTED && uartPort->USARTx == INVERTER_USART) { if (inverted && uartPort->USARTx == INVERTER_USART) {
// Enable hardware inverter if available. // Enable hardware inverter if available.
INVERTER_ON; INVERTER_ON;
} }
@ -60,9 +61,9 @@ static void usartConfigurePinInversion(uartPort_t *uartPort) {
// Note: inversion when using MODE_BIDIR not supported yet. // 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 #endif
} }
static void uartReconfigure(uartPort_t *uartPort) 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_BaudRate = uartPort->port.baudRate;
USART_InitStructure.USART_WordLength = USART_WordLength_8b; 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_HardwareFlowControl = USART_HardwareFlowControl_None;
USART_InitStructure.USART_Mode = 0; USART_InitStructure.USART_Mode = 0;
if (uartPort->port.mode & MODE_RX) if (uartPort->port.mode & MODE_RX)
@ -99,7 +93,7 @@ static void uartReconfigure(uartPort_t *uartPort)
USART_Cmd(uartPort->USARTx, ENABLE); 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; uartPort_t *s = NULL;
@ -125,7 +119,7 @@ serialPort_t *uartOpen(USART_TypeDef *USARTx, serialReceiveCallbackPtr callback,
s->port.callback = callback; s->port.callback = callback;
s->port.mode = mode; s->port.mode = mode;
s->port.baudRate = baudRate; s->port.baudRate = baudRate;
s->port.inversion = inversion; s->port.options = options;
uartReconfigure(s); uartReconfigure(s);

View File

@ -44,7 +44,7 @@ typedef struct {
USART_TypeDef *USARTx; USART_TypeDef *USARTx;
} uartPort_t; } 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 // serialPort API
void uartWrite(serialPort_t *instance, uint8_t ch); void uartWrite(serialPort_t *instance, uint8_t ch);

View File

@ -238,7 +238,7 @@ serialPort_t *openSerialPort(
serialReceiveCallbackPtr callback, serialReceiveCallbackPtr callback,
uint32_t baudRate, uint32_t baudRate,
portMode_t mode, portMode_t mode,
serialInversion_e inversion) portOptions_t options)
{ {
serialPortUsage_t *serialPortUsage = findSerialPortUsageByIdentifier(identifier); serialPortUsage_t *serialPortUsage = findSerialPortUsageByIdentifier(identifier);
if (serialPortUsage->function != FUNCTION_NONE) { if (serialPortUsage->function != FUNCTION_NONE) {
@ -256,28 +256,28 @@ serialPort_t *openSerialPort(
#endif #endif
#ifdef USE_USART1 #ifdef USE_USART1
case SERIAL_PORT_USART1: case SERIAL_PORT_USART1:
serialPort = uartOpen(USART1, callback, baudRate, mode, inversion); serialPort = uartOpen(USART1, callback, baudRate, mode, options);
break; break;
#endif #endif
#ifdef USE_USART2 #ifdef USE_USART2
case SERIAL_PORT_USART2: case SERIAL_PORT_USART2:
serialPort = uartOpen(USART2, callback, baudRate, mode, inversion); serialPort = uartOpen(USART2, callback, baudRate, mode, options);
break; break;
#endif #endif
#ifdef USE_USART3 #ifdef USE_USART3
case SERIAL_PORT_USART3: case SERIAL_PORT_USART3:
serialPort = uartOpen(USART3, callback, baudRate, mode, inversion); serialPort = uartOpen(USART3, callback, baudRate, mode, options);
break; break;
#endif #endif
#ifdef USE_SOFTSERIAL1 #ifdef USE_SOFTSERIAL1
case SERIAL_PORT_SOFTSERIAL1: case SERIAL_PORT_SOFTSERIAL1:
serialPort = openSoftSerial(SOFTSERIAL1, callback, baudRate, inversion); serialPort = openSoftSerial(SOFTSERIAL1, callback, baudRate, options);
serialSetMode(serialPort, mode); serialSetMode(serialPort, mode);
break; break;
#endif #endif
#ifdef USE_SOFTSERIAL2 #ifdef USE_SOFTSERIAL2
case SERIAL_PORT_SOFTSERIAL2: case SERIAL_PORT_SOFTSERIAL2:
serialPort = openSoftSerial(SOFTSERIAL2, callback, baudRate, inversion); serialPort = openSoftSerial(SOFTSERIAL2, callback, baudRate, options);
serialSetMode(serialPort, mode); serialSetMode(serialPort, mode);
break; break;
#endif #endif

View File

@ -114,7 +114,7 @@ serialPort_t *openSerialPort(
serialReceiveCallbackPtr callback, serialReceiveCallbackPtr callback,
uint32_t baudrate, uint32_t baudrate,
portMode_t mode, portMode_t mode,
serialInversion_e inversion portOptions_t options
); );
void closeSerialPort(serialPort_t *serialPort); void closeSerialPort(serialPort_t *serialPort);

View File

@ -68,6 +68,7 @@ static uint16_t sbusStateFlags = 0;
#define SBUS_FRAME_END_BYTE 0x00 #define SBUS_FRAME_END_BYTE 0x00
#define SBUS_BAUDRATE 100000 #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_MIN 173
#define SBUS_DIGITAL_CHANNEL_MAX 1812 #define SBUS_DIGITAL_CHANNEL_MAX 1812
@ -92,7 +93,7 @@ bool sbusInit(rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig, rcReadRa
return false; 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; return sBusPort != NULL;
} }

View File

@ -433,7 +433,7 @@ void configureFrSkyTelemetryPort(void)
return; 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) { if (!frskyPort) {
return; return;
} }

View File

@ -233,7 +233,7 @@ void configureSmartPortTelemetryPort(void)
return; 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) { if (!smartPortSerialPort) {
return; return;

View File

@ -37,7 +37,7 @@ typedef enum {
typedef struct telemetryConfig_s { 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. 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 gpsNoFixLatitude;
float gpsNoFixLongitude; float gpsNoFixLongitude;
frskyGpsCoordFormat_e frsky_coordinate_format; frskyGpsCoordFormat_e frsky_coordinate_format;

View File

@ -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(identifier);
UNUSED(functionMask); UNUSED(functionMask);
UNUSED(baudRate); UNUSED(baudRate);
UNUSED(callback); UNUSED(callback);
UNUSED(mode); UNUSED(mode);
UNUSED(inversion); UNUSED(options);
return NULL; return NULL;
} }