diff --git a/src/main/blackbox/blackbox.h b/src/main/blackbox/blackbox.h index b73b54ea7d..694343d44b 100644 --- a/src/main/blackbox/blackbox.h +++ b/src/main/blackbox/blackbox.h @@ -27,12 +27,8 @@ typedef enum BlackboxDevice { BLACKBOX_DEVICE_NONE = 0, -#ifdef USE_FLASHFS BLACKBOX_DEVICE_FLASH = 1, -#endif -#ifdef USE_SDCARD BLACKBOX_DEVICE_SDCARD = 2, -#endif BLACKBOX_DEVICE_SERIAL = 3 } BlackboxDevice_e; diff --git a/src/main/blackbox/blackbox_io.c b/src/main/blackbox/blackbox_io.c index a0ee1c91e7..da8886475d 100644 --- a/src/main/blackbox/blackbox_io.c +++ b/src/main/blackbox/blackbox_io.c @@ -261,7 +261,7 @@ bool blackboxDeviceOpen(void) switch (blackboxConfig()->device) { case BLACKBOX_DEVICE_SERIAL: { - serialPortConfig_t *portConfig = findSerialPortConfig(FUNCTION_BLACKBOX); + const serialPortConfig_t *portConfig = findSerialPortConfig(FUNCTION_BLACKBOX); baudRate_e baudRateIndex; portOptions_e portOptions = SERIAL_PARITY_NO | SERIAL_NOT_INVERTED; diff --git a/src/main/cli/cli.c b/src/main/cli/cli.c index 7e5f7d1e6e..8902d83fc3 100644 --- a/src/main/cli/cli.c +++ b/src/main/cli/cli.c @@ -1238,14 +1238,14 @@ static void cliSerial(char *cmdline) serialPortConfig_t portConfig; memset(&portConfig, 0 , sizeof(portConfig)); - serialPortConfig_t *currentConfig; uint8_t validArgumentCount = 0; const char *ptr = cmdline; int val = atoi(ptr++); - currentConfig = serialFindPortConfiguration(val); + serialPortConfig_t *currentConfig = serialFindPortConfigurationMutable(val); + if (currentConfig) { portConfig.identifier = val; validArgumentCount++; diff --git a/src/main/config/config.c b/src/main/config/config.c index 1805f314e3..eb546f8057 100644 --- a/src/main/config/config.c +++ b/src/main/config/config.c @@ -62,6 +62,7 @@ #include "osd/osd.h" +#include "pg/adc.h" #include "pg/beeper.h" #include "pg/beeper_dev.h" #include "pg/gyrodev.h" @@ -69,9 +70,12 @@ #include "pg/pg.h" #include "pg/pg_ids.h" #include "pg/rx.h" +#include "pg/rx_spi.h" +#include "pg/sdcard.h" #include "pg/vtx_table.h" #include "rx/rx.h" +#include "rx/rx_spi.h" #include "scheduler/scheduler.h" @@ -205,7 +209,7 @@ static void validateAndFixConfig(void) } #if defined(USE_GPS) - serialPortConfig_t *gpsSerial = findSerialPortConfig(FUNCTION_GPS); + const serialPortConfig_t *gpsSerial = findSerialPortConfig(FUNCTION_GPS); if (gpsConfig()->provider == GPS_MSP && gpsSerial) { serialRemovePort(gpsSerial->identifier); } @@ -392,6 +396,18 @@ static void validateAndFixConfig(void) } #endif +#ifdef USE_ADC + adcConfigMutable()->vbat.enabled = (batteryConfig()->voltageMeterSource == VOLTAGE_METER_ADC); + adcConfigMutable()->current.enabled = (batteryConfig()->currentMeterSource == CURRENT_METER_ADC); + + // The FrSky D SPI RX sends RSSI_ADC_PIN (if configured) as A2 + adcConfigMutable()->rssi.enabled = featureIsEnabled(FEATURE_RSSI_ADC); +#ifdef USE_RX_SPI + adcConfigMutable()->rssi.enabled |= (featureIsEnabled(FEATURE_RX_SPI) && rxSpiConfig()->rx_spi_protocol == RX_SPI_FRSKY_D); +#endif +#endif // USE_ADC + + // clear features that are not supported. // I have kept them all here in one place, some could be moved to sections of code above. @@ -647,16 +663,19 @@ void validateAndFixGyroConfig(void) #ifdef USE_BLACKBOX #ifndef USE_FLASHFS - if (blackboxConfig()->device == 1) { // BLACKBOX_DEVICE_FLASH (but not defined) + if (blackboxConfig()->device == BLACKBOX_DEVICE_FLASH) { blackboxConfigMutable()->device = BLACKBOX_DEVICE_NONE; } #endif // USE_FLASHFS -#ifndef USE_SDCARD - if (blackboxConfig()->device == 2) { // BLACKBOX_DEVICE_SDCARD (but not defined) - blackboxConfigMutable()->device = BLACKBOX_DEVICE_NONE; + if (blackboxConfig()->device == BLACKBOX_DEVICE_SDCARD) { +#if defined(USE_SDCARD) + if (!sdcardConfig()->mode) +#endif + { + blackboxConfigMutable()->device = BLACKBOX_DEVICE_NONE; + } } -#endif // USE_SDCARD #endif // USE_BLACKBOX if (systemConfig()->activeRateProfile >= CONTROL_RATE_PROFILE_COUNT) { diff --git a/src/main/drivers/rangefinder/rangefinder_lidartf.c b/src/main/drivers/rangefinder/rangefinder_lidartf.c index 5bc72a9403..76e97d052b 100644 --- a/src/main/drivers/rangefinder/rangefinder_lidartf.c +++ b/src/main/drivers/rangefinder/rangefinder_lidartf.c @@ -241,7 +241,7 @@ int32_t lidarTFGetDistance(rangefinderDev_t *dev) static bool lidarTFDetect(rangefinderDev_t *dev, uint8_t devtype) { - serialPortConfig_t *portConfig = findSerialPortConfig(FUNCTION_LIDAR_TF); + const serialPortConfig_t *portConfig = findSerialPortConfig(FUNCTION_LIDAR_TF); if (!portConfig) { return false; diff --git a/src/main/fc/controlrate_profile.c b/src/main/fc/controlrate_profile.c index 3c2651e9d2..17838e5e69 100644 --- a/src/main/fc/controlrate_profile.c +++ b/src/main/fc/controlrate_profile.c @@ -87,6 +87,6 @@ void copyControlRateProfile(const uint8_t dstControlRateProfileIndex, const uint if ((dstControlRateProfileIndex < CONTROL_RATE_PROFILE_COUNT && srcControlRateProfileIndex < CONTROL_RATE_PROFILE_COUNT) && dstControlRateProfileIndex != srcControlRateProfileIndex ) { - memcpy(controlRateProfilesMutable(dstControlRateProfileIndex), controlRateProfilesMutable(srcControlRateProfileIndex), sizeof(controlRateConfig_t)); + memcpy(controlRateProfilesMutable(dstControlRateProfileIndex), controlRateProfiles(srcControlRateProfileIndex), sizeof(controlRateConfig_t)); } } diff --git a/src/main/fc/init.c b/src/main/fc/init.c index 6862b20ba8..8a9e2447f8 100644 --- a/src/main/fc/init.c +++ b/src/main/fc/init.c @@ -144,14 +144,12 @@ #include "pg/pin_pull_up_down.h" #include "pg/pg.h" #include "pg/rx.h" -#include "pg/rx_spi.h" #include "pg/rx_pwm.h" #include "pg/sdcard.h" #include "pg/vcd.h" #include "pg/vtx_io.h" #include "rx/rx.h" -#include "rx/rx_spi.h" #include "rx/spektrum.h" #include "scheduler/scheduler.h" @@ -682,14 +680,6 @@ void init(void) #endif #ifdef USE_ADC - adcConfigMutable()->vbat.enabled = (batteryConfig()->voltageMeterSource == VOLTAGE_METER_ADC); - adcConfigMutable()->current.enabled = (batteryConfig()->currentMeterSource == CURRENT_METER_ADC); - - // The FrSky D SPI RX sends RSSI_ADC_PIN (if configured) as A2 - adcConfigMutable()->rssi.enabled = featureIsEnabled(FEATURE_RSSI_ADC); -#ifdef USE_RX_SPI - adcConfigMutable()->rssi.enabled |= (featureIsEnabled(FEATURE_RX_SPI) && rxSpiConfig()->rx_spi_protocol == RX_SPI_FRSKY_D); -#endif adcInit(adcConfig()); #endif @@ -900,8 +890,6 @@ void init(void) initFlags |= SD_INIT_ATTEMPTED; sdCardAndFSInit(); } - } else { - blackboxConfigMutable()->device = BLACKBOX_DEVICE_NONE; } } #endif diff --git a/src/main/io/beeper.c b/src/main/io/beeper.c index f9b689c822..3ceedcaca3 100644 --- a/src/main/io/beeper.c +++ b/src/main/io/beeper.c @@ -249,7 +249,7 @@ void beeper(beeperMode_e mode) { if ( mode == BEEPER_SILENCE || ( - (beeperConfigMutable()->beeper_off_flags & BEEPER_GET_FLAG(BEEPER_USB)) + (beeperConfig()->beeper_off_flags & BEEPER_GET_FLAG(BEEPER_USB)) && getBatteryState() == BATTERY_NOT_PRESENT ) ) { @@ -361,7 +361,7 @@ void beeperWarningBeeps(uint8_t beepCount) #ifdef USE_GPS static void beeperGpsStatus(void) { - if (!(beeperConfigMutable()->beeper_off_flags & BEEPER_GET_FLAG(BEEPER_GPS_STATUS))) { + if (!(beeperConfig()->beeper_off_flags & BEEPER_GET_FLAG(BEEPER_GPS_STATUS))) { // if GPS fix then beep out number of satellites if (STATE(GPS_FIX) && gpsSol.numSat >= 5) { uint8_t i = 0; @@ -417,7 +417,7 @@ void beeperUpdate(timeUs_t currentTimeUs) #endif if (currentBeeperEntry->sequence[beeperPos] != 0) { - if (!(beeperConfigMutable()->beeper_off_flags & BEEPER_GET_FLAG(currentBeeperEntry->mode))) { + if (!(beeperConfig()->beeper_off_flags & BEEPER_GET_FLAG(currentBeeperEntry->mode))) { BEEP_ON; beeperIsOn = true; } diff --git a/src/main/io/gps.c b/src/main/io/gps.c index de1e4ff9e7..ef451d1ad2 100644 --- a/src/main/io/gps.c +++ b/src/main/io/gps.c @@ -279,7 +279,7 @@ void gpsInit(void) return; } - serialPortConfig_t *gpsPortConfig = findSerialPortConfig(FUNCTION_GPS); + const serialPortConfig_t *gpsPortConfig = findSerialPortConfig(FUNCTION_GPS); if (!gpsPortConfig) { return; } diff --git a/src/main/io/ledstrip.c b/src/main/io/ledstrip.c index eac37dd67c..ecc47537e9 100644 --- a/src/main/io/ledstrip.c +++ b/src/main/io/ledstrip.c @@ -435,14 +435,14 @@ static quadrant_e getLedQuadrant(const int ledIndex) return quad; } -static hsvColor_t* getDirectionalModeColor(const int ledIndex, const modeColorIndexes_t *modeColors) +static const hsvColor_t* getDirectionalModeColor(const int ledIndex, const modeColorIndexes_t *modeColors) { const ledConfig_t *ledConfig = &ledStripStatusModeConfig()->ledConfigs[ledIndex]; const int ledDirection = ledGetDirection(ledConfig); for (unsigned i = 0; i < LED_DIRECTION_COUNT; i++) { if (ledDirection & (1 << i)) { - return &ledStripStatusModeConfigMutable()->colors[modeColors->color[i]]; + return &ledStripStatusModeConfig()->colors[modeColors->color[i]]; } } diff --git a/src/main/io/rcdevice.c b/src/main/io/rcdevice.c index 842521a6b0..eb62e666c4 100644 --- a/src/main/io/rcdevice.c +++ b/src/main/io/rcdevice.c @@ -272,7 +272,7 @@ void runcamDeviceInit(runcamDevice_t *device) { device->isReady = false; serialPortFunction_e portID = FUNCTION_RCDEVICE; - serialPortConfig_t *portConfig = findSerialPortConfig(portID); + const serialPortConfig_t *portConfig = findSerialPortConfig(portID); if (portConfig != NULL) { device->serialPort = openSerialPort(portConfig->identifier, portID, NULL, NULL, 115200, MODE_RXTX, SERIAL_NOT_INVERTED); device->info.protocolVersion = rcdeviceConfig()->protocolVersion; diff --git a/src/main/io/serial.c b/src/main/io/serial.c index 2f0877ab42..06ff2b928a 100644 --- a/src/main/io/serial.c +++ b/src/main/io/serial.c @@ -108,6 +108,17 @@ const uint32_t baudRates[] = {0, 9600, 19200, 38400, 57600, 115200, 230400, 2500 #define BAUD_RATE_COUNT (sizeof(baudRates) / sizeof(baudRates[0])) +serialPortConfig_t *serialFindPortConfigurationMutable(serialPortIdentifier_e identifier) +{ + for (int index = 0; index < SERIAL_PORT_COUNT; index++) { + serialPortConfig_t *candidate = &serialConfigMutable()->portConfigs[index]; + if (candidate->identifier == identifier) { + return candidate; + } + } + return NULL; +} + PG_REGISTER_WITH_RESET_FN(serialConfig_t, serialConfig, PG_SERIAL_CONFIG, 0); void pgResetFn_serialConfig(serialConfig_t *serialConfig) @@ -125,14 +136,14 @@ void pgResetFn_serialConfig(serialConfig_t *serialConfig) serialConfig->portConfigs[0].functionMask = FUNCTION_MSP; #ifdef SERIALRX_UART - serialPortConfig_t *serialRxUartConfig = serialFindPortConfiguration(SERIALRX_UART); + serialPortConfig_t *serialRxUartConfig = serialFindPortConfigurationMutable(SERIALRX_UART); if (serialRxUartConfig) { serialRxUartConfig->functionMask = FUNCTION_RX_SERIAL; } #endif #ifdef SBUS_TELEMETRY_UART - serialPortConfig_t *serialTlemetryUartConfig = serialFindPortConfiguration(SBUS_TELEMETRY_UART); + serialPortConfig_t *serialTlemetryUartConfig = serialFindPortConfigurationMutable(SBUS_TELEMETRY_UART); if (serialTlemetryUartConfig) { serialTlemetryUartConfig->functionMask = FUNCTION_TELEMETRY_SMARTPORT; } @@ -140,7 +151,7 @@ void pgResetFn_serialConfig(serialConfig_t *serialConfig) #if defined(USE_VCP) && defined(USE_MSP_UART) if (serialConfig->portConfigs[0].identifier == SERIAL_PORT_USB_VCP) { - serialPortConfig_t * uart1Config = serialFindPortConfiguration(SERIAL_PORT_USART1); + serialPortConfig_t * uart1Config = serialFindPortConfigurationMutable(SERIAL_PORT_USART1); if (uart1Config) { uart1Config->functionMask = FUNCTION_MSP; } @@ -202,17 +213,17 @@ typedef struct findSerialPortConfigState_s { static findSerialPortConfigState_t findSerialPortConfigState; -serialPortConfig_t *findSerialPortConfig(serialPortFunction_e function) +const serialPortConfig_t *findSerialPortConfig(serialPortFunction_e function) { memset(&findSerialPortConfigState, 0, sizeof(findSerialPortConfigState)); return findNextSerialPortConfig(function); } -serialPortConfig_t *findNextSerialPortConfig(serialPortFunction_e function) +const serialPortConfig_t *findNextSerialPortConfig(serialPortFunction_e function) { while (findSerialPortConfigState.lastIndex < SERIAL_PORT_COUNT) { - serialPortConfig_t *candidate = &serialConfigMutable()->portConfigs[findSerialPortConfigState.lastIndex++]; + const serialPortConfig_t *candidate = &serialConfig()->portConfigs[findSerialPortConfigState.lastIndex++]; if (candidate->functionMask & function) { return candidate; @@ -306,10 +317,10 @@ bool isSerialConfigValid(const serialConfig_t *serialConfigToCheck) return true; } -serialPortConfig_t *serialFindPortConfiguration(serialPortIdentifier_e identifier) +const serialPortConfig_t *serialFindPortConfiguration(serialPortIdentifier_e identifier) { for (int index = 0; index < SERIAL_PORT_COUNT; index++) { - serialPortConfig_t *candidate = &serialConfigMutable()->portConfigs[index]; + const serialPortConfig_t *candidate = &serialConfig()->portConfigs[index]; if (candidate->identifier == identifier) { return candidate; } @@ -319,7 +330,7 @@ serialPortConfig_t *serialFindPortConfiguration(serialPortIdentifier_e identifie bool doesConfigurationUsePort(serialPortIdentifier_e identifier) { - serialPortConfig_t *candidate = serialFindPortConfiguration(identifier); + const serialPortConfig_t *candidate = serialFindPortConfiguration(identifier); return candidate != NULL && candidate->functionMask; } diff --git a/src/main/io/serial.h b/src/main/io/serial.h index dff90a1970..94eb170d41 100644 --- a/src/main/io/serial.h +++ b/src/main/io/serial.h @@ -139,10 +139,11 @@ void serialRemovePort(serialPortIdentifier_e identifier); uint8_t serialGetAvailablePortCount(void); bool serialIsPortAvailable(serialPortIdentifier_e identifier); bool isSerialConfigValid(const serialConfig_t *serialConfig); -serialPortConfig_t *serialFindPortConfiguration(serialPortIdentifier_e identifier); +const serialPortConfig_t *serialFindPortConfiguration(serialPortIdentifier_e identifier); +serialPortConfig_t *serialFindPortConfigurationMutable(serialPortIdentifier_e identifier); bool doesConfigurationUsePort(serialPortIdentifier_e portIdentifier); -serialPortConfig_t *findSerialPortConfig(serialPortFunction_e function); -serialPortConfig_t *findNextSerialPortConfig(serialPortFunction_e function); +const serialPortConfig_t *findSerialPortConfig(serialPortFunction_e function); +const serialPortConfig_t *findNextSerialPortConfig(serialPortFunction_e function); portSharing_e determinePortSharing(const serialPortConfig_t *portConfig, serialPortFunction_e function); bool isSerialPortShared(const serialPortConfig_t *portConfig, uint16_t functionMask, serialPortFunction_e sharedWithFunction); diff --git a/src/main/io/vtx_smartaudio.c b/src/main/io/vtx_smartaudio.c index 8b7f2faf5d..c0a9192a3a 100644 --- a/src/main/io/vtx_smartaudio.c +++ b/src/main/io/vtx_smartaudio.c @@ -697,7 +697,7 @@ bool vtxSmartAudioInit(void) dprintf(("smartAudioInit: OK\r\n")); #endif - serialPortConfig_t *portConfig = findSerialPortConfig(FUNCTION_VTX_SMARTAUDIO); + const serialPortConfig_t *portConfig = findSerialPortConfig(FUNCTION_VTX_SMARTAUDIO); if (portConfig) { portOptions_e portOptions = SERIAL_STOPBITS_2 | SERIAL_BIDIR_NOPULL; #if defined(USE_VTX_COMMON) diff --git a/src/main/io/vtx_tramp.c b/src/main/io/vtx_tramp.c index dfe49c17a6..27b072714d 100644 --- a/src/main/io/vtx_tramp.c +++ b/src/main/io/vtx_tramp.c @@ -620,7 +620,7 @@ static const vtxVTable_t trampVTable = { bool vtxTrampInit(void) { - serialPortConfig_t *portConfig = findSerialPortConfig(FUNCTION_VTX_TRAMP); + const serialPortConfig_t *portConfig = findSerialPortConfig(FUNCTION_VTX_TRAMP); if (portConfig) { portOptions_e portOptions = 0; diff --git a/src/main/msp/msp.c b/src/main/msp/msp.c index 58fef8cc16..3f882d3718 100644 --- a/src/main/msp/msp.c +++ b/src/main/msp/msp.c @@ -2961,7 +2961,8 @@ static mspResult_e mspProcessInCommand(mspDescriptor_t srcDesc, uint8_t cmdMSP, while (remainingPortsInPacket--) { uint8_t identifier = sbufReadU8(src); - serialPortConfig_t *portConfig = serialFindPortConfiguration(identifier); + serialPortConfig_t *portConfig = serialFindPortConfigurationMutable(identifier); + if (!portConfig) { return MSP_RESULT_ERROR; } diff --git a/src/main/msp/msp_serial.c b/src/main/msp/msp_serial.c index 31a21ed124..4790fa9fb8 100644 --- a/src/main/msp/msp_serial.c +++ b/src/main/msp/msp_serial.c @@ -54,7 +54,7 @@ static void resetMspPort(mspPort_t *mspPortToReset, serialPort_t *serialPort, bo void mspSerialAllocatePorts(void) { uint8_t portIndex = 0; - serialPortConfig_t *portConfig = findSerialPortConfig(FUNCTION_MSP); + const serialPortConfig_t *portConfig = findSerialPortConfig(FUNCTION_MSP); while (portConfig && portIndex < MAX_MSP_PORT_COUNT) { mspPort_t *mspPort = &mspPorts[portIndex]; diff --git a/src/main/sensors/esc_sensor.c b/src/main/sensors/esc_sensor.c index 83e5b50055..5444766f62 100644 --- a/src/main/sensors/esc_sensor.c +++ b/src/main/sensors/esc_sensor.c @@ -209,7 +209,7 @@ static void escSensorDataReceive(uint16_t c, void *data) bool escSensorInit(void) { - serialPortConfig_t *portConfig = findSerialPortConfig(FUNCTION_ESC_SENSOR); + const serialPortConfig_t *portConfig = findSerialPortConfig(FUNCTION_ESC_SENSOR); if (!portConfig) { return false; } diff --git a/src/main/target/BLUEJAYF4/initialisation.c b/src/main/target/BLUEJAYF4/initialisation.c index bf08512323..6c49ab5abc 100644 --- a/src/main/target/BLUEJAYF4/initialisation.c +++ b/src/main/target/BLUEJAYF4/initialisation.c @@ -55,7 +55,7 @@ void targetPreInit(void) IOConfigGPIO(inverter, IOCFG_OUT_PP); bool high = false; - serialPortConfig_t *portConfig = serialFindPortConfiguration(SERIAL_PORT_USART1); + serialPortConfig_t *portConfig = serialFindPortConfigurationMutable(SERIAL_PORT_USART1); if (portConfig) { bool smartportEnabled = (portConfig->functionMask & FUNCTION_TELEMETRY_SMARTPORT); if (smartportEnabled && (!telemetryConfig()->telemetry_inverted) && (featureIsEnabled(FEATURE_TELEMETRY))) { diff --git a/src/main/target/MAMBAF722/config.c b/src/main/target/MAMBAF722/config.c index 375e2a5070..625abf2d35 100644 --- a/src/main/target/MAMBAF722/config.c +++ b/src/main/target/MAMBAF722/config.c @@ -37,10 +37,10 @@ void targetConfiguration(void) pinioConfigMutable()->config[0] = PINIO_CONFIG_OUT_INVERTED | PINIO_CONFIG_MODE_OUT_PP; pinioBoxConfigMutable()->permanentId[0] = BOXARM; - serialPortConfig_t *bluetoothMspUART = serialFindPortConfiguration(BLUETOOTH_MSP_UART); + serialPortConfig_t *bluetoothMspUART = serialFindPortConfigurationMutable(BLUETOOTH_MSP_UART); if (bluetoothMspUART) { bluetoothMspUART->functionMask = FUNCTION_MSP; bluetoothMspUART->msp_baudrateIndex = BLUETOOTH_MSP_BAUDRATE; } } -#endif \ No newline at end of file +#endif diff --git a/src/main/target/SPEEDYBEEF4/config.c b/src/main/target/SPEEDYBEEF4/config.c index 6bb40a7518..4ea356f0f8 100644 --- a/src/main/target/SPEEDYBEEF4/config.c +++ b/src/main/target/SPEEDYBEEF4/config.c @@ -37,7 +37,7 @@ void targetConfiguration(void) pinioConfigMutable()->config[0] = PINIO_CONFIG_OUT_INVERTED | PINIO_CONFIG_MODE_OUT_PP; pinioBoxConfigMutable()->permanentId[0] = BOXARM; - serialPortConfig_t *bluetoothMspUART = serialFindPortConfiguration(BLUETOOTH_MSP_UART); + serialPortConfig_t *bluetoothMspUART = serialFindPortConfigurationMutable(BLUETOOTH_MSP_UART); if (bluetoothMspUART) { bluetoothMspUART->functionMask = FUNCTION_MSP; bluetoothMspUART->msp_baudrateIndex = BLUETOOTH_MSP_BAUDRATE; diff --git a/src/main/target/SPEEDYBEEF7/config.c b/src/main/target/SPEEDYBEEF7/config.c index b52c826a95..9ca8b9bee4 100644 --- a/src/main/target/SPEEDYBEEF7/config.c +++ b/src/main/target/SPEEDYBEEF7/config.c @@ -47,7 +47,7 @@ void targetConfiguration(void) pinioConfigMutable()->config[0] = PINIO_CONFIG_OUT_INVERTED | PINIO_CONFIG_MODE_OUT_PP; pinioBoxConfigMutable()->permanentId[0] = BOXARM; - serialPortConfig_t *bluetoothMspUART = serialFindPortConfiguration(BLUETOOTH_MSP_UART); + serialPortConfig_t *bluetoothMspUART = serialFindPortConfigurationMutable(BLUETOOTH_MSP_UART); if (bluetoothMspUART) { bluetoothMspUART->functionMask = FUNCTION_MSP; bluetoothMspUART->msp_baudrateIndex = BLUETOOTH_MSP_BAUDRATE; diff --git a/src/main/telemetry/frsky_hub.c b/src/main/telemetry/frsky_hub.c index 8d484e6983..424ac943e7 100644 --- a/src/main/telemetry/frsky_hub.c +++ b/src/main/telemetry/frsky_hub.c @@ -74,7 +74,7 @@ #include "frsky_hub.h" static serialPort_t *frSkyHubPort = NULL; -static serialPortConfig_t *portConfig = NULL; +static const serialPortConfig_t *portConfig = NULL; #define FRSKY_HUB_BAUDRATE 9600 #define FRSKY_HUB_INITIAL_PORT_MODE MODE_TX diff --git a/src/main/telemetry/hott.c b/src/main/telemetry/hott.c index aa6cc5d759..ba22bdaeaa 100644 --- a/src/main/telemetry/hott.c +++ b/src/main/telemetry/hott.c @@ -124,7 +124,7 @@ static uint8_t hottMsgCrc; #define HOTT_PORT_MODE MODE_RXTX // must be opened in RXTX so that TX and RX pins are allocated. static serialPort_t *hottPort = NULL; -static serialPortConfig_t *portConfig; +static const serialPortConfig_t *portConfig; static bool hottTelemetryEnabled = false; static portSharing_e hottPortSharing; diff --git a/src/main/telemetry/ibus.c b/src/main/telemetry/ibus.c index 6c2bca0a96..9f1c817166 100644 --- a/src/main/telemetry/ibus.c +++ b/src/main/telemetry/ibus.c @@ -76,7 +76,7 @@ static serialPort_t *ibusSerialPort = NULL; -static serialPortConfig_t *ibusSerialPortConfig; +static const serialPortConfig_t *ibusSerialPortConfig; /* The sent bytes will be echoed back since Tx and Rx are wired together, this counter * will keep track of how many rx chars that shall be discarded */ diff --git a/src/main/telemetry/ltm.c b/src/main/telemetry/ltm.c index 667b79b35b..5d6df83249 100644 --- a/src/main/telemetry/ltm.c +++ b/src/main/telemetry/ltm.c @@ -84,7 +84,7 @@ #define LTM_CYCLETIME 100 static serialPort_t *ltmPort; -static serialPortConfig_t *portConfig; +static const serialPortConfig_t *portConfig; static bool ltmEnabled; static portSharing_e ltmPortSharing; static uint8_t ltm_crc; diff --git a/src/main/telemetry/mavlink.c b/src/main/telemetry/mavlink.c index ede42bd263..8355687172 100644 --- a/src/main/telemetry/mavlink.c +++ b/src/main/telemetry/mavlink.c @@ -86,7 +86,7 @@ extern uint16_t rssi; // FIXME dependency on mw.c static serialPort_t *mavlinkPort = NULL; -static serialPortConfig_t *portConfig; +static const serialPortConfig_t *portConfig; static bool mavlinkTelemetryEnabled = false; static portSharing_e mavlinkPortSharing; diff --git a/src/main/telemetry/smartport.c b/src/main/telemetry/smartport.c index 5dac8a3bb0..18a0ba87e8 100644 --- a/src/main/telemetry/smartport.c +++ b/src/main/telemetry/smartport.c @@ -180,7 +180,7 @@ static frSkyTableInfo_t frSkyEscDataIdTableInfo = {frSkyEscDataIdTable, 0, 0}; #define SMARTPORT_SERVICE_TIMEOUT_US 1000 // max allowed time to find a value to send static serialPort_t *smartPortSerialPort = NULL; // The 'SmartPort'(tm) Port. -static serialPortConfig_t *portConfig; +static const serialPortConfig_t *portConfig; static portSharing_e smartPortPortSharing; diff --git a/src/main/telemetry/telemetry.c b/src/main/telemetry/telemetry.c index daacd8bf35..c8b57511ed 100644 --- a/src/main/telemetry/telemetry.c +++ b/src/main/telemetry/telemetry.c @@ -228,6 +228,6 @@ void telemetryProcess(uint32_t currentTime) bool telemetryIsSensorEnabled(sensor_e sensor) { - return ~(telemetryConfigMutable()->disabledSensors) & sensor; + return ~(telemetryConfig()->disabledSensors) & sensor; } #endif diff --git a/src/test/unit/blackbox_unittest.cc b/src/test/unit/blackbox_unittest.cc index 408b543fea..1cc19e64a1 100644 --- a/src/test/unit/blackbox_unittest.cc +++ b/src/test/unit/blackbox_unittest.cc @@ -394,7 +394,7 @@ uint32_t serialTxBytesFree(const serialPort_t *) {return 0;} bool isSerialTransmitBufferEmpty(const serialPort_t *) {return false;} bool featureIsEnabled(uint32_t) {return false;} void mspSerialReleasePortIfAllocated(serialPort_t *) {} -serialPortConfig_t *findSerialPortConfig(serialPortFunction_e ) {return NULL;} +const serialPortConfig_t *findSerialPortConfig(serialPortFunction_e ) {return NULL;} serialPort_t *findSharedSerialPort(uint16_t , serialPortFunction_e ) {return NULL;} serialPort_t *openSerialPort(serialPortIdentifier_e, serialPortFunction_e, serialReceiveCallbackPtr, void *, uint32_t, portMode_e, portOptions_e) {return NULL;} void closeSerialPort(serialPort_t *) {} diff --git a/src/test/unit/cli_unittest.cc b/src/test/unit/cli_unittest.cc index 04e9dc8c53..14b2ae7c57 100644 --- a/src/test/unit/cli_unittest.cc +++ b/src/test/unit/cli_unittest.cc @@ -278,7 +278,7 @@ uint8_t getCurrentControlRateProfileIndex(void){ return 1; } void changeControlRateProfile(uint8_t) {} void resetAllRxChannelRangeConfigurations(rxChannelRangeConfig_t *) {} void writeEEPROM() {} -serialPortConfig_t *serialFindPortConfiguration(serialPortIdentifier_e) {return NULL; } +serialPortConfig_t *serialFindPortConfigurationMutable(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, void *, uint32_t, portMode_e, portOptions_e) { return NULL; } diff --git a/src/test/unit/io_serial_unittest.cc b/src/test/unit/io_serial_unittest.cc index 3fc4ff7adf..5e53baa373 100644 --- a/src/test/unit/io_serial_unittest.cc +++ b/src/test/unit/io_serial_unittest.cc @@ -47,7 +47,7 @@ TEST(IoSerialTest, TestFindPortConfig) serialInit(false, SERIAL_PORT_NONE); // when - serialPortConfig_t *portConfig = findSerialPortConfig(FUNCTION_MSP); + const serialPortConfig_t *portConfig = findSerialPortConfig(FUNCTION_MSP); // then EXPECT_EQ(NULL, portConfig); diff --git a/src/test/unit/link_quality_unittest.cc b/src/test/unit/link_quality_unittest.cc index 3d965c4b2d..e8df023050 100644 --- a/src/test/unit/link_quality_unittest.cc +++ b/src/test/unit/link_quality_unittest.cc @@ -431,7 +431,7 @@ extern "C" { bool isBlackboxDeviceWorking() { return true; } bool isBlackboxDeviceFull() { return false; } serialPort_t *openSerialPort(serialPortIdentifier_e, serialPortFunction_e, serialReceiveCallbackPtr, void *, uint32_t, portMode_e, portOptions_e) {return NULL;} - serialPortConfig_t *findSerialPortConfig(serialPortFunction_e ) {return NULL;} + const serialPortConfig_t *findSerialPortConfig(serialPortFunction_e ) {return NULL;} bool telemetryCheckRxPortShared(const serialPortConfig_t *) {return false;} bool cmsDisplayPortRegister(displayPort_t *) { return false; } uint16_t getCoreTemperatureCelsius(void) { return 0; } diff --git a/src/test/unit/rcdevice_unittest.cc b/src/test/unit/rcdevice_unittest.cc index 89f800d2b9..0392453244 100644 --- a/src/test/unit/rcdevice_unittest.cc +++ b/src/test/unit/rcdevice_unittest.cc @@ -791,7 +791,7 @@ extern "C" { return NULL; } - serialPortConfig_t *findSerialPortConfig(serialPortFunction_e function) + const serialPortConfig_t *findSerialPortConfig(serialPortFunction_e function) { UNUSED(function); if (testData.isRunCamSplitPortConfigurated) { @@ -960,7 +960,7 @@ extern "C" { // testData.maxTimesOfRespDataAvailable = testData.responseDataLen + 1; } - serialPortConfig_t *findNextSerialPortConfig(serialPortFunction_e function) + const serialPortConfig_t *findNextSerialPortConfig(serialPortFunction_e function) { UNUSED(function); diff --git a/src/test/unit/rx_crsf_unittest.cc b/src/test/unit/rx_crsf_unittest.cc index 194333d932..fa1cbdb41f 100644 --- a/src/test/unit/rx_crsf_unittest.cc +++ b/src/test/unit/rx_crsf_unittest.cc @@ -291,7 +291,7 @@ int16_t debug[DEBUG16_VALUE_COUNT]; uint32_t micros(void) {return dummyTimeUs;} uint32_t microsISR(void) {return micros();} serialPort_t *openSerialPort(serialPortIdentifier_e, serialPortFunction_e, serialReceiveCallbackPtr, void *, uint32_t, portMode_e, portOptions_e) {return NULL;} -serialPortConfig_t *findSerialPortConfig(serialPortFunction_e ) {return NULL;} +const serialPortConfig_t *findSerialPortConfig(serialPortFunction_e ) {return NULL;} bool telemetryCheckRxPortShared(const serialPortConfig_t *) {return false;} serialPort_t *telemetrySharedPort = NULL; void crsfScheduleDeviceInfoResponse(void) {}; diff --git a/src/test/unit/rx_ibus_unittest.cc b/src/test/unit/rx_ibus_unittest.cc index 9323a91809..d767ac16c7 100644 --- a/src/test/unit/rx_ibus_unittest.cc +++ b/src/test/unit/rx_ibus_unittest.cc @@ -103,7 +103,7 @@ bool isSerialPortShared(const serialPortConfig_t *portConfig, return portIsShared; } -serialPortConfig_t *findSerialPortConfig(serialPortFunction_e function) +const serialPortConfig_t *findSerialPortConfig(serialPortFunction_e function) { EXPECT_EQ(function, FUNCTION_RX_SERIAL); return findSerialPortConfig_stub_retval; diff --git a/src/test/unit/rx_sumd_unittest.cc b/src/test/unit/rx_sumd_unittest.cc index 05d6aedab9..f8b6bed5f0 100644 --- a/src/test/unit/rx_sumd_unittest.cc +++ b/src/test/unit/rx_sumd_unittest.cc @@ -99,7 +99,7 @@ static portMode_e serialExpectedMode = MODE_RX; static portOptions_e serialExpectedOptions = SERIAL_UNIDIR; -serialPortConfig_t *findSerialPortConfig(serialPortFunction_e function) +const serialPortConfig_t *findSerialPortConfig(serialPortFunction_e function) { EXPECT_EQ(function, FUNCTION_RX_SERIAL); return findSerialPortConfig_stub_retval; diff --git a/src/test/unit/telemetry_crsf_msp_unittest.cc b/src/test/unit/telemetry_crsf_msp_unittest.cc index d2890d45d1..3049f9872a 100644 --- a/src/test/unit/telemetry_crsf_msp_unittest.cc +++ b/src/test/unit/telemetry_crsf_msp_unittest.cc @@ -257,7 +257,7 @@ extern "C" { uint32_t micros(void) {return dummyTimeUs;} uint32_t microsISR(void) {return micros();} serialPort_t *openSerialPort(serialPortIdentifier_e, serialPortFunction_e, serialReceiveCallbackPtr, void *, uint32_t, portMode_e, portOptions_e) {return NULL;} - serialPortConfig_t *findSerialPortConfig(serialPortFunction_e ) {return NULL;} + const serialPortConfig_t *findSerialPortConfig(serialPortFunction_e ) {return NULL;} bool isBatteryVoltageConfigured(void) { return true; } 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 cb1ac99b97..9280ed3d46 100644 --- a/src/test/unit/telemetry_crsf_unittest.cc +++ b/src/test/unit/telemetry_crsf_unittest.cc @@ -327,7 +327,7 @@ serialPort_t *openSerialPort(serialPortIdentifier_e, serialPortFunction_e, seria void closeSerialPort(serialPort_t *) {} bool isSerialTransmitBufferEmpty(const serialPort_t *) { return true; } -serialPortConfig_t *findSerialPortConfig(serialPortFunction_e) {return NULL;} +const serialPortConfig_t *findSerialPortConfig(serialPortFunction_e) {return NULL;} bool telemetryDetermineEnabledState(portSharing_e) {return true;} bool telemetryCheckRxPortShared(const serialPortConfig_t *, SerialRXType) {return true;} diff --git a/src/test/unit/telemetry_hott_unittest.cc b/src/test/unit/telemetry_hott_unittest.cc index f5bbef28fd..25325ca5d2 100644 --- a/src/test/unit/telemetry_hott_unittest.cc +++ b/src/test/unit/telemetry_hott_unittest.cc @@ -237,7 +237,7 @@ void closeSerialPort(serialPort_t *serialPort) UNUSED(serialPort); } -serialPortConfig_t *findSerialPortConfig(serialPortFunction_e function) +const serialPortConfig_t *findSerialPortConfig(serialPortFunction_e function) { UNUSED(function); diff --git a/src/test/unit/telemetry_ibus_unittest.cc b/src/test/unit/telemetry_ibus_unittest.cc index ab1463e1c1..2b5436c266 100644 --- a/src/test/unit/telemetry_ibus_unittest.cc +++ b/src/test/unit/telemetry_ibus_unittest.cc @@ -162,7 +162,7 @@ void rescheduleTask(cfTaskId_e taskId, uint32_t newPeriodMicros) -serialPortConfig_t *findSerialPortConfig(serialPortFunction_e function) +const serialPortConfig_t *findSerialPortConfig(serialPortFunction_e function) { EXPECT_EQ(FUNCTION_TELEMETRY_IBUS, function); return findSerialPortConfig_stub_retval;