From 8cb7abd15f424e82f192980fdbaeff0f71ec6adf Mon Sep 17 00:00:00 2001 From: Martin Budden Date: Sat, 25 Nov 2017 07:06:02 +0000 Subject: [PATCH] Added data parameter to UART RX callback --- src/main/blackbox/blackbox_io.c | 2 +- src/main/drivers/serial.h | 3 ++- src/main/drivers/serial_escserial.c | 4 ++-- src/main/drivers/serial_softserial.c | 5 +++-- src/main/drivers/serial_softserial.h | 2 +- src/main/drivers/serial_tcp.c | 3 ++- src/main/drivers/serial_tcp.h | 2 +- src/main/drivers/serial_uart.h | 2 +- src/main/drivers/serial_uart_hal.c | 3 ++- src/main/drivers/serial_uart_init.c | 3 ++- src/main/drivers/serial_uart_stm32f10x.c | 2 +- src/main/drivers/serial_uart_stm32f30x.c | 2 +- src/main/drivers/serial_uart_stm32f4xx.c | 2 +- src/main/drivers/serial_uart_stm32f7xx.c | 2 +- src/main/interface/cli.c | 2 +- src/main/io/gps.c | 2 +- src/main/io/rcdevice.c | 2 +- src/main/io/serial.c | 10 ++++++---- src/main/io/serial.h | 1 + src/main/io/vtx_smartaudio.c | 4 ++-- src/main/io/vtx_tramp.c | 2 +- src/main/msp/msp_serial.c | 2 +- src/main/rx/crsf.c | 5 ++++- src/main/rx/fport.c | 5 ++++- src/main/rx/ibus.c | 5 ++++- src/main/rx/jetiexbus.c | 5 ++++- src/main/rx/sbus.c | 5 ++++- src/main/rx/spektrum.c | 5 ++++- src/main/rx/sumd.c | 5 ++++- src/main/rx/sumh.c | 6 ++++-- src/main/rx/xbus.c | 5 ++++- src/main/sensors/esc_sensor.c | 6 ++++-- src/main/target/CRAZYFLIE2/serialrx.c | 5 ++++- src/main/telemetry/frsky.c | 2 +- src/main/telemetry/hott.c | 4 ++-- src/main/telemetry/ibus.c | 2 +- src/main/telemetry/ltm.c | 2 +- src/main/telemetry/mavlink.c | 2 +- src/main/telemetry/smartport.c | 2 +- src/test/unit/blackbox_unittest.cc | 2 +- src/test/unit/cli_unittest.cc | 2 +- src/test/unit/io_serial_unittest.cc | 4 ++-- src/test/unit/rcdevice_unittest.cc | 6 +++--- src/test/unit/rx_crsf_unittest.cc | 2 +- src/test/unit/rx_ibus_unittest.cc | 18 ++++++++++-------- src/test/unit/telemetry_crsf_msp_unittest.cc | 2 +- src/test/unit/telemetry_crsf_unittest.cc | 2 +- src/test/unit/telemetry_hott_unittest.cc | 3 ++- src/test/unit/telemetry_ibus_unittest.cc | 5 ++++- 49 files changed, 112 insertions(+), 67 deletions(-) diff --git a/src/main/blackbox/blackbox_io.c b/src/main/blackbox/blackbox_io.c index 9b93ba952..eac6e95c4 100644 --- a/src/main/blackbox/blackbox_io.c +++ b/src/main/blackbox/blackbox_io.c @@ -202,7 +202,7 @@ bool blackboxDeviceOpen(void) portOptions |= SERIAL_STOPBITS_1; } - blackboxPort = openSerialPort(portConfig->identifier, FUNCTION_BLACKBOX, NULL, baudRates[baudRateIndex], + blackboxPort = openSerialPort(portConfig->identifier, FUNCTION_BLACKBOX, NULL, NULL, baudRates[baudRateIndex], BLACKBOX_SERIAL_PORT_MODE, portOptions); /* diff --git a/src/main/drivers/serial.h b/src/main/drivers/serial.h index 1be303602..af8d93a94 100644 --- a/src/main/drivers/serial.h +++ b/src/main/drivers/serial.h @@ -47,7 +47,7 @@ typedef enum { SERIAL_BIDIR_PP = 1 << 4 } portOptions_e; -typedef void (*serialReceiveCallbackPtr)(uint16_t data); // used by serial drivers to return frames to app +typedef void (*serialReceiveCallbackPtr)(uint16_t data, void *rxCallbackData); // used by serial drivers to return frames to app typedef struct serialPort_s { @@ -69,6 +69,7 @@ typedef struct serialPort_s { uint32_t txBufferTail; serialReceiveCallbackPtr rxCallback; + void *rxCallbackData; } serialPort_t; #if defined(USE_SOFTSERIAL1) || defined(USE_SOFTSERIAL2) diff --git a/src/main/drivers/serial_escserial.c b/src/main/drivers/serial_escserial.c index 25feddb38..84b173315 100644 --- a/src/main/drivers/serial_escserial.c +++ b/src/main/drivers/serial_escserial.c @@ -284,7 +284,7 @@ static void extractAndStoreRxByteBL(escSerial_t *escSerial) uint8_t rxByte = (escSerial->internalRxBuffer >> 1) & 0xFF; if (escSerial->port.rxCallback) { - escSerial->port.rxCallback(rxByte); + escSerial->port.rxCallback(rxByte, escSerial->port.rxCallbackData); } else { escSerial->port.rxBuffer[escSerial->port.rxBufferHead] = rxByte; escSerial->port.rxBufferHead = (escSerial->port.rxBufferHead + 1) % escSerial->port.rxBufferSize; @@ -560,7 +560,7 @@ static void extractAndStoreRxByteEsc(escSerial_t *escSerial) uint8_t rxByte = (escSerial->internalRxBuffer) & 0xFF; if (escSerial->port.rxCallback) { - escSerial->port.rxCallback(rxByte); + escSerial->port.rxCallback(rxByte, escSerial->port.rxCallbackData); } else { escSerial->port.rxBuffer[escSerial->port.rxBufferHead] = rxByte; escSerial->port.rxBufferHead = (escSerial->port.rxBufferHead + 1) % escSerial->port.rxBufferSize; diff --git a/src/main/drivers/serial_softserial.c b/src/main/drivers/serial_softserial.c index d1396e89d..c1edcec6b 100644 --- a/src/main/drivers/serial_softserial.c +++ b/src/main/drivers/serial_softserial.c @@ -232,7 +232,7 @@ static void resetBuffers(softSerial_t *softSerial) softSerial->port.txBufferHead = 0; } -serialPort_t *openSoftSerial(softSerialPortIndex_e portIndex, serialReceiveCallbackPtr rxCallback, uint32_t baud, portMode_e mode, portOptions_e options) +serialPort_t *openSoftSerial(softSerialPortIndex_e portIndex, serialReceiveCallbackPtr rxCallback, void *rxCallbackData, uint32_t baud, portMode_e mode, portOptions_e options) { softSerial_t *softSerial = &(softSerialPorts[portIndex]); @@ -296,6 +296,7 @@ serialPort_t *openSoftSerial(softSerialPortIndex_e portIndex, serialReceiveCallb softSerial->port.mode = mode; softSerial->port.options = options; softSerial->port.rxCallback = rxCallback; + softSerial->port.rxCallbackData = rxCallbackData; resetBuffers(softSerial); @@ -444,7 +445,7 @@ void extractAndStoreRxByte(softSerial_t *softSerial) uint8_t rxByte = (softSerial->internalRxBuffer >> 1) & 0xFF; if (softSerial->port.rxCallback) { - softSerial->port.rxCallback(rxByte); + softSerial->port.rxCallback(rxByte, softSerial->port.rxCallbackData); } else { softSerial->port.rxBuffer[softSerial->port.rxBufferHead] = rxByte; softSerial->port.rxBufferHead = (softSerial->port.rxBufferHead + 1) % softSerial->port.rxBufferSize; diff --git a/src/main/drivers/serial_softserial.h b/src/main/drivers/serial_softserial.h index 4bdeaa058..a3d4bb0ca 100644 --- a/src/main/drivers/serial_softserial.h +++ b/src/main/drivers/serial_softserial.h @@ -24,7 +24,7 @@ typedef enum { SOFTSERIAL2 } softSerialPortIndex_e; -serialPort_t *openSoftSerial(softSerialPortIndex_e portIndex, serialReceiveCallbackPtr rxCallback, uint32_t baud, portMode_e mode, portOptions_e options); +serialPort_t *openSoftSerial(softSerialPortIndex_e portIndex, serialReceiveCallbackPtr rxCallback, void *rxCallbackData, uint32_t baud, portMode_e mode, portOptions_e options); // serialPort API void softSerialWriteByte(serialPort_t *instance, uint8_t ch); diff --git a/src/main/drivers/serial_tcp.c b/src/main/drivers/serial_tcp.c index f8c4dcb01..85a52ca1f 100644 --- a/src/main/drivers/serial_tcp.c +++ b/src/main/drivers/serial_tcp.c @@ -111,7 +111,7 @@ static tcpPort_t* tcpReconfigure(tcpPort_t *s, int id) return s; } -serialPort_t *serTcpOpen(int id, serialReceiveCallbackPtr rxCallback, uint32_t baudRate, portMode_e mode, portOptions_e options) +serialPort_t *serTcpOpen(int id, serialReceiveCallbackPtr rxCallback, void *rxCallbackData, uint32_t baudRate, portMode_e mode, portOptions_e options) { tcpPort_t *s = NULL; @@ -135,6 +135,7 @@ serialPort_t *serTcpOpen(int id, serialReceiveCallbackPtr rxCallback, uint32_t b // callback works for IRQ-based RX ONLY s->port.rxCallback = rxCallback; + s->port.rxCallbackData = rxCallbackData; s->port.mode = mode; s->port.baudRate = baudRate; s->port.options = options; diff --git a/src/main/drivers/serial_tcp.h b/src/main/drivers/serial_tcp.h index 07e4e5444..5711f5af3 100644 --- a/src/main/drivers/serial_tcp.h +++ b/src/main/drivers/serial_tcp.h @@ -38,7 +38,7 @@ typedef struct { uint8_t id; } tcpPort_t; -serialPort_t *serTcpOpen(int id, serialReceiveCallbackPtr rxCallback, uint32_t baudRate, portMode_e mode, portOptions_e options); +serialPort_t *serTcpOpen(int id, serialReceiveCallbackPtr rxCallback, void *rxCallbackData, uint32_t baudRate, portMode_e mode, portOptions_e options); // tcpPort API void tcpDataIn(tcpPort_t *instance, uint8_t* ch, int size); diff --git a/src/main/drivers/serial_uart.h b/src/main/drivers/serial_uart.h index 3b9614d86..15c100582 100644 --- a/src/main/drivers/serial_uart.h +++ b/src/main/drivers/serial_uart.h @@ -72,7 +72,7 @@ typedef struct uartPort_s { } uartPort_t; void uartPinConfigure(const serialPinConfig_t *pSerialPinConfig); -serialPort_t *uartOpen(UARTDevice_e device, serialReceiveCallbackPtr rxCallback, uint32_t baudRate, portMode_e mode, portOptions_e options); +serialPort_t *uartOpen(UARTDevice_e device, serialReceiveCallbackPtr rxCallback, void *rxCallbackData, uint32_t baudRate, portMode_e mode, portOptions_e options); // serialPort API void uartWrite(serialPort_t *instance, uint8_t ch); diff --git a/src/main/drivers/serial_uart_hal.c b/src/main/drivers/serial_uart_hal.c index 0b485da4e..29a1cf2ea 100644 --- a/src/main/drivers/serial_uart_hal.c +++ b/src/main/drivers/serial_uart_hal.c @@ -183,7 +183,7 @@ void uartReconfigure(uartPort_t *uartPort) return; } -serialPort_t *uartOpen(UARTDevice_e device, serialReceiveCallbackPtr callback, uint32_t baudRate, portMode_e mode, portOptions_e options) +serialPort_t *uartOpen(UARTDevice_e device, serialReceiveCallbackPtr callback, void *callbackData, uint32_t baudRate, portMode_e mode, portOptions_e options) { uartPort_t *s = serialUART(device, baudRate, mode, options); @@ -198,6 +198,7 @@ serialPort_t *uartOpen(UARTDevice_e device, serialReceiveCallbackPtr callback, u s->port.txBufferHead = s->port.txBufferTail = 0; // callback works for IRQ-based RX ONLY s->port.rxCallback = callback; + s->port.rxCallbackData = callbackData; s->port.mode = mode; s->port.baudRate = baudRate; s->port.options = options; diff --git a/src/main/drivers/serial_uart_init.c b/src/main/drivers/serial_uart_init.c index d27ab0759..b54dd09c9 100644 --- a/src/main/drivers/serial_uart_init.c +++ b/src/main/drivers/serial_uart_init.c @@ -111,7 +111,7 @@ void uartReconfigure(uartPort_t *uartPort) USART_Cmd(uartPort->USARTx, ENABLE); } -serialPort_t *uartOpen(UARTDevice_e device, serialReceiveCallbackPtr rxCallback, uint32_t baudRate, portMode_e mode, portOptions_e options) +serialPort_t *uartOpen(UARTDevice_e device, serialReceiveCallbackPtr rxCallback, void *rxCallbackData, uint32_t baudRate, portMode_e mode, portOptions_e options) { uartPort_t *s = serialUART(device, baudRate, mode, options); @@ -125,6 +125,7 @@ serialPort_t *uartOpen(UARTDevice_e device, serialReceiveCallbackPtr rxCallback, s->port.txBufferHead = s->port.txBufferTail = 0; // callback works for IRQ-based RX ONLY s->port.rxCallback = rxCallback; + s->port.rxCallbackData = rxCallbackData; s->port.mode = mode; s->port.baudRate = baudRate; s->port.options = options; diff --git a/src/main/drivers/serial_uart_stm32f10x.c b/src/main/drivers/serial_uart_stm32f10x.c index 73c5a4f95..4e2e7cf0f 100644 --- a/src/main/drivers/serial_uart_stm32f10x.c +++ b/src/main/drivers/serial_uart_stm32f10x.c @@ -193,7 +193,7 @@ void uartIrqHandler(uartPort_t *s) if (SR & USART_FLAG_RXNE && !s->rxDMAChannel) { // If we registered a callback, pass crap there if (s->port.rxCallback) { - s->port.rxCallback(s->USARTx->DR); + s->port.rxCallback(s->USARTx->DR, s->port.rxCallbackData); } else { s->port.rxBuffer[s->port.rxBufferHead++] = s->USARTx->DR; if (s->port.rxBufferHead >= s->port.rxBufferSize) { diff --git a/src/main/drivers/serial_uart_stm32f30x.c b/src/main/drivers/serial_uart_stm32f30x.c index e626d62f8..b96296252 100644 --- a/src/main/drivers/serial_uart_stm32f30x.c +++ b/src/main/drivers/serial_uart_stm32f30x.c @@ -260,7 +260,7 @@ void uartIrqHandler(uartPort_t *s) if (!s->rxDMAChannel && (ISR & USART_FLAG_RXNE)) { if (s->port.rxCallback) { - s->port.rxCallback(s->USARTx->RDR); + s->port.rxCallback(s->USARTx->RDR, s->port.rxCallbackData); } else { s->port.rxBuffer[s->port.rxBufferHead++] = s->USARTx->RDR; if (s->port.rxBufferHead >= s->port.rxBufferSize) { diff --git a/src/main/drivers/serial_uart_stm32f4xx.c b/src/main/drivers/serial_uart_stm32f4xx.c index 5f8c16d89..ab36cca7a 100644 --- a/src/main/drivers/serial_uart_stm32f4xx.c +++ b/src/main/drivers/serial_uart_stm32f4xx.c @@ -270,7 +270,7 @@ void uartIrqHandler(uartPort_t *s) { if (!s->rxDMAStream && (USART_GetITStatus(s->USARTx, USART_IT_RXNE) == SET)) { if (s->port.rxCallback) { - s->port.rxCallback(s->USARTx->DR); + s->port.rxCallback(s->USARTx->DR, s->port.rxCallbackData); } else { s->port.rxBuffer[s->port.rxBufferHead] = s->USARTx->DR; s->port.rxBufferHead = (s->port.rxBufferHead + 1) % s->port.rxBufferSize; diff --git a/src/main/drivers/serial_uart_stm32f7xx.c b/src/main/drivers/serial_uart_stm32f7xx.c index 78c9ec880..aa97ed43f 100644 --- a/src/main/drivers/serial_uart_stm32f7xx.c +++ b/src/main/drivers/serial_uart_stm32f7xx.c @@ -248,7 +248,7 @@ void uartIrqHandler(uartPort_t *s) uint8_t rbyte = (uint8_t)(huart->Instance->RDR & (uint8_t) 0xff); if (s->port.rxCallback) { - s->port.rxCallback(rbyte); + s->port.rxCallback(rbyte, s->port.rxCallbackData); } else { s->port.rxBuffer[s->port.rxBufferHead] = rbyte; s->port.rxBufferHead = (s->port.rxBufferHead + 1) % s->port.rxBufferSize; diff --git a/src/main/interface/cli.c b/src/main/interface/cli.c index e56448eac..7a6292338 100755 --- a/src/main/interface/cli.c +++ b/src/main/interface/cli.c @@ -926,7 +926,7 @@ static void cliSerialPassthrough(char *cmdline) if (!mode) mode = MODE_RXTX; - passThroughPort = openSerialPort(id, FUNCTION_NONE, NULL, + passThroughPort = openSerialPort(id, FUNCTION_NONE, NULL, NULL, baud, mode, SERIAL_NOT_INVERTED); if (!passThroughPort) { diff --git a/src/main/io/gps.c b/src/main/io/gps.c index cdb1deea7..c0f409f7b 100755 --- a/src/main/io/gps.c +++ b/src/main/io/gps.c @@ -285,7 +285,7 @@ void gpsInit(void) #endif // no callback - buffer will be consumed in gpsUpdate() - gpsPort = openSerialPort(gpsPortConfig->identifier, FUNCTION_GPS, NULL, gpsInitData[gpsData.baudrateIndex].baudrateIndex, mode, SERIAL_NOT_INVERTED); + gpsPort = openSerialPort(gpsPortConfig->identifier, FUNCTION_GPS, NULL, NULL, gpsInitData[gpsData.baudrateIndex].baudrateIndex, mode, SERIAL_NOT_INVERTED); if (!gpsPort) { featureClear(FEATURE_GPS); return; diff --git a/src/main/io/rcdevice.c b/src/main/io/rcdevice.c index cef937618..14c02c6ee 100644 --- a/src/main/io/rcdevice.c +++ b/src/main/io/rcdevice.c @@ -251,7 +251,7 @@ bool runcamDeviceInit(runcamDevice_t *device) serialPortFunction_e portID = FUNCTION_RCDEVICE; serialPortConfig_t *portConfig = findSerialPortConfig(portID); if (portConfig != NULL) { - device->serialPort = openSerialPort(portConfig->identifier, portID, NULL, 115200, MODE_RXTX, SERIAL_NOT_INVERTED); + device->serialPort = openSerialPort(portConfig->identifier, portID, NULL, NULL, 115200, MODE_RXTX, SERIAL_NOT_INVERTED); if (device->serialPort != NULL) { // send RCDEVICE_PROTOCOL_COMMAND_GET_DEVICE_INFO to device to retrive diff --git a/src/main/io/serial.c b/src/main/io/serial.c index a45be6bb3..7dc0f9bbf 100644 --- a/src/main/io/serial.c +++ b/src/main/io/serial.c @@ -332,12 +332,14 @@ serialPort_t *openSerialPort( serialPortIdentifier_e identifier, serialPortFunction_e function, serialReceiveCallbackPtr rxCallback, + void *rxCallbackData, uint32_t baudRate, portMode_e mode, portOptions_e options) { #if !(defined(USE_UART) || defined(USE_SOFTSERIAL1) || defined(USE_SOFTSERIAL2)) UNUSED(rxCallback); + UNUSED(rxCallbackData); UNUSED(baudRate); UNUSED(mode); UNUSED(options); @@ -385,21 +387,21 @@ serialPort_t *openSerialPort( #endif #ifdef SITL // SITL emulates serial ports over TCP - serialPort = serTcpOpen(SERIAL_PORT_IDENTIFIER_TO_UARTDEV(identifier), rxCallback, baudRate, mode, options); + serialPort = serTcpOpen(SERIAL_PORT_IDENTIFIER_TO_UARTDEV(identifier), rxCallback, rxCallbackData, baudRate, mode, options); #else - serialPort = uartOpen(SERIAL_PORT_IDENTIFIER_TO_UARTDEV(identifier), rxCallback, baudRate, mode, options); + serialPort = uartOpen(SERIAL_PORT_IDENTIFIER_TO_UARTDEV(identifier), rxCallback, rxCallbackData, baudRate, mode, options); #endif break; #endif #ifdef USE_SOFTSERIAL1 case SERIAL_PORT_SOFTSERIAL1: - serialPort = openSoftSerial(SOFTSERIAL1, rxCallback, baudRate, mode, options); + serialPort = openSoftSerial(SOFTSERIAL1, rxCallback, rxCallbackData, baudRate, mode, options); break; #endif #ifdef USE_SOFTSERIAL2 case SERIAL_PORT_SOFTSERIAL2: - serialPort = openSoftSerial(SOFTSERIAL2, rxCallback, baudRate, mode, options); + serialPort = openSoftSerial(SOFTSERIAL2, rxCallback, rxCallbackData, baudRate, mode, options); break; #endif default: diff --git a/src/main/io/serial.h b/src/main/io/serial.h index d0e8dea1c..8b6fde54b 100644 --- a/src/main/io/serial.h +++ b/src/main/io/serial.h @@ -150,6 +150,7 @@ serialPort_t *openSerialPort( serialPortIdentifier_e identifier, serialPortFunction_e function, serialReceiveCallbackPtr rxCallback, + void *rxCallbackData, uint32_t baudrate, portMode_e mode, portOptions_e options diff --git a/src/main/io/vtx_smartaudio.c b/src/main/io/vtx_smartaudio.c index e11c29c72..7f74309af 100644 --- a/src/main/io/vtx_smartaudio.c +++ b/src/main/io/vtx_smartaudio.c @@ -673,7 +673,7 @@ bool vtxSmartAudioInit(void) #ifdef SMARTAUDIO_DPRINTF // Setup debugSerialPort - debugSerialPort = openSerialPort(DPRINTF_SERIAL_PORT, FUNCTION_NONE, NULL, 115200, MODE_RXTX, 0); + debugSerialPort = openSerialPort(DPRINTF_SERIAL_PORT, FUNCTION_NONE, NULL, NULL, 115200, MODE_RXTX, 0); if (debugSerialPort) { setPrintfSerialPort(debugSerialPort); dprintf(("smartAudioInit: OK\r\n")); @@ -689,7 +689,7 @@ bool vtxSmartAudioInit(void) portOptions = SERIAL_BIDIR; #endif - smartAudioSerialPort = openSerialPort(portConfig->identifier, FUNCTION_VTX_SMARTAUDIO, NULL, 4800, MODE_RXTX, portOptions); + smartAudioSerialPort = openSerialPort(portConfig->identifier, FUNCTION_VTX_SMARTAUDIO, NULL, NULL, 4800, MODE_RXTX, portOptions); } if (!smartAudioSerialPort) { diff --git a/src/main/io/vtx_tramp.c b/src/main/io/vtx_tramp.c index 7ecb4a7ec..20f2240cd 100644 --- a/src/main/io/vtx_tramp.c +++ b/src/main/io/vtx_tramp.c @@ -603,7 +603,7 @@ bool vtxTrampInit(void) portOptions = SERIAL_BIDIR; #endif - trampSerialPort = openSerialPort(portConfig->identifier, FUNCTION_VTX_TRAMP, NULL, 9600, MODE_RXTX, portOptions); + trampSerialPort = openSerialPort(portConfig->identifier, FUNCTION_VTX_TRAMP, NULL, NULL, 9600, MODE_RXTX, portOptions); } if (!trampSerialPort) { diff --git a/src/main/msp/msp_serial.c b/src/main/msp/msp_serial.c index 03c585886..10980231f 100644 --- a/src/main/msp/msp_serial.c +++ b/src/main/msp/msp_serial.c @@ -52,7 +52,7 @@ void mspSerialAllocatePorts(void) continue; } - serialPort_t *serialPort = openSerialPort(portConfig->identifier, FUNCTION_MSP, NULL, baudRates[portConfig->msp_baudrateIndex], MODE_RXTX, SERIAL_NOT_INVERTED); + serialPort_t *serialPort = openSerialPort(portConfig->identifier, FUNCTION_MSP, NULL, NULL, baudRates[portConfig->msp_baudrateIndex], MODE_RXTX, SERIAL_NOT_INVERTED); if (serialPort) { resetMspPort(mspPort, serialPort); portIndex++; diff --git a/src/main/rx/crsf.c b/src/main/rx/crsf.c index 6aa24c0f2..ac8a0a534 100644 --- a/src/main/rx/crsf.c +++ b/src/main/rx/crsf.c @@ -120,8 +120,10 @@ STATIC_UNIT_TESTED uint8_t crsfFrameCRC(void) } // Receive ISR callback, called back from serial port -STATIC_UNIT_TESTED void crsfDataReceive(uint16_t c) +STATIC_UNIT_TESTED void crsfDataReceive(uint16_t c, void *data) { + UNUSED(data); + static uint8_t crsfFramePosition = 0; const uint32_t currentTimeUs = micros(); @@ -257,6 +259,7 @@ bool crsfRxInit(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig) serialPort = openSerialPort(portConfig->identifier, FUNCTION_RX_SERIAL, crsfDataReceive, + NULL, CRSF_BAUDRATE, CRSF_PORT_MODE, CRSF_PORT_OPTIONS | (rxConfig->serialrx_inverted ? SERIAL_INVERTED : 0) diff --git a/src/main/rx/fport.c b/src/main/rx/fport.c index 3dedc476d..ed624d169 100644 --- a/src/main/rx/fport.c +++ b/src/main/rx/fport.c @@ -140,8 +140,10 @@ static void reportFrameError(uint8_t errorReason) { } // Receive ISR callback -static void fportDataReceive(uint16_t c) +static void fportDataReceive(uint16_t c, void *data) { + UNUSED(data); + static timeUs_t frameStartAt = 0; static bool frameStarting = false; static bool escapedCharacter = false; @@ -353,6 +355,7 @@ bool fportRxInit(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig) fportPort = openSerialPort(portConfig->identifier, FUNCTION_RX_SERIAL, fportDataReceive, + NULL, FPORT_BAUDRATE, MODE_RXTX, FPORT_PORT_OPTIONS | (rxConfig->serialrx_inverted ? 0: SERIAL_INVERTED) | (rxConfig->halfDuplex ? SERIAL_BIDIR : 0) diff --git a/src/main/rx/ibus.c b/src/main/rx/ibus.c index ec2430af3..96302f3a3 100755 --- a/src/main/rx/ibus.c +++ b/src/main/rx/ibus.c @@ -76,8 +76,10 @@ static bool isValidIa6bIbusPacketLength(uint8_t length) // Receive ISR callback -static void ibusDataReceive(uint16_t c) +static void ibusDataReceive(uint16_t c, void *data) { + UNUSED(data); + uint32_t ibusTime; static uint32_t ibusTimeLast; static uint8_t ibusFramePosition; @@ -216,6 +218,7 @@ bool ibusInit(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig) serialPort_t *ibusPort = openSerialPort(portConfig->identifier, FUNCTION_RX_SERIAL, ibusDataReceive, + NULL, IBUS_BAUDRATE, portShared ? MODE_RXTX : MODE_RX, (rxConfig->serialrx_inverted ? SERIAL_INVERTED : 0) | (rxConfig->halfDuplex || portShared ? SERIAL_BIDIR : 0) diff --git a/src/main/rx/jetiexbus.c b/src/main/rx/jetiexbus.c index caa66f273..25f299f9b 100644 --- a/src/main/rx/jetiexbus.c +++ b/src/main/rx/jetiexbus.c @@ -145,8 +145,10 @@ void jetiExBusFrameReset(void) */ // Receive ISR callback -static void jetiExBusDataReceive(uint16_t c) +static void jetiExBusDataReceive(uint16_t c, void *data) { + UNUSED(data); + uint32_t now; static uint32_t jetiExBusTimeLast = 0; static int32_t jetiExBusTimeInterval; @@ -264,6 +266,7 @@ bool jetiExBusInit(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfi jetiExBusPort = openSerialPort(portConfig->identifier, FUNCTION_RX_SERIAL, jetiExBusDataReceive, + NULL, JETIEXBUS_BAUDRATE, MODE_RXTX, JETIEXBUS_OPTIONS | (rxConfig->serialrx_inverted ? SERIAL_INVERTED : 0) | (rxConfig->halfDuplex ? SERIAL_BIDIR : 0) diff --git a/src/main/rx/sbus.c b/src/main/rx/sbus.c index 58cc1d798..6e33ea09a 100644 --- a/src/main/rx/sbus.c +++ b/src/main/rx/sbus.c @@ -100,8 +100,10 @@ typedef union { static sbusFrame_t sbusFrame; // Receive ISR callback -static void sbusDataReceive(uint16_t c) +static void sbusDataReceive(uint16_t c, void *data) { + UNUSED(data); + static uint8_t sbusFramePosition = 0; static uint32_t sbusFrameStartAt = 0; uint32_t now = micros(); @@ -178,6 +180,7 @@ bool sbusInit(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig) serialPort_t *sBusPort = openSerialPort(portConfig->identifier, FUNCTION_RX_SERIAL, sbusDataReceive, + &sbusFrame, SBUS_BAUDRATE, portShared ? MODE_RXTX : MODE_RX, SBUS_PORT_OPTIONS | (rxConfig->serialrx_inverted ? 0 : SERIAL_INVERTED) | (rxConfig->halfDuplex ? SERIAL_BIDIR : 0) diff --git a/src/main/rx/spektrum.c b/src/main/rx/spektrum.c index 6ca6fe53d..0c60131a7 100644 --- a/src/main/rx/spektrum.c +++ b/src/main/rx/spektrum.c @@ -323,8 +323,10 @@ const uint8_t vtxTrampPi[] = { // Spektrum Spec Tx menu Tx sends // Receive ISR callback -static void spektrumDataReceive(uint16_t c) +static void spektrumDataReceive(uint16_t c, void *data) { + UNUSED(data); + uint32_t spekTime, spekTimeInterval; static uint32_t spekTimeLast = 0; static uint8_t spekFramePosition = 0; @@ -663,6 +665,7 @@ bool spektrumInit(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig serialPort = openSerialPort(portConfig->identifier, FUNCTION_RX_SERIAL, spektrumDataReceive, + NULL, SPEKTRUM_BAUDRATE, portShared || srxlEnabled ? MODE_RXTX : MODE_RX, (rxConfig->serialrx_inverted ? SERIAL_INVERTED : 0) | ((srxlEnabled || rxConfig->halfDuplex) ? SERIAL_BIDIR : 0) diff --git a/src/main/rx/sumd.c b/src/main/rx/sumd.c index 0a6ccb205..88a817894 100644 --- a/src/main/rx/sumd.c +++ b/src/main/rx/sumd.c @@ -55,8 +55,10 @@ static uint8_t sumd[SUMD_BUFFSIZE] = { 0, }; static uint8_t sumdChannelCount; // Receive ISR callback -static void sumdDataReceive(uint16_t c) +static void sumdDataReceive(uint16_t c, void *data) { + UNUSED(data); + uint32_t sumdTime; static uint32_t sumdTimeLast; static uint8_t sumdIndex; @@ -167,6 +169,7 @@ bool sumdInit(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig) serialPort_t *sumdPort = openSerialPort(portConfig->identifier, FUNCTION_RX_SERIAL, sumdDataReceive, + NULL, SUMD_BAUDRATE, portShared ? MODE_RXTX : MODE_RX, (rxConfig->serialrx_inverted ? SERIAL_INVERTED : 0) | (rxConfig->halfDuplex ? SERIAL_BIDIR : 0) diff --git a/src/main/rx/sumh.c b/src/main/rx/sumh.c index 53e058d74..a6552f6ad 100644 --- a/src/main/rx/sumh.c +++ b/src/main/rx/sumh.c @@ -58,8 +58,10 @@ static serialPort_t *sumhPort; // Receive ISR callback -static void sumhDataReceive(uint16_t c) +static void sumhDataReceive(uint16_t c, void *data) { + UNUSED(data); + uint32_t sumhTime; static uint32_t sumhTimeLast, sumhTimeInterval; static uint8_t sumhFramePosition; @@ -133,7 +135,7 @@ bool sumhInit(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig) bool portShared = false; #endif - sumhPort = openSerialPort(portConfig->identifier, FUNCTION_RX_SERIAL, sumhDataReceive, SUMH_BAUDRATE, portShared ? MODE_RXTX : MODE_RX, (rxConfig->serialrx_inverted ? SERIAL_INVERTED : 0)); + sumhPort = openSerialPort(portConfig->identifier, FUNCTION_RX_SERIAL, sumhDataReceive, NULL, SUMH_BAUDRATE, portShared ? MODE_RXTX : MODE_RX, (rxConfig->serialrx_inverted ? SERIAL_INVERTED : 0)); #ifdef USE_TELEMETRY if (portShared) { diff --git a/src/main/rx/xbus.c b/src/main/rx/xbus.c index e9aae3fd4..471193e6b 100644 --- a/src/main/rx/xbus.c +++ b/src/main/rx/xbus.c @@ -181,8 +181,10 @@ static void xBusUnpackRJ01Frame(void) } // Receive ISR callback -static void xBusDataReceive(uint16_t c) +static void xBusDataReceive(uint16_t c, void *data) { + UNUSED(data); + uint32_t now; static uint32_t xBusTimeLast, xBusTimeInterval; @@ -301,6 +303,7 @@ bool xBusInit(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig) serialPort_t *xBusPort = openSerialPort(portConfig->identifier, FUNCTION_RX_SERIAL, xBusDataReceive, + NULL, baudRate, portShared ? MODE_RXTX : MODE_RX, (rxConfig->serialrx_inverted ? SERIAL_INVERTED : 0) | (rxConfig->halfDuplex ? SERIAL_BIDIR : 0) diff --git a/src/main/sensors/esc_sensor.c b/src/main/sensors/esc_sensor.c index 898af2a79..523da5ee5 100644 --- a/src/main/sensors/esc_sensor.c +++ b/src/main/sensors/esc_sensor.c @@ -180,8 +180,10 @@ escSensorData_t *getEscSensorData(uint8_t motorNumber) } // Receive ISR callback -static void escSensorDataReceive(uint16_t c) +static void escSensorDataReceive(uint16_t c, void *data) { + UNUSED(data); + // KISS ESC sends some data during startup, ignore this for now (maybe future use) // startup data could be firmware version and serialnumber @@ -202,7 +204,7 @@ bool escSensorInit(void) portOptions_e options = SERIAL_NOT_INVERTED | (escSensorConfig()->halfDuplex ? SERIAL_BIDIR : 0); // Initialize serial port - escSensorPort = openSerialPort(portConfig->identifier, FUNCTION_ESC_SENSOR, escSensorDataReceive, ESC_SENSOR_BAUDRATE, MODE_RX, options); + escSensorPort = openSerialPort(portConfig->identifier, FUNCTION_ESC_SENSOR, escSensorDataReceive, NULL, ESC_SENSOR_BAUDRATE, MODE_RX, options); for (int i = 0; i < MAX_SUPPORTED_MOTORS; i = i + 1) { escSensorData[i].dataAge = ESC_DATA_INVALID; diff --git a/src/main/target/CRAZYFLIE2/serialrx.c b/src/main/target/CRAZYFLIE2/serialrx.c index 3d9b6b074..f58015ae7 100644 --- a/src/main/target/CRAZYFLIE2/serialrx.c +++ b/src/main/target/CRAZYFLIE2/serialrx.c @@ -121,8 +121,10 @@ static void routeIncommingPacket(syslinkPacket_t* slp) } // Receive ISR callback -static void dataReceive(uint16_t c) +static void dataReceive(uint16_t c, void *data) { + UNUSED(data); + counter++; switch (rxState) { case waitForFirstStart: @@ -223,6 +225,7 @@ bool targetCustomSerialRxInit(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxR serialPort = openSerialPort(portConfig->identifier, FUNCTION_RX_SERIAL, dataReceive, + NULL, SYSLINK_BAUDRATE, MODE_RX, SERIAL_NOT_INVERTED | SERIAL_STOPBITS_1 | SERIAL_PARITY_NO diff --git a/src/main/telemetry/frsky.c b/src/main/telemetry/frsky.c index 81ab4f52f..1d12406ce 100644 --- a/src/main/telemetry/frsky.c +++ b/src/main/telemetry/frsky.c @@ -486,7 +486,7 @@ void freeFrSkyTelemetryPort(void) static void configureFrSkyTelemetryPort(void) { if (portConfig) { - frskyPort = openSerialPort(portConfig->identifier, FUNCTION_TELEMETRY_FRSKY, NULL, FRSKY_BAUDRATE, FRSKY_INITIAL_PORT_MODE, telemetryConfig()->telemetry_inverted ? SERIAL_NOT_INVERTED : SERIAL_INVERTED); + frskyPort = openSerialPort(portConfig->identifier, FUNCTION_TELEMETRY_FRSKY, NULL, NULL, FRSKY_BAUDRATE, FRSKY_INITIAL_PORT_MODE, telemetryConfig()->telemetry_inverted ? SERIAL_NOT_INVERTED : SERIAL_INVERTED); if (!frskyPort) { return; } diff --git a/src/main/telemetry/hott.c b/src/main/telemetry/hott.c index 833207f81..d53bb3a9c 100644 --- a/src/main/telemetry/hott.c +++ b/src/main/telemetry/hott.c @@ -329,7 +329,7 @@ static void workAroundForHottTelemetryOnUsart(serialPort_t *instance, portMode_e portOptions |= SERIAL_BIDIR; } - hottPort = openSerialPort(instance->identifier, FUNCTION_TELEMETRY_HOTT, NULL, HOTT_BAUDRATE, mode, portOptions); + hottPort = openSerialPort(instance->identifier, FUNCTION_TELEMETRY_HOTT, NULL, NULL, HOTT_BAUDRATE, mode, portOptions); } static bool hottIsUsingHardwareUART(void) @@ -374,7 +374,7 @@ void configureHoTTTelemetryPort(void) portOptions |= SERIAL_BIDIR; } - hottPort = openSerialPort(portConfig->identifier, FUNCTION_TELEMETRY_HOTT, NULL, HOTT_BAUDRATE, HOTT_PORT_MODE, portOptions); + hottPort = openSerialPort(portConfig->identifier, FUNCTION_TELEMETRY_HOTT, NULL, NULL, HOTT_BAUDRATE, HOTT_PORT_MODE, portOptions); if (!hottPort) { return; diff --git a/src/main/telemetry/ibus.c b/src/main/telemetry/ibus.c index 38ddc390a..b826a3c2b 100644 --- a/src/main/telemetry/ibus.c +++ b/src/main/telemetry/ibus.c @@ -152,7 +152,7 @@ void configureIbusTelemetryPort(void) return; } - ibusSerialPort = openSerialPort(ibusSerialPortConfig->identifier, FUNCTION_TELEMETRY_IBUS, NULL, IBUS_BAUDRATE, IBUS_UART_MODE, SERIAL_BIDIR | (telemetryConfig()->telemetry_inverted ? SERIAL_INVERTED : SERIAL_NOT_INVERTED)); + ibusSerialPort = openSerialPort(ibusSerialPortConfig->identifier, FUNCTION_TELEMETRY_IBUS, NULL, NULL, IBUS_BAUDRATE, IBUS_UART_MODE, SERIAL_BIDIR | (telemetryConfig()->telemetry_inverted ? SERIAL_INVERTED : SERIAL_NOT_INVERTED)); if (!ibusSerialPort) { return; diff --git a/src/main/telemetry/ltm.c b/src/main/telemetry/ltm.c index 233e7ee11..7328171c2 100644 --- a/src/main/telemetry/ltm.c +++ b/src/main/telemetry/ltm.c @@ -282,7 +282,7 @@ void configureLtmTelemetryPort(void) if (baudRateIndex == BAUD_AUTO) { baudRateIndex = BAUD_19200; } - ltmPort = openSerialPort(portConfig->identifier, FUNCTION_TELEMETRY_LTM, NULL, baudRates[baudRateIndex], TELEMETRY_LTM_INITIAL_PORT_MODE, telemetryConfig()->telemetry_inverted ? SERIAL_INVERTED : SERIAL_NOT_INVERTED); + ltmPort = openSerialPort(portConfig->identifier, FUNCTION_TELEMETRY_LTM, NULL, NULL, baudRates[baudRateIndex], TELEMETRY_LTM_INITIAL_PORT_MODE, telemetryConfig()->telemetry_inverted ? SERIAL_INVERTED : SERIAL_NOT_INVERTED); if (!ltmPort) return; ltmEnabled = true; diff --git a/src/main/telemetry/mavlink.c b/src/main/telemetry/mavlink.c index bc8fe8670..a01a63f88 100755 --- a/src/main/telemetry/mavlink.c +++ b/src/main/telemetry/mavlink.c @@ -158,7 +158,7 @@ void configureMAVLinkTelemetryPort(void) baudRateIndex = BAUD_57600; } - mavlinkPort = openSerialPort(portConfig->identifier, FUNCTION_TELEMETRY_MAVLINK, NULL, baudRates[baudRateIndex], TELEMETRY_MAVLINK_INITIAL_PORT_MODE, telemetryConfig()->telemetry_inverted ? SERIAL_INVERTED : SERIAL_NOT_INVERTED); + mavlinkPort = openSerialPort(portConfig->identifier, FUNCTION_TELEMETRY_MAVLINK, NULL, NULL, baudRates[baudRateIndex], TELEMETRY_MAVLINK_INITIAL_PORT_MODE, telemetryConfig()->telemetry_inverted ? SERIAL_INVERTED : SERIAL_NOT_INVERTED); if (!mavlinkPort) { return; diff --git a/src/main/telemetry/smartport.c b/src/main/telemetry/smartport.c index 7ccddee3a..dea2d4aa4 100644 --- a/src/main/telemetry/smartport.c +++ b/src/main/telemetry/smartport.c @@ -309,7 +309,7 @@ static void configureSmartPortTelemetryPort(void) portOptions_e portOptions = (telemetryConfig()->halfDuplex ? SERIAL_BIDIR : SERIAL_UNIDIR) | (telemetryConfig()->telemetry_inverted ? SERIAL_NOT_INVERTED : SERIAL_INVERTED); - smartPortSerialPort = openSerialPort(portConfig->identifier, FUNCTION_TELEMETRY_SMARTPORT, NULL, SMARTPORT_BAUD, SMARTPORT_UART_MODE, portOptions); + smartPortSerialPort = openSerialPort(portConfig->identifier, FUNCTION_TELEMETRY_SMARTPORT, NULL, NULL, SMARTPORT_BAUD, SMARTPORT_UART_MODE, portOptions); } void checkSmartPortTelemetryState(void) diff --git a/src/test/unit/blackbox_unittest.cc b/src/test/unit/blackbox_unittest.cc index 3ac929f89..5e39e4fd0 100644 --- a/src/test/unit/blackbox_unittest.cc +++ b/src/test/unit/blackbox_unittest.cc @@ -389,7 +389,7 @@ bool feature(uint32_t) {return false;} void mspSerialReleasePortIfAllocated(serialPort_t *) {} serialPortConfig_t *findSerialPortConfig(serialPortFunction_e ) {return NULL;} serialPort_t *findSharedSerialPort(uint16_t , serialPortFunction_e ) {return NULL;} -serialPort_t *openSerialPort(serialPortIdentifier_e, serialPortFunction_e, serialReceiveCallbackPtr, uint32_t, portMode_e, portOptions_e) {return NULL;} +serialPort_t *openSerialPort(serialPortIdentifier_e, serialPortFunction_e, serialReceiveCallbackPtr, void *, uint32_t, portMode_e, portOptions_e) {return NULL;} void closeSerialPort(serialPort_t *) {} portSharing_e determinePortSharing(const serialPortConfig_t *, serialPortFunction_e ) {return PORTSHARING_UNUSED;} failsafePhase_e failsafePhase(void) {return FAILSAFE_IDLE;} diff --git a/src/test/unit/cli_unittest.cc b/src/test/unit/cli_unittest.cc index 1787d5085..75f51d61d 100644 --- a/src/test/unit/cli_unittest.cc +++ b/src/test/unit/cli_unittest.cc @@ -212,7 +212,7 @@ void writeEEPROM() {} serialPortConfig_t *serialFindPortConfiguration(serialPortIdentifier_e) {return NULL; } baudRate_e lookupBaudRateIndex(uint32_t){return BAUD_9600; } serialPortUsage_t *findSerialPortUsageByIdentifier(serialPortIdentifier_e){ return NULL; } -serialPort_t *openSerialPort(serialPortIdentifier_e, serialPortFunction_e, serialReceiveCallbackPtr, uint32_t, portMode_e, portOptions_e) { return NULL; } +serialPort_t *openSerialPort(serialPortIdentifier_e, serialPortFunction_e, serialReceiveCallbackPtr, void *, uint32_t, portMode_e, portOptions_e) { return NULL; } void serialSetBaudRate(serialPort_t *, uint32_t) {} void serialSetMode(serialPort_t *, portMode_e) {} void serialPassthrough(serialPort_t *, serialPort_t *, serialConsumer *, serialConsumer *) {} diff --git a/src/test/unit/io_serial_unittest.cc b/src/test/unit/io_serial_unittest.cc index 8f77a4cd5..b35ffdedb 100644 --- a/src/test/unit/io_serial_unittest.cc +++ b/src/test/unit/io_serial_unittest.cc @@ -64,11 +64,11 @@ extern "C" { serialPort_t *usbVcpOpen(void) { return NULL; } - serialPort_t *uartOpen(UARTDevice_e, serialReceiveCallbackPtr, uint32_t, portMode_e, portOptions_e) { + serialPort_t *uartOpen(UARTDevice_e, serialReceiveCallbackPtr, void *, uint32_t, portMode_e, portOptions_e) { return NULL; } - serialPort_t *openSoftSerial(softSerialPortIndex_e, serialReceiveCallbackPtr, uint32_t, portMode_e, portOptions_e) { + serialPort_t *openSoftSerial(softSerialPortIndex_e, serialReceiveCallbackPtr, void *, uint32_t, portMode_e, portOptions_e) { return NULL; } } diff --git a/src/test/unit/rcdevice_unittest.cc b/src/test/unit/rcdevice_unittest.cc index 299b4885f..d514034c9 100644 --- a/src/test/unit/rcdevice_unittest.cc +++ b/src/test/unit/rcdevice_unittest.cc @@ -1381,12 +1381,11 @@ TEST(RCDeviceTest, TestDSAInfoAccessProtocol) } extern "C" { - serialPort_t *openSerialPort(serialPortIdentifier_e identifier, serialPortFunction_e functionMask, serialReceiveCallbackPtr callback, uint32_t baudRate, portMode_e mode, portOptions_e options) + serialPort_t *openSerialPort(serialPortIdentifier_e identifier, serialPortFunction_e functionMask, serialReceiveCallbackPtr callback, void *callbackData, uint32_t baudRate, portMode_e mode, portOptions_e options) { UNUSED(identifier); UNUSED(functionMask); UNUSED(baudRate); - UNUSED(callback); UNUSED(mode); UNUSED(options); @@ -1403,7 +1402,8 @@ extern "C" { s.txBuffer = s.txBuffer; // callback works for IRQ-based RX ONLY - s.rxCallback = NULL; + s.rxCallback = callback; + s.rxCallbackData = callbackData; s.baudRate = 0; return (serialPort_t *)&s; diff --git a/src/test/unit/rx_crsf_unittest.cc b/src/test/unit/rx_crsf_unittest.cc index 8b1a9e450..0e6abfef8 100644 --- a/src/test/unit/rx_crsf_unittest.cc +++ b/src/test/unit/rx_crsf_unittest.cc @@ -281,7 +281,7 @@ extern "C" { int16_t debug[DEBUG16_VALUE_COUNT]; uint32_t micros(void) {return dummyTimeUs;} -serialPort_t *openSerialPort(serialPortIdentifier_e, serialPortFunction_e, serialReceiveCallbackPtr, uint32_t, portMode_e, portOptions_e) {return NULL;} +serialPort_t *openSerialPort(serialPortIdentifier_e, serialPortFunction_e, serialReceiveCallbackPtr, void *, uint32_t, portMode_e, portOptions_e) {return NULL;} serialPortConfig_t *findSerialPortConfig(serialPortFunction_e ) {return NULL;} bool telemetryCheckRxPortShared(const serialPortConfig_t *) {return false;} serialPort_t *telemetrySharedPort = NULL; diff --git a/src/test/unit/rx_ibus_unittest.cc b/src/test/unit/rx_ibus_unittest.cc index bca2bee45..d070fd912 100644 --- a/src/test/unit/rx_ibus_unittest.cc +++ b/src/test/unit/rx_ibus_unittest.cc @@ -111,6 +111,7 @@ serialPort_t *openSerialPort( serialPortIdentifier_e identifier, serialPortFunction_e function, serialReceiveCallbackPtr callback, + void *callbackData, uint32_t baudrate, portMode_e mode, portOptions_e options @@ -118,6 +119,7 @@ serialPort_t *openSerialPort( { openSerial_called = true; EXPECT_FALSE(NULL == callback); + EXPECT_TRUE(NULL == callbackData); EXPECT_EQ(identifier, SERIAL_PORT_DUMMY_IDENTIFIER); EXPECT_EQ(options, serialExpectedOptions); EXPECT_EQ(function, FUNCTION_RX_SERIAL); @@ -263,7 +265,7 @@ protected: EXPECT_EQ(RX_FRAME_PENDING, rxRuntimeConfig.rcFrameStatusFn()); for (size_t i=0; i < length; i++) { EXPECT_EQ(RX_FRAME_PENDING, rxRuntimeConfig.rcFrameStatusFn()); - stub_serialRxCallback(packet[i]); + stub_serialRxCallback(packet[i], NULL); } } }; @@ -287,7 +289,7 @@ TEST_F(IbusRxProtocollUnitTest, Test_IA6B_OnePacketReceived) for (size_t i=0; i < sizeof(packet); i++) { EXPECT_EQ(RX_FRAME_PENDING, rxRuntimeConfig.rcFrameStatusFn()); - stub_serialRxCallback(packet[i]); + stub_serialRxCallback(packet[i], NULL); } //report frame complete once @@ -312,7 +314,7 @@ TEST_F(IbusRxProtocollUnitTest, Test_IA6B_OnePacketReceivedWithBadCrc) isChecksumOkReturnValue = false; for (size_t i=0; i < sizeof(packet); i++) { EXPECT_EQ(RX_FRAME_PENDING, rxRuntimeConfig.rcFrameStatusFn()); - stub_serialRxCallback(packet[i]); + stub_serialRxCallback(packet[i], NULL); } //no frame complete @@ -338,7 +340,7 @@ TEST_F(IbusRxProtocollUnitTest, Test_IA6B_HalfPacketReceived_then_interPacketGap for (size_t i=0; i < sizeof(packet_half); i++) { EXPECT_EQ(RX_FRAME_PENDING, rxRuntimeConfig.rcFrameStatusFn()); - stub_serialRxCallback(packet_half[i]); + stub_serialRxCallback(packet_half[i], NULL); } microseconds_stub_value += 5000; @@ -346,7 +348,7 @@ TEST_F(IbusRxProtocollUnitTest, Test_IA6B_HalfPacketReceived_then_interPacketGap for (size_t i=0; i < sizeof(packet_full); i++) { EXPECT_EQ(RX_FRAME_PENDING, rxRuntimeConfig.rcFrameStatusFn()); - stub_serialRxCallback(packet_full[i]); + stub_serialRxCallback(packet_full[i], NULL); } //report frame complete once @@ -370,7 +372,7 @@ TEST_F(IbusRxProtocollUnitTest, Test_IA6_OnePacketReceived) for (size_t i=0; i < sizeof(packet); i++) { EXPECT_EQ(RX_FRAME_PENDING, rxRuntimeConfig.rcFrameStatusFn()); - stub_serialRxCallback(packet[i]); + stub_serialRxCallback(packet[i], NULL); } //report frame complete once @@ -394,7 +396,7 @@ TEST_F(IbusRxProtocollUnitTest, Test_IA6_OnePacketReceivedBadCrc) for (size_t i=0; i < sizeof(packet); i++) { EXPECT_EQ(RX_FRAME_PENDING, rxRuntimeConfig.rcFrameStatusFn()); - stub_serialRxCallback(packet[i]); + stub_serialRxCallback(packet[i], NULL); } //no frame complete @@ -436,7 +438,7 @@ TEST_F(IbusRxProtocollUnitTest, Test_IA6B_OnePacketReceived_not_shared_port) for (size_t i=0; i < sizeof(packet); i++) { EXPECT_EQ(RX_FRAME_PENDING, rxRuntimeConfig.rcFrameStatusFn()); - stub_serialRxCallback(packet[i]); + stub_serialRxCallback(packet[i], NULL); } //report frame complete once diff --git a/src/test/unit/telemetry_crsf_msp_unittest.cc b/src/test/unit/telemetry_crsf_msp_unittest.cc index 724542682..ea31f172e 100644 --- a/src/test/unit/telemetry_crsf_msp_unittest.cc +++ b/src/test/unit/telemetry_crsf_msp_unittest.cc @@ -252,7 +252,7 @@ extern "C" { attitudeEulerAngles_t attitude = { { 0, 0, 0 } }; uint32_t micros(void) {return dummyTimeUs;} - serialPort_t *openSerialPort(serialPortIdentifier_e, serialPortFunction_e, serialReceiveCallbackPtr, uint32_t, portMode_e, portOptions_e) {return NULL;} + serialPort_t *openSerialPort(serialPortIdentifier_e, serialPortFunction_e, serialReceiveCallbackPtr, void *, uint32_t, portMode_e, portOptions_e) {return NULL;} serialPortConfig_t *findSerialPortConfig(serialPortFunction_e ) {return NULL;} uint16_t getBatteryVoltage(void) { return testBatteryVoltage; diff --git a/src/test/unit/telemetry_crsf_unittest.cc b/src/test/unit/telemetry_crsf_unittest.cc index 7571f7916..e2821313b 100644 --- a/src/test/unit/telemetry_crsf_unittest.cc +++ b/src/test/unit/telemetry_crsf_unittest.cc @@ -300,7 +300,7 @@ uint8_t serialRead(serialPort_t *) {return 0;} void serialWrite(serialPort_t *, uint8_t) {} void serialWriteBuf(serialPort_t *, const uint8_t *, int) {} void serialSetMode(serialPort_t *, portMode_e) {} -serialPort_t *openSerialPort(serialPortIdentifier_e, serialPortFunction_e, serialReceiveCallbackPtr, uint32_t, portMode_e, portOptions_e) {return NULL;} +serialPort_t *openSerialPort(serialPortIdentifier_e, serialPortFunction_e, serialReceiveCallbackPtr, void *, uint32_t, portMode_e, portOptions_e) {return NULL;} void closeSerialPort(serialPort_t *) {} bool isSerialTransmitBufferEmpty(const serialPort_t *) { return true; } diff --git a/src/test/unit/telemetry_hott_unittest.cc b/src/test/unit/telemetry_hott_unittest.cc index 20ec7dc9a..ec5df96c0 100644 --- a/src/test/unit/telemetry_hott_unittest.cc +++ b/src/test/unit/telemetry_hott_unittest.cc @@ -219,12 +219,13 @@ void serialSetMode(serialPort_t *instance, portMode_e mode) UNUSED(mode); } -serialPort_t *openSerialPort(serialPortIdentifier_e identifier, serialPortFunction_e functionMask, serialReceiveCallbackPtr callback, uint32_t baudRate, portMode_e mode, portOptions_e options) +serialPort_t *openSerialPort(serialPortIdentifier_e identifier, serialPortFunction_e functionMask, serialReceiveCallbackPtr callback, void *callbackData, uint32_t baudRate, portMode_e mode, portOptions_e options) { UNUSED(identifier); UNUSED(functionMask); UNUSED(baudRate); UNUSED(callback); + UNUSED(callbackData); UNUSED(mode); UNUSED(options); diff --git a/src/test/unit/telemetry_ibus_unittest.cc b/src/test/unit/telemetry_ibus_unittest.cc index a512ab2ee..bded7e50d 100644 --- a/src/test/unit/telemetry_ibus_unittest.cc +++ b/src/test/unit/telemetry_ibus_unittest.cc @@ -20,6 +20,7 @@ extern "C" { #include +#include "common/utils.h" #include "config/parameter_group.h" #include "drivers/serial.h" #include "io/serial.h" @@ -140,13 +141,15 @@ serialPort_t *openSerialPort( serialPortIdentifier_e identifier, serialPortFunction_e function, serialReceiveCallbackPtr callback, + void *callbackData, uint32_t baudrate, portMode_e mode, portOptions_e options ) { openSerial_called = true; - (void) callback; + UNUSED(callback); + UNUSED(callbackData); EXPECT_EQ(SERIAL_PORT_DUMMY_IDENTIFIER, identifier); EXPECT_EQ(SERIAL_BIDIR, options); EXPECT_EQ(FUNCTION_TELEMETRY_IBUS, function);