From 1a8500c768157b902206956644b83eacf3b50faa Mon Sep 17 00:00:00 2001 From: Dominic Clifton Date: Fri, 27 Feb 2015 01:05:37 +0000 Subject: [PATCH] Transition to new per-port & per-function baud rate configuration. --- src/main/blackbox/blackbox_io.c | 2 +- src/main/config/config.c | 5 ++++- src/main/io/gps.c | 26 ++++++++++++------------ src/main/io/serial.c | 20 +++++++++++++++++- src/main/io/serial.h | 21 ++++++++++++++++--- src/main/io/serial_cli.c | 25 ++++++++++++++++++----- src/main/io/serial_msp.c | 16 ++++++++++----- src/main/rx/spektrum.c | 2 +- src/main/telemetry/frsky.c | 2 +- src/main/telemetry/hott.c | 2 +- src/main/telemetry/msp.c | 7 ++++++- src/main/telemetry/smartport.c | 2 +- src/test/unit/telemetry_hott_unittest.cc | 2 +- 13 files changed, 97 insertions(+), 35 deletions(-) diff --git a/src/main/blackbox/blackbox_io.c b/src/main/blackbox/blackbox_io.c index 4f1fefb1d..9fbcaa650 100644 --- a/src/main/blackbox/blackbox_io.c +++ b/src/main/blackbox/blackbox_io.c @@ -62,7 +62,7 @@ #ifdef BLACKBOX -#define BLACKBOX_BAUDRATE 115200 +#define BLACKBOX_BAUDRATE BAUD_115200 #define BLACKBOX_INITIAL_PORT_MODE MODE_TX // How many bytes should we transmit per loop iteration? diff --git a/src/main/config/config.c b/src/main/config/config.c index 74185f061..08d2c6416 100644 --- a/src/main/config/config.c +++ b/src/main/config/config.c @@ -256,10 +256,13 @@ void resetSerialConfig(serialConfig_t *serialConfig) for (index = 0; index < SERIAL_PORT_COUNT; index++) { serialConfig->portConfigs[index].identifier = serialPortIdentifiers[index]; + serialConfig->portConfigs[index].msp_baudrateIndex = BAUD_115200; + serialConfig->portConfigs[index].gps_baudrateIndex = BAUD_57600; + serialConfig->portConfigs[index].telemetry_baudrateIndex = BAUD_AUTO; + serialConfig->portConfigs[index].blackbox_baudrateIndex = BAUD_115200; } serialConfig->portConfigs[0].functionMask = FUNCTION_MSP; - serialConfig->portConfigs[0].baudrate = 115200; #ifdef CC3D // Temporary workaround for CC3D non-functional VCP when using OpenPilot bootloader. diff --git a/src/main/io/gps.c b/src/main/io/gps.c index 07f832eda..904f32f5e 100644 --- a/src/main/io/gps.c +++ b/src/main/io/gps.c @@ -100,19 +100,19 @@ static serialPort_t *gpsPort; typedef struct gpsInitData_t { uint8_t index; - uint32_t baudrate; + uint8_t baudrateIndex; // see baudRate_e const char *ubx; const char *mtk; } gpsInitData_t; // NMEA will cycle through these until valid data is received static const gpsInitData_t gpsInitData[] = { - { GPS_BAUDRATE_115200, 115200, "$PUBX,41,1,0003,0001,115200,0*1E\r\n", "$PMTK251,115200*1F\r\n" }, - { GPS_BAUDRATE_57600, 57600, "$PUBX,41,1,0003,0001,57600,0*2D\r\n", "$PMTK251,57600*2C\r\n" }, - { GPS_BAUDRATE_38400, 38400, "$PUBX,41,1,0003,0001,38400,0*26\r\n", "$PMTK251,38400*27\r\n" }, - { GPS_BAUDRATE_19200, 19200, "$PUBX,41,1,0003,0001,19200,0*23\r\n", "$PMTK251,19200*22\r\n" }, + { GPS_BAUDRATE_115200, BAUD_115200, "$PUBX,41,1,0003,0001,115200,0*1E\r\n", "$PMTK251,115200*1F\r\n" }, + { GPS_BAUDRATE_57600, BAUD_57600, "$PUBX,41,1,0003,0001,57600,0*2D\r\n", "$PMTK251,57600*2C\r\n" }, + { GPS_BAUDRATE_38400, BAUD_38400, "$PUBX,41,1,0003,0001,38400,0*26\r\n", "$PMTK251,38400*27\r\n" }, + { GPS_BAUDRATE_19200, BAUD_19200, "$PUBX,41,1,0003,0001,19200,0*23\r\n", "$PMTK251,19200*22\r\n" }, // 9600 is not enough for 5Hz updates - leave for compatibility to dumb NMEA that only runs at this speed - { GPS_BAUDRATE_9600, 9600, "$PUBX,41,1,0003,0001,9600,0*16\r\n", "" } + { GPS_BAUDRATE_9600, BAUD_9600, "$PUBX,41,1,0003,0001,9600,0*16\r\n", "" } }; #define GPS_INIT_DATA_ENTRY_COUNT (sizeof(gpsInitData) / sizeof(gpsInitData[0])) @@ -226,7 +226,7 @@ void gpsInit(serialConfig_t *initialSerialConfig, gpsConfig_t *initialGpsConfig) return; } - while (gpsInitData[gpsData.baudrateIndex].baudrate != gpsPortConfig->baudrate) { + while (gpsInitData[gpsData.baudrateIndex].baudrateIndex != gpsPortConfig->gps_baudrateIndex) { gpsData.baudrateIndex++; if (gpsData.baudrateIndex >= GPS_INIT_DATA_ENTRY_COUNT) { gpsData.baudrateIndex = DEFAULT_BAUD_RATE_INDEX; @@ -240,7 +240,7 @@ void gpsInit(serialConfig_t *initialSerialConfig, gpsConfig_t *initialGpsConfig) mode &= ~MODE_TX; // no callback - buffer will be consumed in gpsThread() - gpsPort = openSerialPort(gpsPortConfig->identifier, FUNCTION_GPS, NULL, gpsInitData[gpsData.baudrateIndex].baudrate, mode, SERIAL_NOT_INVERTED); + gpsPort = openSerialPort(gpsPortConfig->identifier, FUNCTION_GPS, NULL, gpsInitData[gpsData.baudrateIndex].baudrateIndex, mode, SERIAL_NOT_INVERTED); if (!gpsPort) { featureClear(FEATURE_GPS); return; @@ -255,7 +255,7 @@ void gpsInitNmea(void) switch(gpsData.state) { case GPS_INITIALIZING: case GPS_CHANGE_BAUD: - serialSetBaudRate(gpsPort, gpsInitData[gpsData.baudrateIndex].baudrate); + serialSetBaudRate(gpsPort, baudRates[gpsInitData[gpsData.baudrateIndex].baudrateIndex]); gpsSetState(GPS_RECEIVING_DATA); break; } @@ -279,13 +279,13 @@ void gpsInitUblox(void) if (gpsData.state_position < GPS_INIT_ENTRIES) { // try different speed to INIT - uint32_t newBaudRate = gpsInitData[gpsData.state_position].baudrate; + baudRate_e newBaudRateIndex = gpsInitData[gpsData.state_position].baudrateIndex; gpsData.state_ts = now; - if (serialGetBaudRate(gpsPort) != newBaudRate) { + if (lookupBaudRateIndex(serialGetBaudRate(gpsPort)) != newBaudRateIndex) { // change the rate if needed and wait a little - serialSetBaudRate(gpsPort, newBaudRate); + serialSetBaudRate(gpsPort, baudRates[newBaudRateIndex]); return; } @@ -299,7 +299,7 @@ void gpsInitUblox(void) } break; case GPS_CHANGE_BAUD: - serialSetBaudRate(gpsPort, gpsInitData[gpsData.baudrateIndex].baudrate); + serialSetBaudRate(gpsPort, baudRates[gpsInitData[gpsData.baudrateIndex].baudrateIndex]); gpsSetState(GPS_CONFIGURE); break; case GPS_CONFIGURE: diff --git a/src/main/io/serial.c b/src/main/io/serial.c index e26a89495..cc291bad4 100644 --- a/src/main/io/serial.c +++ b/src/main/io/serial.c @@ -68,6 +68,22 @@ serialPortIdentifier_e serialPortIdentifiers[SERIAL_PORT_COUNT] = { #endif }; +uint32_t baudRates[] = {0, 9600, 19200, 38400, 57600, 115200}; // see baudRate_e + +#define BAUD_RATE_COUNT (sizeof(baudRates) / sizeof(baudRates[0])) + +baudRate_e lookupBaudRateIndex(uint32_t baudRate) +{ + uint8_t index; + + for (index = 0; index < BAUD_RATE_COUNT; index++) { + if (baudRates[index] == baudRate) { + return index; + } + } + return 0; +} + static serialPortUsage_t *findSerialPortUsageByIdentifier(serialPortIdentifier_e identifier) { uint8_t index; @@ -220,7 +236,7 @@ serialPort_t *openSerialPort( serialPortIdentifier_e identifier, serialPortFunction_e function, serialReceiveCallbackPtr callback, - uint32_t baudRate, + baudRate_e baudRateIndex, portMode_t mode, serialInversion_e inversion) { @@ -232,6 +248,8 @@ serialPort_t *openSerialPort( serialPort_t *serialPort = NULL; + uint32_t baudRate = baudRates[baudRateIndex]; + switch(identifier) { #ifdef USE_VCP case SERIAL_PORT_USB_VCP: diff --git a/src/main/io/serial.h b/src/main/io/serial.h index 82c9fdb2b..503a25c73 100644 --- a/src/main/io/serial.h +++ b/src/main/io/serial.h @@ -35,6 +35,17 @@ typedef enum { FUNCTION_BLACKBOX = (1 << 7) } serialPortFunction_e; +typedef enum { + BAUD_AUTO = 0, + BAUD_9600, + BAUD_19200, + BAUD_38400, + BAUD_57600, + BAUD_115200 +} baudRate_e; + +extern uint32_t baudRates[]; + // serial port identifiers are now fixed, these values are used by MSP commands. typedef enum { SERIAL_PORT_USART1 = 0, @@ -64,11 +75,13 @@ serialPort_t *findNextSharedSerialPort(uint16_t functionMask, serialPortFunction // // configuration // - typedef struct serialPortConfig_s { serialPortIdentifier_e identifier; uint16_t functionMask; - uint32_t baudrate; // not used for all functions, e.g. HoTT only works at 19200. + uint8_t msp_baudrateIndex; + uint8_t gps_baudrateIndex; + uint8_t blackbox_baudrateIndex; + uint8_t telemetry_baudrateIndex; // not used for all telemetry systems, e.g. HoTT only works at 19200. } serialPortConfig_t; typedef struct serialConfig_s { @@ -97,7 +110,7 @@ serialPort_t *openSerialPort( serialPortIdentifier_e identifier, serialPortFunction_e function, serialReceiveCallbackPtr callback, - uint32_t baudrate, + baudRate_e baudrate, portMode_t mode, serialInversion_e inversion ); @@ -105,6 +118,8 @@ void closeSerialPort(serialPort_t *serialPort); void waitForSerialPortToFinishTransmitting(serialPort_t *serialPort); +baudRate_e lookupBaudRateIndex(uint32_t baudRate); + // // msp/cli/bootloader // diff --git a/src/main/io/serial_cli.c b/src/main/io/serial_cli.c index b883db0b8..35317b7a8 100644 --- a/src/main/io/serial_cli.c +++ b/src/main/io/serial_cli.c @@ -280,19 +280,34 @@ const clivalue_t valueTable[] = { { "fixedwing_althold_dir", VAR_INT8 | MASTER_VALUE, &masterConfig.airplaneConfig.fixedwing_althold_dir, -1, 1 }, { "serial_port_1_functions", VAR_UINT16 | MASTER_VALUE, &masterConfig.serialConfig.portConfigs[0].functionMask, 0, 0xFFFF }, - { "serial_port_1_baudrate", VAR_UINT32 | MASTER_VALUE, &masterConfig.serialConfig.portConfigs[0].baudrate, 1200, 115200 }, + { "serial_port_1_msp_baudrate", VAR_UINT8 | MASTER_VALUE, &masterConfig.serialConfig.portConfigs[0].msp_baudrateIndex, BAUD_9600, BAUD_115200 }, + { "serial_port_1_telemetry_baudrate", VAR_UINT8 | MASTER_VALUE, &masterConfig.serialConfig.portConfigs[0].telemetry_baudrateIndex, BAUD_AUTO, BAUD_115200 }, + { "serial_port_1_blackbox_baudrate", VAR_UINT8 | MASTER_VALUE, &masterConfig.serialConfig.portConfigs[0].blackbox_baudrateIndex, BAUD_9600, BAUD_115200 }, + { "serial_port_1_gps_baudrate", VAR_UINT8 | MASTER_VALUE, &masterConfig.serialConfig.portConfigs[0].gps_baudrateIndex, BAUD_9600, BAUD_115200 }, #if (SERIAL_PORT_COUNT >= 2) { "serial_port_2_functions", VAR_UINT16 | MASTER_VALUE, &masterConfig.serialConfig.portConfigs[1].functionMask, 0, 0xFFFF }, - { "serial_port_2_baudrate", VAR_UINT32 | MASTER_VALUE, &masterConfig.serialConfig.portConfigs[1].baudrate, 1200, 115200 }, + { "serial_port_2_msp_baudrate", VAR_UINT8 | MASTER_VALUE, &masterConfig.serialConfig.portConfigs[1].msp_baudrateIndex, BAUD_9600, BAUD_115200 }, + { "serial_port_2_telemetry_baudrate", VAR_UINT8 | MASTER_VALUE, &masterConfig.serialConfig.portConfigs[1].telemetry_baudrateIndex, BAUD_AUTO, BAUD_115200 }, + { "serial_port_2_blackbox_baudrate", VAR_UINT8 | MASTER_VALUE, &masterConfig.serialConfig.portConfigs[1].blackbox_baudrateIndex, BAUD_9600, BAUD_115200 }, + { "serial_port_2_gps_baudrate", VAR_UINT8 | MASTER_VALUE, &masterConfig.serialConfig.portConfigs[1].gps_baudrateIndex, BAUD_9600, BAUD_115200 }, #if (SERIAL_PORT_COUNT >= 3) { "serial_port_3_functions", VAR_UINT16 | MASTER_VALUE, &masterConfig.serialConfig.portConfigs[2].functionMask, 0, 0xFFFF}, - { "serial_port_3_baudrate", VAR_UINT32 | MASTER_VALUE, &masterConfig.serialConfig.portConfigs[2].baudrate, 1200, 115200 }, + { "serial_port_3_msp_baudrate", VAR_UINT8 | MASTER_VALUE, &masterConfig.serialConfig.portConfigs[2].msp_baudrateIndex, BAUD_9600, BAUD_115200 }, + { "serial_port_3_telemetry_baudrate", VAR_UINT8 | MASTER_VALUE, &masterConfig.serialConfig.portConfigs[2].telemetry_baudrateIndex, BAUD_AUTO, BAUD_115200 }, + { "serial_port_3_blackbox_baudrate", VAR_UINT8 | MASTER_VALUE, &masterConfig.serialConfig.portConfigs[2].blackbox_baudrateIndex, BAUD_9600, BAUD_115200 }, + { "serial_port_3_gps_baudrate", VAR_UINT8 | MASTER_VALUE, &masterConfig.serialConfig.portConfigs[2].gps_baudrateIndex, BAUD_9600, BAUD_115200 }, #if (SERIAL_PORT_COUNT >= 4) { "serial_port_4_functions", VAR_UINT16 | MASTER_VALUE, &masterConfig.serialConfig.portConfigs[3].functionMask, 0, 0xFFFF }, - { "serial_port_4_baudrate", VAR_UINT32 | MASTER_VALUE, &masterConfig.serialConfig.portConfigs[3].baudrate, 1200, 115200 }, + { "serial_port_4_msp_baudrate", VAR_UINT8 | MASTER_VALUE, &masterConfig.serialConfig.portConfigs[3].msp_baudrateIndex, BAUD_9600, BAUD_115200 }, + { "serial_port_4_telemetry_baudrate", VAR_UINT8 | MASTER_VALUE, &masterConfig.serialConfig.portConfigs[3].telemetry_baudrateIndex, BAUD_AUTO, BAUD_115200 }, + { "serial_port_4_blackbox_baudrate", VAR_UINT8 | MASTER_VALUE, &masterConfig.serialConfig.portConfigs[3].blackbox_baudrateIndex, BAUD_9600, BAUD_115200 }, + { "serial_port_4_gps_baudrate", VAR_UINT8 | MASTER_VALUE, &masterConfig.serialConfig.portConfigs[3].gps_baudrateIndex, BAUD_9600, BAUD_115200 }, #if (SERIAL_PORT_COUNT >= 5) { "serial_port_5_functions", VAR_UINT16 | MASTER_VALUE, &masterConfig.serialConfig.portConfigs[4].functionMask, 0, 0xFFFF }, - { "serial_port_5_baudrate", VAR_UINT32 | MASTER_VALUE, &masterConfig.serialConfig.portConfigs[4].baudrate, 1200, 115200 }, + { "serial_port_5_msp_baudrate", VAR_UINT8 | MASTER_VALUE, &masterConfig.serialConfig.portConfigs[4].msp_baudrateIndex, BAUD_9600, BAUD_115200 }, + { "serial_port_5_telemetry_baudrate", VAR_UINT8 | MASTER_VALUE, &masterConfig.serialConfig.portConfigs[4].telemetry_baudrateIndex, BAUD_AUTO, BAUD_115200 }, + { "serial_port_5_blackbox_baudrate", VAR_UINT8 | MASTER_VALUE, &masterConfig.serialConfig.portConfigs[4].blackbox_baudrateIndex, BAUD_9600, BAUD_115200 }, + { "serial_port_5_gps_baudrate", VAR_UINT8 | MASTER_VALUE, &masterConfig.serialConfig.portConfigs[4].gps_baudrateIndex, BAUD_9600, BAUD_115200 }, #endif #endif #endif diff --git a/src/main/io/serial_msp.c b/src/main/io/serial_msp.c index 32b51e4b6..b8a489374 100644 --- a/src/main/io/serial_msp.c +++ b/src/main/io/serial_msp.c @@ -602,7 +602,7 @@ void mspAllocateSerialPorts(serialConfig_t *serialConfig) continue; } - serialPort = openSerialPort(portConfig->identifier, FUNCTION_MSP, NULL, portConfig->baudrate, MODE_RXTX, SERIAL_NOT_INVERTED); + serialPort = openSerialPort(portConfig->identifier, FUNCTION_MSP, NULL, portConfig->msp_baudrateIndex, MODE_RXTX, SERIAL_NOT_INVERTED); if (serialPort) { resetMspPort(mspPort, serialPort, FOR_GENERAL_MSP); portIndex++; @@ -1151,12 +1151,15 @@ static bool processOutCommand(uint8_t cmdMSP) case MSP_CF_SERIAL_CONFIG: headSerialReply( - ((sizeof(uint8_t) + sizeof(uint16_t) + sizeof(uint32_t)) * SERIAL_PORT_COUNT) + ((sizeof(uint8_t) + sizeof(uint16_t) + (sizeof(uint8_t) * 4)) * SERIAL_PORT_COUNT) ); for (i = 0; i < SERIAL_PORT_COUNT; i++) { serialize8(masterConfig.serialConfig.portConfigs[i].identifier); serialize16(masterConfig.serialConfig.portConfigs[i].functionMask); - serialize32(masterConfig.serialConfig.portConfigs[i].baudrate); + serialize8(masterConfig.serialConfig.portConfigs[i].msp_baudrateIndex); + serialize8(masterConfig.serialConfig.portConfigs[i].gps_baudrateIndex); + serialize8(masterConfig.serialConfig.portConfigs[i].telemetry_baudrateIndex); + serialize8(masterConfig.serialConfig.portConfigs[i].blackbox_baudrateIndex); } break; @@ -1529,7 +1532,7 @@ static bool processInCommand(void) case MSP_SET_CF_SERIAL_CONFIG: { - uint8_t portConfigSize = sizeof(uint8_t) + sizeof(uint16_t) + sizeof(uint32_t); + uint8_t portConfigSize = sizeof(uint8_t) + sizeof(uint16_t) + (sizeof(uint8_t) * 4); if ((SERIAL_PORT_COUNT * portConfigSize) != SERIAL_PORT_COUNT) { headSerialError(0); @@ -1538,7 +1541,10 @@ static bool processInCommand(void) for (i = 0; i < SERIAL_PORT_COUNT; i++) { masterConfig.serialConfig.portConfigs[i].identifier = read8(); masterConfig.serialConfig.portConfigs[i].functionMask = read16(); - masterConfig.serialConfig.portConfigs[i].baudrate = read32(); + masterConfig.serialConfig.portConfigs[i].msp_baudrateIndex = read8(); + masterConfig.serialConfig.portConfigs[i].gps_baudrateIndex = read8(); + masterConfig.serialConfig.portConfigs[i].telemetry_baudrateIndex = read8(); + masterConfig.serialConfig.portConfigs[i].blackbox_baudrateIndex = read8(); } } break; diff --git a/src/main/rx/spektrum.c b/src/main/rx/spektrum.c index 5d037c383..66e12214f 100644 --- a/src/main/rx/spektrum.c +++ b/src/main/rx/spektrum.c @@ -43,7 +43,7 @@ #define SPEK_FRAME_SIZE 16 -#define SPEKTRUM_BAUDRATE 115200 +#define SPEKTRUM_BAUDRATE BAUD_115200 static uint8_t spek_chan_shift; static uint8_t spek_chan_mask; diff --git a/src/main/telemetry/frsky.c b/src/main/telemetry/frsky.c index c02eaf756..0ed04496f 100644 --- a/src/main/telemetry/frsky.c +++ b/src/main/telemetry/frsky.c @@ -64,7 +64,7 @@ static serialPort_t *frskyPort = NULL; static serialPortConfig_t *portConfig; -#define FRSKY_BAUDRATE 9600 +#define FRSKY_BAUDRATE BAUD_9600 #define FRSKY_INITIAL_PORT_MODE MODE_TX static telemetryConfig_t *telemetryConfig; diff --git a/src/main/telemetry/hott.c b/src/main/telemetry/hott.c index dee3629a1..c0345f61f 100644 --- a/src/main/telemetry/hott.c +++ b/src/main/telemetry/hott.c @@ -100,7 +100,7 @@ static uint8_t hottMsgCrc; #define HOTT_CRC_SIZE (sizeof(hottMsgCrc)) -#define HOTT_BAUDRATE 19200 +#define HOTT_BAUDRATE BAUD_19200 #define HOTT_INITIAL_PORT_MODE MODE_RX static serialPort_t *hottPort = NULL; diff --git a/src/main/telemetry/msp.c b/src/main/telemetry/msp.c index 74493e866..a5773244e 100644 --- a/src/main/telemetry/msp.c +++ b/src/main/telemetry/msp.c @@ -95,7 +95,12 @@ void configureMSPTelemetryPort(void) return; } - mspTelemetryPort = openSerialPort(portConfig->identifier, FUNCTION_MSP_TELEMETRY, NULL, portConfig->baudrate, MSP_TELEMETRY_INITIAL_PORT_MODE, SERIAL_NOT_INVERTED); + baudRate_e baudRateIndex = portConfig->telemetry_baudrateIndex; + if (baudRateIndex == BAUD_AUTO) { + baudRateIndex = BAUD_19200; + } + + mspTelemetryPort = openSerialPort(portConfig->identifier, FUNCTION_MSP_TELEMETRY, NULL, baudRateIndex, MSP_TELEMETRY_INITIAL_PORT_MODE, SERIAL_NOT_INVERTED); if (!mspTelemetryPort) { return; diff --git a/src/main/telemetry/smartport.c b/src/main/telemetry/smartport.c index 8b1e77506..8b58d564e 100644 --- a/src/main/telemetry/smartport.c +++ b/src/main/telemetry/smartport.c @@ -133,7 +133,7 @@ const uint16_t frSkyDataIdTable[] = { }; #define __USE_C99_MATH // for roundf() -#define SMARTPORT_BAUD 57600 +#define SMARTPORT_BAUD BAUD_57600 #define SMARTPORT_UART_MODE MODE_BIDIR #define SMARTPORT_SERVICE_DELAY_MS 5 // telemetry requests comes in at roughly 12 ms intervals, keep this under that #define SMARTPORT_NOT_CONNECTED_TIMEOUT_MS 7000 diff --git a/src/test/unit/telemetry_hott_unittest.cc b/src/test/unit/telemetry_hott_unittest.cc index 2b01e9c51..e536a0c1a 100644 --- a/src/test/unit/telemetry_hott_unittest.cc +++ b/src/test/unit/telemetry_hott_unittest.cc @@ -187,7 +187,7 @@ 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, baudRate_e baudRateIndex, portMode_t mode, serialInversion_e inversion) { UNUSED(identifier); UNUSED(functionMask); UNUSED(baudRate);