From 946f65601f7eb65c5d0b1ef92342af3ed1559174 Mon Sep 17 00:00:00 2001 From: Dominic Clifton Date: Tue, 3 Mar 2015 22:35:40 +0000 Subject: [PATCH] Cleanup some enum values - using topic_type instead of type_topic. --- src/main/config/config.c | 4 ++-- src/main/io/serial.c | 2 +- src/main/io/serial.h | 10 +++++----- src/main/io/serial_msp.c | 4 ++-- src/main/mw.c | 2 +- src/main/rx/sbus.c | 4 ++-- src/main/rx/spektrum.c | 4 ++-- src/main/rx/sumd.c | 4 ++-- src/main/rx/sumh.c | 4 ++-- src/main/rx/xbus.c | 4 ++-- src/main/telemetry/frsky.c | 6 +++--- src/main/telemetry/hott.c | 6 +++--- src/main/telemetry/hott.h | 6 +++--- src/main/telemetry/msp.c | 8 ++++---- src/main/telemetry/smartport.c | 6 +++--- 15 files changed, 37 insertions(+), 37 deletions(-) diff --git a/src/main/config/config.c b/src/main/config/config.c index 08d2c6416..0ce6354fa 100644 --- a/src/main/config/config.c +++ b/src/main/config/config.c @@ -484,9 +484,9 @@ static void resetConf(void) featureSet(FEATURE_FAILSAFE); featureClear(FEATURE_VBAT); #ifdef ALIENWIIF3 - masterConfig.serialConfig.portConfigs[2].functionMask = FUNCTION_SERIAL_RX; + masterConfig.serialConfig.portConfigs[2].functionMask = FUNCTION_RX_SERIAL; #else - masterConfig.serialConfig.portConfigs[1].functionMask = FUNCTION_SERIAL_RX; + masterConfig.serialConfig.portConfigs[1].functionMask = FUNCTION_RX_SERIAL; #endif masterConfig.rxConfig.serialrx_provider = 1; masterConfig.rxConfig.spektrum_sat_bind = 5; diff --git a/src/main/io/serial.c b/src/main/io/serial.c index 3f358b1d7..562c31169 100644 --- a/src/main/io/serial.c +++ b/src/main/io/serial.c @@ -174,7 +174,7 @@ serialPort_t *findNextSharedSerialPort(uint16_t functionMask, serialPortFunction return NULL; } -#define ALL_TELEMETRY_FUNCTIONS_MASK (FUNCTION_FRSKY_TELEMETRY | FUNCTION_HOTT_TELEMETRY | FUNCTION_MSP_TELEMETRY | FUNCTION_SMARTPORT_TELEMETRY) +#define ALL_TELEMETRY_FUNCTIONS_MASK (FUNCTION_TELEMETRY_FRSKY | FUNCTION_TELEMETRY_HOTT | FUNCTION_TELEMETRY_MSP | FUNCTION_TELEMETRY_SMARTPORT) #define ALL_FUNCTIONS_SHARABLE_WITH_MSP (FUNCTION_BLACKBOX | ALL_TELEMETRY_FUNCTIONS_MASK) bool isSerialConfigValid(serialConfig_t *serialConfigToCheck) diff --git a/src/main/io/serial.h b/src/main/io/serial.h index f85eab914..188e16e65 100644 --- a/src/main/io/serial.h +++ b/src/main/io/serial.h @@ -27,11 +27,11 @@ typedef enum { FUNCTION_NONE = 0, FUNCTION_MSP = (1 << 0), FUNCTION_GPS = (1 << 1), - FUNCTION_FRSKY_TELEMETRY = (1 << 2), - FUNCTION_HOTT_TELEMETRY = (1 << 3), - FUNCTION_MSP_TELEMETRY = (1 << 4), - FUNCTION_SMARTPORT_TELEMETRY = (1 << 5), - FUNCTION_SERIAL_RX = (1 << 6), + FUNCTION_TELEMETRY_FRSKY = (1 << 2), + FUNCTION_TELEMETRY_HOTT = (1 << 3), + FUNCTION_TELEMETRY_MSP = (1 << 4), + FUNCTION_TELEMETRY_SMARTPORT = (1 << 5), + FUNCTION_RX_SERIAL = (1 << 6), FUNCTION_BLACKBOX = (1 << 7) } serialPortFunction_e; diff --git a/src/main/io/serial_msp.c b/src/main/io/serial_msp.c index 9b0da5dc4..19e75a874 100644 --- a/src/main/io/serial_msp.c +++ b/src/main/io/serial_msp.c @@ -1707,7 +1707,7 @@ static const uint8_t mspTelemetryCommandSequence[] = { MSP_SERVO }; -#define MSP_TELEMETRY_COMMAND_SEQUENCE_ENTRY_COUNT (sizeof(mspTelemetryCommandSequence) / sizeof(mspTelemetryCommandSequence[0])) +#define TELEMETRY_MSP_COMMAND_SEQUENCE_ENTRY_COUNT (sizeof(mspTelemetryCommandSequence) / sizeof(mspTelemetryCommandSequence[0])) static mspPort_t *mspTelemetryPort = NULL; @@ -1758,7 +1758,7 @@ void sendMspTelemetry(void) tailSerialReply(); sequenceIndex++; - if (sequenceIndex >= MSP_TELEMETRY_COMMAND_SEQUENCE_ENTRY_COUNT) { + if (sequenceIndex >= TELEMETRY_MSP_COMMAND_SEQUENCE_ENTRY_COUNT) { sequenceIndex = 0; } } diff --git a/src/main/mw.c b/src/main/mw.c index 12bbf377a..db8d34e4e 100644 --- a/src/main/mw.c +++ b/src/main/mw.c @@ -322,7 +322,7 @@ void mwDisarm(void) } } -#define TELEMETRY_FUNCTION_MASK (FUNCTION_FRSKY_TELEMETRY | FUNCTION_HOTT_TELEMETRY | FUNCTION_MSP_TELEMETRY | FUNCTION_SMARTPORT_TELEMETRY) +#define TELEMETRY_FUNCTION_MASK (FUNCTION_TELEMETRY_FRSKY | FUNCTION_TELEMETRY_HOTT | FUNCTION_TELEMETRY_MSP | FUNCTION_TELEMETRY_SMARTPORT) void mwArm(void) { diff --git a/src/main/rx/sbus.c b/src/main/rx/sbus.c index d1f1194f1..2ea8441b1 100644 --- a/src/main/rx/sbus.c +++ b/src/main/rx/sbus.c @@ -87,12 +87,12 @@ bool sbusInit(rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig, rcReadRa *callback = sbusReadRawRC; rxRuntimeConfig->channelCount = SBUS_MAX_CHANNEL; - serialPortConfig_t *portConfig = findSerialPortConfig(FUNCTION_SERIAL_RX); + serialPortConfig_t *portConfig = findSerialPortConfig(FUNCTION_RX_SERIAL); if (!portConfig) { return false; } - serialPort_t *sBusPort = openSerialPort(portConfig->identifier, FUNCTION_SERIAL_RX, sbusDataReceive, SBUS_BAUDRATE, (portMode_t)(MODE_RX | MODE_SBUS), SERIAL_INVERTED); + serialPort_t *sBusPort = openSerialPort(portConfig->identifier, FUNCTION_RX_SERIAL, sbusDataReceive, SBUS_BAUDRATE, (portMode_t)(MODE_RX | MODE_SBUS), SERIAL_INVERTED); return sBusPort != NULL; } diff --git a/src/main/rx/spektrum.c b/src/main/rx/spektrum.c index 5d037c383..253d3ecbe 100644 --- a/src/main/rx/spektrum.c +++ b/src/main/rx/spektrum.c @@ -78,12 +78,12 @@ bool spektrumInit(rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig, rcRe if (callback) *callback = spektrumReadRawRC; - serialPortConfig_t *portConfig = findSerialPortConfig(FUNCTION_SERIAL_RX); + serialPortConfig_t *portConfig = findSerialPortConfig(FUNCTION_RX_SERIAL); if (!portConfig) { return false; } - serialPort_t *spektrumPort = openSerialPort(portConfig->identifier, FUNCTION_SERIAL_RX, spektrumDataReceive, SPEKTRUM_BAUDRATE, MODE_RX, SERIAL_NOT_INVERTED); + serialPort_t *spektrumPort = openSerialPort(portConfig->identifier, FUNCTION_RX_SERIAL, spektrumDataReceive, SPEKTRUM_BAUDRATE, MODE_RX, SERIAL_NOT_INVERTED); return spektrumPort != NULL; } diff --git a/src/main/rx/sumd.c b/src/main/rx/sumd.c index 98425fba2..0f43edbc9 100644 --- a/src/main/rx/sumd.c +++ b/src/main/rx/sumd.c @@ -57,12 +57,12 @@ bool sumdInit(rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig, rcReadRa rxRuntimeConfig->channelCount = SUMD_MAX_CHANNEL; - serialPortConfig_t *portConfig = findSerialPortConfig(FUNCTION_SERIAL_RX); + serialPortConfig_t *portConfig = findSerialPortConfig(FUNCTION_RX_SERIAL); if (!portConfig) { return false; } - serialPort_t *sumdPort = openSerialPort(portConfig->identifier, FUNCTION_SERIAL_RX, sumdDataReceive, SUMD_BAUDRATE, MODE_RX, SERIAL_NOT_INVERTED); + serialPort_t *sumdPort = openSerialPort(portConfig->identifier, FUNCTION_RX_SERIAL, sumdDataReceive, SUMD_BAUDRATE, MODE_RX, SERIAL_NOT_INVERTED); return sumdPort != NULL; } diff --git a/src/main/rx/sumh.c b/src/main/rx/sumh.c index 379ba2527..740cf6436 100644 --- a/src/main/rx/sumh.c +++ b/src/main/rx/sumh.c @@ -64,12 +64,12 @@ bool sumhInit(rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig, rcReadRa rxRuntimeConfig->channelCount = SUMH_MAX_CHANNEL_COUNT; - serialPortConfig_t *portConfig = findSerialPortConfig(FUNCTION_SERIAL_RX); + serialPortConfig_t *portConfig = findSerialPortConfig(FUNCTION_RX_SERIAL); if (!portConfig) { return false; } - sumhPort = openSerialPort(portConfig->identifier, FUNCTION_SERIAL_RX, sumhDataReceive, SUMH_BAUDRATE, MODE_RX, SERIAL_NOT_INVERTED); + sumhPort = openSerialPort(portConfig->identifier, FUNCTION_RX_SERIAL, sumhDataReceive, SUMH_BAUDRATE, MODE_RX, SERIAL_NOT_INVERTED); return sumhPort != NULL; } diff --git a/src/main/rx/xbus.c b/src/main/rx/xbus.c index 88f03c351..850c7110c 100644 --- a/src/main/rx/xbus.c +++ b/src/main/rx/xbus.c @@ -118,12 +118,12 @@ bool xBusInit(rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig, rcReadRa *callback = xBusReadRawRC; } - serialPortConfig_t *portConfig = findSerialPortConfig(FUNCTION_SERIAL_RX); + serialPortConfig_t *portConfig = findSerialPortConfig(FUNCTION_RX_SERIAL); if (!portConfig) { return false; } - serialPort_t *xBusPort = openSerialPort(portConfig->identifier, FUNCTION_SERIAL_RX, xBusDataReceive, baudRate, MODE_RX, SERIAL_NOT_INVERTED); + serialPort_t *xBusPort = openSerialPort(portConfig->identifier, FUNCTION_RX_SERIAL, xBusDataReceive, baudRate, MODE_RX, SERIAL_NOT_INVERTED); return xBusPort != NULL; } diff --git a/src/main/telemetry/frsky.c b/src/main/telemetry/frsky.c index c02eaf756..c61cb87f5 100644 --- a/src/main/telemetry/frsky.c +++ b/src/main/telemetry/frsky.c @@ -407,8 +407,8 @@ static void sendHeading(void) void initFrSkyTelemetry(telemetryConfig_t *initialTelemetryConfig) { telemetryConfig = initialTelemetryConfig; - portConfig = findSerialPortConfig(FUNCTION_FRSKY_TELEMETRY); - frskyPortSharing = determinePortSharing(portConfig, FUNCTION_FRSKY_TELEMETRY); + portConfig = findSerialPortConfig(FUNCTION_TELEMETRY_FRSKY); + frskyPortSharing = determinePortSharing(portConfig, FUNCTION_TELEMETRY_FRSKY); } void freeFrSkyTelemetryPort(void) @@ -424,7 +424,7 @@ void configureFrSkyTelemetryPort(void) return; } - frskyPort = openSerialPort(portConfig->identifier, FUNCTION_FRSKY_TELEMETRY, NULL, FRSKY_BAUDRATE, FRSKY_INITIAL_PORT_MODE, telemetryConfig->telemetry_inversion); + frskyPort = openSerialPort(portConfig->identifier, FUNCTION_TELEMETRY_FRSKY, NULL, FRSKY_BAUDRATE, FRSKY_INITIAL_PORT_MODE, telemetryConfig->telemetry_inversion); if (!frskyPort) { return; } diff --git a/src/main/telemetry/hott.c b/src/main/telemetry/hott.c index 748164931..eb29cbd7a 100644 --- a/src/main/telemetry/hott.c +++ b/src/main/telemetry/hott.c @@ -260,8 +260,8 @@ void freeHoTTTelemetryPort(void) void initHoTTTelemetry(telemetryConfig_t *initialTelemetryConfig) { telemetryConfig = initialTelemetryConfig; - portConfig = findSerialPortConfig(FUNCTION_HOTT_TELEMETRY); - hottPortSharing = determinePortSharing(portConfig, FUNCTION_HOTT_TELEMETRY); + portConfig = findSerialPortConfig(FUNCTION_TELEMETRY_HOTT); + hottPortSharing = determinePortSharing(portConfig, FUNCTION_TELEMETRY_HOTT); initialiseMessages(); } @@ -272,7 +272,7 @@ void configureHoTTTelemetryPort(void) return; } - hottPort = openSerialPort(portConfig->identifier, FUNCTION_HOTT_TELEMETRY, NULL, HOTT_BAUDRATE, HOTT_INITIAL_PORT_MODE, SERIAL_NOT_INVERTED); + hottPort = openSerialPort(portConfig->identifier, FUNCTION_TELEMETRY_HOTT, NULL, HOTT_BAUDRATE, HOTT_INITIAL_PORT_MODE, SERIAL_NOT_INVERTED); if (!hottPort) { return; diff --git a/src/main/telemetry/hott.h b/src/main/telemetry/hott.h index 39d133646..37b8e6f10 100644 --- a/src/main/telemetry/hott.h +++ b/src/main/telemetry/hott.h @@ -23,8 +23,8 @@ * Texmode add-on by Michi (mamaretti32@gmail.com) */ -#ifndef TELEMETRY_HOTT_H_ -#define TELEMETRY_HOTT_H_ +#ifndef HOTT_TELEMETRY_H_ +#define HOTT_TELEMETRY_H_ #define HOTTV4_RXTX 4 @@ -498,4 +498,4 @@ uint32_t getHoTTTelemetryProviderBaudRate(void); void hottPrepareGPSResponse(HOTT_GPS_MSG_t *hottGPSMessage); -#endif /* TELEMETRY_HOTT_H_ */ +#endif /* HOTT_TELEMETRY_H_ */ diff --git a/src/main/telemetry/msp.c b/src/main/telemetry/msp.c index 832fd9449..4055b38a8 100644 --- a/src/main/telemetry/msp.c +++ b/src/main/telemetry/msp.c @@ -44,15 +44,15 @@ static serialPortConfig_t *portConfig; static bool mspTelemetryEnabled = false; static portSharing_e mspPortSharing; -#define MSP_TELEMETRY_INITIAL_PORT_MODE MODE_TX +#define TELEMETRY_MSP_INITIAL_PORT_MODE MODE_TX static serialPort_t *mspTelemetryPort = NULL; void initMSPTelemetry(telemetryConfig_t *initialTelemetryConfig) { telemetryConfig = initialTelemetryConfig; - portConfig = findSerialPortConfig(FUNCTION_MSP_TELEMETRY); - mspPortSharing = determinePortSharing(portConfig, FUNCTION_MSP_TELEMETRY); + portConfig = findSerialPortConfig(FUNCTION_TELEMETRY_MSP); + mspPortSharing = determinePortSharing(portConfig, FUNCTION_TELEMETRY_MSP); } void checkMSPTelemetryState(void) @@ -100,7 +100,7 @@ void configureMSPTelemetryPort(void) baudRateIndex = BAUD_19200; } - mspTelemetryPort = openSerialPort(portConfig->identifier, FUNCTION_MSP_TELEMETRY, NULL, baudRates[baudRateIndex], MSP_TELEMETRY_INITIAL_PORT_MODE, SERIAL_NOT_INVERTED); + mspTelemetryPort = openSerialPort(portConfig->identifier, FUNCTION_TELEMETRY_MSP, NULL, baudRates[baudRateIndex], TELEMETRY_MSP_INITIAL_PORT_MODE, SERIAL_NOT_INVERTED); if (!mspTelemetryPort) { return; diff --git a/src/main/telemetry/smartport.c b/src/main/telemetry/smartport.c index 8b1e77506..6f74e55a1 100644 --- a/src/main/telemetry/smartport.c +++ b/src/main/telemetry/smartport.c @@ -214,8 +214,8 @@ static void smartPortSendPackage(uint16_t id, uint32_t val) void initSmartPortTelemetry(telemetryConfig_t *initialTelemetryConfig) { telemetryConfig = initialTelemetryConfig; - portConfig = findSerialPortConfig(FUNCTION_SMARTPORT_TELEMETRY); - smartPortPortSharing = determinePortSharing(portConfig, FUNCTION_SMARTPORT_TELEMETRY); + portConfig = findSerialPortConfig(FUNCTION_TELEMETRY_SMARTPORT); + smartPortPortSharing = determinePortSharing(portConfig, FUNCTION_TELEMETRY_SMARTPORT); } void freeSmartPortTelemetryPort(void) @@ -233,7 +233,7 @@ void configureSmartPortTelemetryPort(void) return; } - smartPortSerialPort = openSerialPort(portConfig->identifier, FUNCTION_SMARTPORT_TELEMETRY, NULL, SMARTPORT_BAUD, SMARTPORT_UART_MODE, telemetryConfig->telemetry_inversion); + smartPortSerialPort = openSerialPort(portConfig->identifier, FUNCTION_TELEMETRY_SMARTPORT, NULL, SMARTPORT_BAUD, SMARTPORT_UART_MODE, telemetryConfig->telemetry_inversion); if (!smartPortSerialPort) { return;