From 944fe0761c58dadffc9b41ebe7d9383bb754e825 Mon Sep 17 00:00:00 2001 From: Martin Budden Date: Sat, 29 Jul 2017 12:34:27 +0100 Subject: [PATCH] Tidied UART enum definitions --- src/main/blackbox/blackbox_io.c | 2 +- src/main/drivers/serial.c | 2 +- src/main/drivers/serial.h | 16 ++++++++-------- src/main/drivers/serial_escserial.c | 6 +++--- src/main/drivers/serial_softserial.c | 4 ++-- src/main/drivers/serial_softserial.h | 2 +- src/main/drivers/serial_tcp.c | 2 +- src/main/drivers/serial_tcp.h | 2 +- src/main/drivers/serial_uart.c | 2 +- src/main/drivers/serial_uart.h | 8 ++++---- src/main/drivers/serial_uart_hal.c | 9 +++------ src/main/drivers/serial_uart_impl.h | 5 ++--- src/main/drivers/serial_uart_init.c | 2 +- src/main/drivers/serial_uart_pinconfig.c | 2 +- src/main/drivers/serial_uart_stm32f10x.c | 2 +- src/main/drivers/serial_uart_stm32f30x.c | 8 +++----- src/main/drivers/serial_uart_stm32f4xx.c | 6 ++---- src/main/drivers/serial_uart_stm32f7xx.c | 2 +- src/main/drivers/serial_usb_vcp.c | 2 +- src/main/io/gps.c | 2 +- src/main/io/serial.c | 4 ++-- src/main/io/serial.h | 4 ++-- src/main/sensors/esc_sensor.c | 2 +- src/main/telemetry/hott.c | 6 +++--- src/main/telemetry/smartport.c | 2 +- src/test/unit/blackbox_unittest.cc | 2 +- src/test/unit/cli_unittest.cc | 4 ++-- src/test/unit/io_serial_unittest.cc | 4 ++-- src/test/unit/rcsplit_unittest.cc | 2 +- src/test/unit/rx_crsf_unittest.cc | 2 +- src/test/unit/rx_ibus_unittest.cc | 8 ++++---- src/test/unit/telemetry_crsf_unittest.cc | 4 ++-- src/test/unit/telemetry_hott_unittest.cc | 4 ++-- src/test/unit/telemetry_ibus_unittest.cc | 4 ++-- 34 files changed, 65 insertions(+), 73 deletions(-) diff --git a/src/main/blackbox/blackbox_io.c b/src/main/blackbox/blackbox_io.c index d74f243a2d..3b21dc835b 100644 --- a/src/main/blackbox/blackbox_io.c +++ b/src/main/blackbox/blackbox_io.c @@ -183,7 +183,7 @@ bool blackboxDeviceOpen(void) { serialPortConfig_t *portConfig = findSerialPortConfig(FUNCTION_BLACKBOX); baudRate_e baudRateIndex; - portOptions_t portOptions = SERIAL_PARITY_NO | SERIAL_NOT_INVERTED; + portOptions_e portOptions = SERIAL_PARITY_NO | SERIAL_NOT_INVERTED; if (!portConfig) { return false; diff --git a/src/main/drivers/serial.c b/src/main/drivers/serial.c index d1439b0667..32d5ac8af2 100644 --- a/src/main/drivers/serial.c +++ b/src/main/drivers/serial.c @@ -81,7 +81,7 @@ bool isSerialTransmitBufferEmpty(const serialPort_t *instance) return instance->vTable->isSerialTransmitBufferEmpty(instance); } -void serialSetMode(serialPort_t *instance, portMode_t mode) +void serialSetMode(serialPort_t *instance, portMode_e mode) { instance->vTable->setMode(instance, mode); } diff --git a/src/main/drivers/serial.h b/src/main/drivers/serial.h index d09e37d0ff..1be3036023 100644 --- a/src/main/drivers/serial.h +++ b/src/main/drivers/serial.h @@ -20,13 +20,13 @@ #include "drivers/io.h" #include "config/parameter_group.h" -typedef enum portMode_t { +typedef enum { MODE_RX = 1 << 0, MODE_TX = 1 << 1, MODE_RXTX = MODE_RX | MODE_TX -} portMode_t; +} portMode_e; -typedef enum portOptions_t { +typedef enum { SERIAL_NOT_INVERTED = 0 << 0, SERIAL_INVERTED = 1 << 0, SERIAL_STOPBITS_1 = 0 << 1, @@ -45,7 +45,7 @@ typedef enum portOptions_t { */ SERIAL_BIDIR_OD = 0 << 4, SERIAL_BIDIR_PP = 1 << 4 -} portOptions_t; +} portOptions_e; typedef void (*serialReceiveCallbackPtr)(uint16_t data); // used by serial drivers to return frames to app @@ -54,8 +54,8 @@ typedef struct serialPort_s { const struct serialPortVTable *vTable; uint8_t identifier; - portMode_t mode; - portOptions_t options; + portMode_e mode; + portOptions_e options; uint32_t baudRate; @@ -102,7 +102,7 @@ struct serialPortVTable { bool (*isSerialTransmitBufferEmpty)(const serialPort_t *instance); - void (*setMode)(serialPort_t *instance, portMode_t mode); + void (*setMode)(serialPort_t *instance, portMode_e mode); void (*writeBuf)(serialPort_t *instance, const void *data, int count); // Optional functions used to buffer large writes. @@ -116,7 +116,7 @@ uint32_t serialTxBytesFree(const serialPort_t *instance); void serialWriteBuf(serialPort_t *instance, const uint8_t *data, int count); uint8_t serialRead(serialPort_t *instance); void serialSetBaudRate(serialPort_t *instance, uint32_t baudRate); -void serialSetMode(serialPort_t *instance, portMode_t mode); +void serialSetMode(serialPort_t *instance, portMode_e mode); bool isSerialTransmitBufferEmpty(const serialPort_t *instance); void serialPrint(serialPort_t *instance, const char *str); uint32_t serialGetBaudRate(serialPort_t *instance); diff --git a/src/main/drivers/serial_escserial.c b/src/main/drivers/serial_escserial.c index 44e924411c..07bb0b81f7 100644 --- a/src/main/drivers/serial_escserial.c +++ b/src/main/drivers/serial_escserial.c @@ -419,7 +419,7 @@ static void onSerialRxPinChangeBL(timerCCHandlerRec_t *cbRec, captureCompare_t c } } -static void serialTimerRxConfigBL(const timerHardware_t *timerHardwarePtr, uint8_t reference, portOptions_t options) +static void serialTimerRxConfigBL(const timerHardware_t *timerHardwarePtr, uint8_t reference, portOptions_e options) { // start bit is usually a FALLING signal TIM_DeInit(timerHardwarePtr->tim); @@ -654,7 +654,7 @@ static void resetBuffers(escSerial_t *escSerial) escSerial->port.txBufferHead = 0; } -static serialPort_t *openEscSerial(escSerialPortIndex_e portIndex, serialReceiveCallbackPtr callback, uint16_t output, uint32_t baud, portOptions_t options, uint8_t mode) +static serialPort_t *openEscSerial(escSerialPortIndex_e portIndex, serialReceiveCallbackPtr callback, uint16_t output, uint32_t baud, portOptions_e options, uint8_t mode) { escSerial_t *escSerial = &(escSerialPorts[portIndex]); @@ -811,7 +811,7 @@ static void escSerialSetBaudRate(serialPort_t *s, uint32_t baudRate) UNUSED(baudRate); } -static void escSerialSetMode(serialPort_t *instance, portMode_t mode) +static void escSerialSetMode(serialPort_t *instance, portMode_e mode) { instance->mode = mode; } diff --git a/src/main/drivers/serial_softserial.c b/src/main/drivers/serial_softserial.c index 1d552bed89..c1ac2b5a5d 100644 --- a/src/main/drivers/serial_softserial.c +++ b/src/main/drivers/serial_softserial.c @@ -236,7 +236,7 @@ static void resetBuffers(softSerial_t *softSerial) softSerial->port.txBufferHead = 0; } -serialPort_t *openSoftSerial(softSerialPortIndex_e portIndex, serialReceiveCallbackPtr rxCallback, uint32_t baud, portMode_t mode, portOptions_t options) +serialPort_t *openSoftSerial(softSerialPortIndex_e portIndex, serialReceiveCallbackPtr rxCallback, uint32_t baud, portMode_e mode, portOptions_e options) { softSerial_t *softSerial = &(softSerialPorts[portIndex]); @@ -615,7 +615,7 @@ void softSerialSetBaudRate(serialPort_t *s, uint32_t baudRate) serialTimerConfigureTimebase(softSerial->timerHardware, baudRate); } -void softSerialSetMode(serialPort_t *instance, portMode_t mode) +void softSerialSetMode(serialPort_t *instance, portMode_e mode) { instance->mode = mode; } diff --git a/src/main/drivers/serial_softserial.h b/src/main/drivers/serial_softserial.h index 032368b2b5..bee1b0417c 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_t mode, portOptions_t options); +serialPort_t *openSoftSerial(softSerialPortIndex_e portIndex, serialReceiveCallbackPtr rxCallback, 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 ba31b7cdca..7911770ef0 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_t mode, portOptions_t options) +serialPort_t *serTcpOpen(int id, serialReceiveCallbackPtr rxCallback, uint32_t baudRate, portMode_e mode, portOptions_e options) { tcpPort_t *s = NULL; diff --git a/src/main/drivers/serial_tcp.h b/src/main/drivers/serial_tcp.h index 5efe413f86..c7f26a3d10 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_t mode, portOptions_t options); +serialPort_t *serTcpOpen(int id, serialReceiveCallbackPtr rxCallback, 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.c b/src/main/drivers/serial_uart.c index fa417bb199..8fb3bb1ac4 100644 --- a/src/main/drivers/serial_uart.c +++ b/src/main/drivers/serial_uart.c @@ -48,7 +48,7 @@ void uartSetBaudRate(serialPort_t *instance, uint32_t baudRate) uartReconfigure(uartPort); } -void uartSetMode(serialPort_t *instance, portMode_t mode) +void uartSetMode(serialPort_t *instance, portMode_e mode) { uartPort_t *uartPort = (uartPort_t *)instance; uartPort->port.mode = mode; diff --git a/src/main/drivers/serial_uart.h b/src/main/drivers/serial_uart.h index f79833f534..3b9614d862 100644 --- a/src/main/drivers/serial_uart.h +++ b/src/main/drivers/serial_uart.h @@ -28,7 +28,7 @@ #define USE_UART #endif -typedef enum UARTDevice { +typedef enum { UARTDEV_1 = 0, UARTDEV_2 = 1, UARTDEV_3 = 2, @@ -37,7 +37,7 @@ typedef enum UARTDevice { UARTDEV_6 = 5, UARTDEV_7 = 6, UARTDEV_8 = 7 -} UARTDevice; +} UARTDevice_e; typedef struct uartPort_s { serialPort_t port; @@ -59,7 +59,6 @@ typedef struct uartPort_s { uint32_t txDMAIrq; uint32_t rxDMAPos; - bool txDMAEmpty; uint32_t txDMAPeripheralBaseAddr; uint32_t rxDMAPeripheralBaseAddr; @@ -69,10 +68,11 @@ typedef struct uartPort_s { UART_HandleTypeDef Handle; #endif USART_TypeDef *USARTx; + bool txDMAEmpty; } uartPort_t; void uartPinConfigure(const serialPinConfig_t *pSerialPinConfig); -serialPort_t *uartOpen(UARTDevice device, serialReceiveCallbackPtr rxCallback, uint32_t baudRate, portMode_t mode, portOptions_t options); +serialPort_t *uartOpen(UARTDevice_e device, serialReceiveCallbackPtr rxCallback, 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 a4a7056c50..39e7ad350e 100644 --- a/src/main/drivers/serial_uart_hal.c +++ b/src/main/drivers/serial_uart_hal.c @@ -182,7 +182,7 @@ void uartReconfigure(uartPort_t *uartPort) return; } -serialPort_t *uartOpen(UARTDevice device, serialReceiveCallbackPtr callback, uint32_t baudRate, portMode_t mode, portOptions_t options) +serialPort_t *uartOpen(UARTDevice_e device, serialReceiveCallbackPtr callback, uint32_t baudRate, portMode_e mode, portOptions_e options) { uartPort_t *s = serialUART(device, baudRate, mode, options); @@ -213,7 +213,7 @@ void uartSetBaudRate(serialPort_t *instance, uint32_t baudRate) uartReconfigure(uartPort); } -void uartSetMode(serialPort_t *instance, portMode_t mode) +void uartSetMode(serialPort_t *instance, portMode_e mode) { uartPort_t *uartPort = (uartPort_t *)instance; uartPort->port.mode = mode; @@ -300,9 +300,8 @@ uint32_t uartTotalTxBytesFree(const serialPort_t *instance) bool isUartTransmitBufferEmpty(const serialPort_t *instance) { - uartPort_t *s = (uartPort_t *)instance; + const uartPort_t *s = (uartPort_t *)instance; if (s->txDMAStream) - return s->txDMAEmpty; else return s->port.txBufferTail == s->port.txBufferHead; @@ -313,9 +312,7 @@ uint8_t uartRead(serialPort_t *instance) uint8_t ch; uartPort_t *s = (uartPort_t *)instance; - if (s->rxDMAStream) { - ch = s->port.rxBuffer[s->port.rxBufferSize - s->rxDMAPos]; if (--s->rxDMAPos == 0) s->rxDMAPos = s->port.rxBufferSize; diff --git a/src/main/drivers/serial_uart_impl.h b/src/main/drivers/serial_uart_impl.h index e9cb8dda2a..38e53cc057 100644 --- a/src/main/drivers/serial_uart_impl.h +++ b/src/main/drivers/serial_uart_impl.h @@ -112,7 +112,7 @@ #define UARTDEV_COUNT (UARTDEV_COUNT_1 + UARTDEV_COUNT_2 + UARTDEV_COUNT_3 + UARTDEV_COUNT_4 + UARTDEV_COUNT_5 + UARTDEV_COUNT_6 + UARTDEV_COUNT_7 + UARTDEV_COUNT_8) typedef struct uartHardware_s { - UARTDevice device; // XXX Not required for full allocation + UARTDevice_e device; // XXX Not required for full allocation USART_TypeDef* reg; #if defined(STM32F1) || defined(STM32F3) DMA_Channel_TypeDef *txDMAChannel; @@ -156,7 +156,6 @@ typedef struct uartDevice_s { volatile uint8_t txBuffer[UART_TX_BUFFER_SIZE]; } uartDevice_t; -extern uartDevice_t uartDevice[]; extern uartDevice_t *uartDevmap[]; extern const struct serialPortVTable uartVTable[]; @@ -167,7 +166,7 @@ void uartStartTxDMA(uartPort_t *s); void uartTryStartTxDMA(uartPort_t *s); #endif -uartPort_t *serialUART(UARTDevice device, uint32_t baudRate, portMode_t mode, portOptions_t options); +uartPort_t *serialUART(UARTDevice_e device, uint32_t baudRate, portMode_e mode, portOptions_e options); void uartIrqHandler(uartPort_t *s); diff --git a/src/main/drivers/serial_uart_init.c b/src/main/drivers/serial_uart_init.c index 1b6d9839d3..d27ab07591 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 device, serialReceiveCallbackPtr rxCallback, uint32_t baudRate, portMode_t mode, portOptions_t options) +serialPort_t *uartOpen(UARTDevice_e device, serialReceiveCallbackPtr rxCallback, uint32_t baudRate, portMode_e mode, portOptions_e options) { uartPort_t *s = serialUART(device, baudRate, mode, options); diff --git a/src/main/drivers/serial_uart_pinconfig.c b/src/main/drivers/serial_uart_pinconfig.c index 0cf2ec679a..3346fec3ca 100644 --- a/src/main/drivers/serial_uart_pinconfig.c +++ b/src/main/drivers/serial_uart_pinconfig.c @@ -46,7 +46,7 @@ void uartPinConfigure(const serialPinConfig_t *pSerialPinConfig) for (size_t hindex = 0; hindex < UARTDEV_COUNT; hindex++) { const uartHardware_t *hardware = &uartHardware[hindex]; - UARTDevice device = hardware->device; + const UARTDevice_e device = hardware->device; for (int pindex = 0 ; pindex < UARTHARDWARE_MAX_PINS ; pindex++) { if (hardware->rxPins[pindex] && (hardware->rxPins[pindex] == pSerialPinConfig->ioTagRx[device])) diff --git a/src/main/drivers/serial_uart_stm32f10x.c b/src/main/drivers/serial_uart_stm32f10x.c index 3e599868de..3767af0725 100644 --- a/src/main/drivers/serial_uart_stm32f10x.c +++ b/src/main/drivers/serial_uart_stm32f10x.c @@ -116,7 +116,7 @@ void uart_tx_dma_IRQHandler(dmaChannelDescriptor_t* descriptor) // XXX Should serialUART be consolidated? -uartPort_t *serialUART(UARTDevice device, uint32_t baudRate, portMode_t mode, portOptions_t options) +uartPort_t *serialUART(UARTDevice_e device, uint32_t baudRate, portMode_e mode, portOptions_e options) { uartDevice_t *uartdev = uartDevmap[device]; if (!uartdev) { diff --git a/src/main/drivers/serial_uart_stm32f30x.c b/src/main/drivers/serial_uart_stm32f30x.c index b94f81f508..e626d62f8b 100644 --- a/src/main/drivers/serial_uart_stm32f30x.c +++ b/src/main/drivers/serial_uart_stm32f30x.c @@ -173,7 +173,7 @@ static void handleUsartTxDma(dmaChannelDescriptor_t* descriptor) uartTryStartTxDMA(s); } -void serialUARTInitIO(IO_t txIO, IO_t rxIO, portMode_t mode, portOptions_t options, uint8_t af, uint8_t index) +void serialUARTInitIO(IO_t txIO, IO_t rxIO, portMode_e mode, portOptions_e options, uint8_t af, uint8_t index) { if ((options & SERIAL_BIDIR) && txIO) { ioConfig_t ioCfg = IO_CONFIG(GPIO_Mode_AF, GPIO_Speed_50MHz, @@ -202,16 +202,14 @@ void serialUARTInitIO(IO_t txIO, IO_t rxIO, portMode_t mode, portOptions_t optio // XXX Should serialUART be consolidated? -uartPort_t *serialUART(UARTDevice device, uint32_t baudRate, portMode_t mode, portOptions_t options) +uartPort_t *serialUART(UARTDevice_e device, uint32_t baudRate, portMode_e mode, portOptions_e options) { - uartPort_t *s; - uartDevice_t *uartDev = uartDevmap[device]; if (!uartDev) { return NULL; } - s = &(uartDev->port); + uartPort_t *s = &(uartDev->port); s->port.vTable = uartVTable; s->port.baudRate = baudRate; diff --git a/src/main/drivers/serial_uart_stm32f4xx.c b/src/main/drivers/serial_uart_stm32f4xx.c index c47e2ee3ff..5f8c16d892 100644 --- a/src/main/drivers/serial_uart_stm32f4xx.c +++ b/src/main/drivers/serial_uart_stm32f4xx.c @@ -194,10 +194,8 @@ void dmaIRQHandler(dmaChannelDescriptor_t* descriptor) // XXX Should serialUART be consolidated? -uartPort_t *serialUART(UARTDevice device, uint32_t baudRate, portMode_t mode, portOptions_t options) +uartPort_t *serialUART(UARTDevice_e device, uint32_t baudRate, portMode_e mode, portOptions_e options) { - uartPort_t *s; - uartDevice_t *uart = uartDevmap[device]; if (!uart) return NULL; @@ -205,7 +203,7 @@ uartPort_t *serialUART(UARTDevice device, uint32_t baudRate, portMode_t mode, po if (!hardware) return NULL; // XXX Can't happen !? - s = &(uart->port); + uartPort_t *s = &(uart->port); s->port.vTable = uartVTable; s->port.baudRate = baudRate; diff --git a/src/main/drivers/serial_uart_stm32f7xx.c b/src/main/drivers/serial_uart_stm32f7xx.c index 25252d133a..8ab4aa7183 100644 --- a/src/main/drivers/serial_uart_stm32f7xx.c +++ b/src/main/drivers/serial_uart_stm32f7xx.c @@ -303,7 +303,7 @@ void dmaIRQHandler(dmaChannelDescriptor_t* descriptor) // XXX Should serialUART be consolidated? -uartPort_t *serialUART(UARTDevice device, uint32_t baudRate, portMode_t mode, portOptions_t options) +uartPort_t *serialUART(UARTDevice_e device, uint32_t baudRate, portMode_e mode, portOptions_e options) { uartDevice_t *uartdev = uartDevmap[device]; if (!uartdev) { diff --git a/src/main/drivers/serial_usb_vcp.c b/src/main/drivers/serial_usb_vcp.c index 2ed3ee1733..dd70c8d028 100644 --- a/src/main/drivers/serial_usb_vcp.c +++ b/src/main/drivers/serial_usb_vcp.c @@ -57,7 +57,7 @@ static void usbVcpSetBaudRate(serialPort_t *instance, uint32_t baudRate) // TODO implement } -static void usbVcpSetMode(serialPort_t *instance, portMode_t mode) +static void usbVcpSetMode(serialPort_t *instance, portMode_e mode) { UNUSED(instance); UNUSED(mode); diff --git a/src/main/io/gps.c b/src/main/io/gps.c index 102b21fbe2..4c4c51b10e 100755 --- a/src/main/io/gps.c +++ b/src/main/io/gps.c @@ -250,7 +250,7 @@ void gpsInit(void) } } - portMode_t mode = MODE_RXTX; + portMode_e mode = MODE_RXTX; // only RX is needed for NMEA-style GPS #if !defined(COLIBRI_RACE) || !defined(LUX_RACE) if (gpsConfig()->provider == GPS_NMEA) diff --git a/src/main/io/serial.c b/src/main/io/serial.c index 866b0240e2..1cc30d1d42 100644 --- a/src/main/io/serial.c +++ b/src/main/io/serial.c @@ -334,8 +334,8 @@ serialPort_t *openSerialPort( serialPortFunction_e function, serialReceiveCallbackPtr rxCallback, uint32_t baudRate, - portMode_t mode, - portOptions_t options) + portMode_e mode, + portOptions_e options) { #if !(defined(USE_UART) || defined(USE_SOFTSERIAL1) || defined(USE_SOFTSERIAL2)) UNUSED(rxCallback); diff --git a/src/main/io/serial.h b/src/main/io/serial.h index 5d0009d1b3..6d47b93db5 100644 --- a/src/main/io/serial.h +++ b/src/main/io/serial.h @@ -151,8 +151,8 @@ serialPort_t *openSerialPort( serialPortFunction_e function, serialReceiveCallbackPtr rxCallback, uint32_t baudrate, - portMode_t mode, - portOptions_t options + portMode_e mode, + portOptions_e options ); void closeSerialPort(serialPort_t *serialPort); diff --git a/src/main/sensors/esc_sensor.c b/src/main/sensors/esc_sensor.c index 3a2d5bfcab..1ac808c1e8 100644 --- a/src/main/sensors/esc_sensor.c +++ b/src/main/sensors/esc_sensor.c @@ -199,7 +199,7 @@ bool escSensorInit(void) return false; } - portOptions_t options = SERIAL_NOT_INVERTED | (escSensorConfig()->halfDuplex ? SERIAL_BIDIR : 0); + 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); diff --git a/src/main/telemetry/hott.c b/src/main/telemetry/hott.c index 1aa65b6462..4ead0d2c0b 100644 --- a/src/main/telemetry/hott.c +++ b/src/main/telemetry/hott.c @@ -327,10 +327,10 @@ static void flushHottRxBuffer(void) } } -static void workAroundForHottTelemetryOnUsart(serialPort_t *instance, portMode_t mode) { +static void workAroundForHottTelemetryOnUsart(serialPort_t *instance, portMode_e mode) { closeSerialPort(hottPort); - portOptions_t portOptions = telemetryConfig()->telemetry_inverted ? SERIAL_INVERTED : SERIAL_NOT_INVERTED; + portOptions_e portOptions = telemetryConfig()->telemetry_inverted ? SERIAL_INVERTED : SERIAL_NOT_INVERTED; if (telemetryConfig()->halfDuplex) { portOptions |= SERIAL_BIDIR; @@ -382,7 +382,7 @@ void configureHoTTTelemetryPort(void) return; } - portOptions_t portOptions = SERIAL_NOT_INVERTED; + portOptions_e portOptions = SERIAL_NOT_INVERTED; if (telemetryConfig()->halfDuplex) { portOptions |= SERIAL_BIDIR; diff --git a/src/main/telemetry/smartport.c b/src/main/telemetry/smartport.c index 53a9590114..080df64911 100644 --- a/src/main/telemetry/smartport.c +++ b/src/main/telemetry/smartport.c @@ -321,7 +321,7 @@ void configureSmartPortTelemetryPort(void) return; } - portOptions_t portOptions = (telemetryConfig()->halfDuplex ? SERIAL_BIDIR : SERIAL_UNIDIR) | (telemetryConfig()->telemetry_inverted ? SERIAL_NOT_INVERTED : SERIAL_INVERTED); + 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); diff --git a/src/test/unit/blackbox_unittest.cc b/src/test/unit/blackbox_unittest.cc index 820f9a7014..c5829a4c61 100644 --- a/src/test/unit/blackbox_unittest.cc +++ b/src/test/unit/blackbox_unittest.cc @@ -388,7 +388,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_t, portOptions_t) {return NULL;} +serialPort_t *openSerialPort(serialPortIdentifier_e, serialPortFunction_e, serialReceiveCallbackPtr, 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 39a1878cf6..f3200e71ca 100644 --- a/src/test/unit/cli_unittest.cc +++ b/src/test/unit/cli_unittest.cc @@ -212,9 +212,9 @@ 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_t, portOptions_t) { return NULL; } +serialPort_t *openSerialPort(serialPortIdentifier_e, serialPortFunction_e, serialReceiveCallbackPtr, uint32_t, portMode_e, portOptions_e) { return NULL; } void serialSetBaudRate(serialPort_t *, uint32_t) {} -void serialSetMode(serialPort_t *, portMode_t) {} +void serialSetMode(serialPort_t *, portMode_e) {} void serialPassthrough(serialPort_t *, serialPort_t *, serialConsumer *, serialConsumer *) {} uint32_t millis(void) { return 0; } uint8_t getBatteryCellCount(void) { return 1; } diff --git a/src/test/unit/io_serial_unittest.cc b/src/test/unit/io_serial_unittest.cc index 34f76b2927..8f77a4cd5d 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, serialReceiveCallbackPtr, uint32_t, portMode_t, portOptions_t) { + serialPort_t *uartOpen(UARTDevice_e, serialReceiveCallbackPtr, uint32_t, portMode_e, portOptions_e) { return NULL; } - serialPort_t *openSoftSerial(softSerialPortIndex_e, serialReceiveCallbackPtr, uint32_t, portMode_t, portOptions_t) { + serialPort_t *openSoftSerial(softSerialPortIndex_e, serialReceiveCallbackPtr, uint32_t, portMode_e, portOptions_e) { return NULL; } } diff --git a/src/test/unit/rcsplit_unittest.cc b/src/test/unit/rcsplit_unittest.cc index d07f357ddf..8f0f6e2b55 100644 --- a/src/test/unit/rcsplit_unittest.cc +++ b/src/test/unit/rcsplit_unittest.cc @@ -311,7 +311,7 @@ TEST(RCSplitTest, TestWifiModeChangeCombine) } extern "C" { - serialPort_t *openSerialPort(serialPortIdentifier_e identifier, serialPortFunction_e functionMask, serialReceiveCallbackPtr callback, uint32_t baudRate, portMode_t mode, portOptions_t options) + serialPort_t *openSerialPort(serialPortIdentifier_e identifier, serialPortFunction_e functionMask, serialReceiveCallbackPtr callback, uint32_t baudRate, portMode_e mode, portOptions_e options) { UNUSED(identifier); UNUSED(functionMask); diff --git a/src/test/unit/rx_crsf_unittest.cc b/src/test/unit/rx_crsf_unittest.cc index b375589537..875061af13 100644 --- a/src/test/unit/rx_crsf_unittest.cc +++ b/src/test/unit/rx_crsf_unittest.cc @@ -275,7 +275,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_t, portOptions_t) {return NULL;} +serialPort_t *openSerialPort(serialPortIdentifier_e, serialPortFunction_e, serialReceiveCallbackPtr, uint32_t, portMode_e, portOptions_e) {return NULL;} serialPortConfig_t *findSerialPortConfig(serialPortFunction_e ) {return NULL;} void serialWriteBuf(serialPort_t *, const uint8_t *, int) {} bool telemetryCheckRxPortShared(const serialPortConfig_t *) {return false;} diff --git a/src/test/unit/rx_ibus_unittest.cc b/src/test/unit/rx_ibus_unittest.cc index eb2453dc52..6810516bc7 100644 --- a/src/test/unit/rx_ibus_unittest.cc +++ b/src/test/unit/rx_ibus_unittest.cc @@ -104,16 +104,16 @@ serialPortConfig_t *findSerialPortConfig(serialPortFunction_e function) return findSerialPortConfig_stub_retval; } -static portMode_t serialExpectedMode = MODE_RX; -static portOptions_t serialExpectedOptions = SERIAL_UNIDIR; +static portMode_e serialExpectedMode = MODE_RX; +static portOptions_e serialExpectedOptions = SERIAL_UNIDIR; serialPort_t *openSerialPort( serialPortIdentifier_e identifier, serialPortFunction_e function, serialReceiveCallbackPtr callback, uint32_t baudrate, - portMode_t mode, - portOptions_t options + portMode_e mode, + portOptions_e options ) { openSerial_called = true; diff --git a/src/test/unit/telemetry_crsf_unittest.cc b/src/test/unit/telemetry_crsf_unittest.cc index 661cb45699..e32994d3af 100644 --- a/src/test/unit/telemetry_crsf_unittest.cc +++ b/src/test/unit/telemetry_crsf_unittest.cc @@ -288,8 +288,8 @@ uint32_t serialTxBytesFree(const serialPort_t *) {return 0;} 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_t ) {} -serialPort_t *openSerialPort(serialPortIdentifier_e, serialPortFunction_e, serialReceiveCallbackPtr, uint32_t, portMode_t, portOptions_t) {return NULL;} +void serialSetMode(serialPort_t *, portMode_e) {} +serialPort_t *openSerialPort(serialPortIdentifier_e, serialPortFunction_e, serialReceiveCallbackPtr, uint32_t, portMode_e, portOptions_e) {return NULL;} void closeSerialPort(serialPort_t *) {} serialPortConfig_t *findSerialPortConfig(serialPortFunction_e) {return NULL;} diff --git a/src/test/unit/telemetry_hott_unittest.cc b/src/test/unit/telemetry_hott_unittest.cc index f8843b2e56..20ec7dc9a9 100644 --- a/src/test/unit/telemetry_hott_unittest.cc +++ b/src/test/unit/telemetry_hott_unittest.cc @@ -213,13 +213,13 @@ void serialWrite(serialPort_t *instance, uint8_t ch) UNUSED(ch); } -void serialSetMode(serialPort_t *instance, portMode_t mode) +void serialSetMode(serialPort_t *instance, portMode_e mode) { UNUSED(instance); UNUSED(mode); } -serialPort_t *openSerialPort(serialPortIdentifier_e identifier, serialPortFunction_e functionMask, serialReceiveCallbackPtr callback, uint32_t baudRate, portMode_t mode, portOptions_t options) +serialPort_t *openSerialPort(serialPortIdentifier_e identifier, serialPortFunction_e functionMask, serialReceiveCallbackPtr callback, uint32_t baudRate, portMode_e mode, portOptions_e options) { UNUSED(identifier); UNUSED(functionMask); diff --git a/src/test/unit/telemetry_ibus_unittest.cc b/src/test/unit/telemetry_ibus_unittest.cc index 04dcb69b3f..a512ab2ee0 100644 --- a/src/test/unit/telemetry_ibus_unittest.cc +++ b/src/test/unit/telemetry_ibus_unittest.cc @@ -141,8 +141,8 @@ serialPort_t *openSerialPort( serialPortFunction_e function, serialReceiveCallbackPtr callback, uint32_t baudrate, - portMode_t mode, - portOptions_t options + portMode_e mode, + portOptions_e options ) { openSerial_called = true;