Cleanup some enum values - using topic_type instead of type_topic.

This commit is contained in:
Dominic Clifton 2015-03-03 22:35:40 +00:00
parent 31a00d6b4d
commit 946f65601f
15 changed files with 37 additions and 37 deletions

View File

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

View File

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

View File

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

View File

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

View File

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

View File

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

View File

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

View File

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

View File

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

View File

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

View File

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

View File

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

View File

@ -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_ */

View File

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

View File

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