1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-18 22:05:17 +03:00

Tidied UART enum definitions

This commit is contained in:
Martin Budden 2017-07-29 12:34:27 +01:00
parent bacc6e6fb1
commit 944fe0761c
34 changed files with 65 additions and 73 deletions

View file

@ -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;

View file

@ -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);
}

View file

@ -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);

View file

@ -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;
}

View file

@ -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;
}

View file

@ -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);

View file

@ -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;

View file

@ -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);

View file

@ -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;

View file

@ -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);

View file

@ -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;

View file

@ -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);

View file

@ -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);

View file

@ -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]))

View file

@ -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) {

View file

@ -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;

View file

@ -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;

View file

@ -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) {

View file

@ -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);

View file

@ -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)

View file

@ -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);

View file

@ -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);

View file

@ -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);

View file

@ -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;

View file

@ -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);

View file

@ -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;}

View file

@ -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; }

View file

@ -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;
}
}

View file

@ -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);

View file

@ -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;}

View file

@ -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;

View file

@ -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;}

View file

@ -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);

View file

@ -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;