From 1964362dce2794c43c0e55354937166904802fda Mon Sep 17 00:00:00 2001 From: Martin Budden Date: Thu, 9 Mar 2017 10:44:23 +0000 Subject: [PATCH] Removal of USE_PARAMETER_GROUPS 1 --- src/main/cms/cms_menu_imu.c | 12 +- src/main/config/config_eeprom.c | 21 +- src/main/config/config_eeprom.h | 2 +- src/main/config/config_master.h | 333 --------------------- src/main/config/parameter_group.h | 29 -- src/main/config/parameter_group_ids.h | 4 - src/main/drivers/serial_softserial.c | 4 +- src/main/fc/cli.c | 3 +- src/main/fc/config.c | 13 +- src/main/fc/config.h | 6 - src/main/fc/fc_msp.c | 2 +- src/main/flight/pid.c | 2 - src/main/io/osd.c | 4 - src/main/io/serial.h | 1 + src/main/rx/msp.h | 4 +- src/main/sensors/acceleration.c | 7 - src/main/target/BLUEJAYF4/initialisation.c | 14 +- src/main/target/COLIBRI_RACE/i2c_bst.c | 14 +- src/main/target/RACEBASE/config.c | 2 - 19 files changed, 48 insertions(+), 429 deletions(-) delete mode 100644 src/main/config/config_master.h diff --git a/src/main/cms/cms_menu_imu.c b/src/main/cms/cms_menu_imu.c index bd9643679a..7d900dcee1 100644 --- a/src/main/cms/cms_menu_imu.c +++ b/src/main/cms/cms_menu_imu.c @@ -37,17 +37,19 @@ #include "common/utils.h" +#include "config/config_profile.h" +#include "config/feature.h" +#include "config/parameter_group.h" + #include "fc/config.h" +#include "fc/controlrate_profile.h" #include "fc/rc_controls.h" #include "fc/runtime_config.h" #include "flight/pid.h" -#include "config/config_master.h" -#include "config/config_profile.h" -#include "config/feature.h" -#include "config/parameter_group.h" -#include "config/parameter_group_ids.h" +#include "sensors/gyro.h" + // // PID diff --git a/src/main/config/config_eeprom.c b/src/main/config/config_eeprom.c index 22859b239d..81c5c847a4 100644 --- a/src/main/config/config_eeprom.c +++ b/src/main/config/config_eeprom.c @@ -26,14 +26,18 @@ #include "common/maths.h" +#include "drivers/light_led.h" + #include "config/config_eeprom.h" #include "config/config_streamer.h" -#include "config/config_master.h" #include "config/parameter_group.h" #include "drivers/system.h" #include "fc/config.h" +#include "fc/rc_adjustments.h" + +#include "flight/pid.h" extern uint8_t __config_start; // configured via linker script when building binaries. extern uint8_t __config_end; @@ -115,11 +119,6 @@ bool isEEPROMContentValid(void) uint16_t crc = CRC_START_VALUE; crc = crc16_ccitt_update(crc, header, sizeof(*header)); p += sizeof(*header); -#ifndef USE_PARAMETER_GROUPS - // include the transitional masterConfig record - crc = crc16_ccitt_update(crc, p, sizeof(masterConfig)); - p += sizeof(masterConfig); -#endif for (;;) { const configRecord_t *record = (const configRecord_t *)p; @@ -166,9 +165,6 @@ static const configRecord_t *findEEPROM(const pgRegistry_t *reg, configRecordFla { const uint8_t *p = &__config_start; p += sizeof(configHeader_t); // skip header -#ifndef USE_PARAMETER_GROUPS - p += sizeof(master_t); // skip the transitional master_t record -#endif while (true) { const configRecord_t *record = (const configRecord_t *)p; if (record->size == 0 @@ -189,13 +185,6 @@ static const configRecord_t *findEEPROM(const pgRegistry_t *reg, configRecordFla // but each PG is loaded/initialized exactly once and in defined order. bool loadEEPROM(void) { -#ifndef USE_PARAMETER_GROUPS - // read in the transitional masterConfig record - const uint8_t *p = &__config_start; - p += sizeof(configHeader_t); // skip header - masterConfig = *(master_t*)p; -#endif - PG_FOREACH(reg) { configRecordFlags_e cls_start, cls_end; if (pgIsSystem(reg)) { diff --git a/src/main/config/config_eeprom.h b/src/main/config/config_eeprom.h index f6316d7f69..bd586459c9 100644 --- a/src/main/config/config_eeprom.h +++ b/src/main/config/config_eeprom.h @@ -20,7 +20,7 @@ #include #include -#define EEPROM_CONF_VERSION 157 +#define EEPROM_CONF_VERSION 158 bool isEEPROMContentValid(void); bool loadEEPROM(void); diff --git a/src/main/config/config_master.h b/src/main/config/config_master.h deleted file mode 100644 index 998770a894..0000000000 --- a/src/main/config/config_master.h +++ /dev/null @@ -1,333 +0,0 @@ -/* - * This file is part of Cleanflight. - * - * Cleanflight is free software: you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * Cleanflight is distributed in the hope that it will be useful, - * but WITHOUT ANY WARRANTY; without even the implied warranty of - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - * GNU General Public License for more details. - * - * You should have received a copy of the GNU General Public License - * along with Cleanflight. If not, see . - */ - -#pragma once - -#include - -#include "config/config_profile.h" -#include "config/feature.h" - -#include "blackbox/blackbox.h" - -#include "cms/cms.h" - -#include "drivers/adc.h" -#include "drivers/rx_pwm.h" -#include "drivers/sound_beeper.h" -#include "drivers/sonar_hcsr04.h" -#include "drivers/sdcard.h" -#include "drivers/vcd.h" -#include "drivers/light_led.h" -#include "drivers/flash.h" -#include "drivers/display.h" -#include "drivers/serial.h" - -#include "fc/config.h" -#include "fc/controlrate_profile.h" -#include "fc/rc_adjustments.h" -#include "fc/rc_controls.h" -#include "fc/fc_core.h" - -#include "flight/altitudehold.h" -#include "flight/failsafe.h" -#include "flight/mixer.h" -#include "flight/servos.h" -#include "flight/imu.h" -#include "flight/navigation.h" -#include "flight/pid.h" - -#include "io/beeper.h" -#include "io/gimbal.h" -#include "io/gps.h" -#include "io/ledstrip.h" -#include "io/osd.h" -#include "io/serial.h" -#include "io/servos.h" -#include "io/transponder_ir.h" -#include "io/vtx.h" - -#include "rx/rx.h" - -#include "telemetry/telemetry.h" - -#include "sensors/sensors.h" -#include "sensors/gyro.h" -#include "sensors/acceleration.h" -#include "sensors/boardalignment.h" -#include "sensors/barometer.h" -#include "sensors/battery.h" -#include "sensors/compass.h" - -#ifndef USE_PARAMETER_GROUPS -#define featureConfig(x) (&masterConfig.featureConfig) -#define systemConfig(x) (&masterConfig.systemConfig) -#define motorConfig(x) (&masterConfig.motorConfig) -#define flight3DConfig(x) (&masterConfig.flight3DConfig) -#define servoConfig(x) (&masterConfig.servoConfig) -#define servoMixerConfig(x) (&masterConfig.servoMixerConfig) -#define gimbalConfig(x) (&masterConfig.gimbalConfig) -#define boardAlignment(x) (&masterConfig.boardAlignment) -#define imuConfig(x) (&masterConfig.imuConfig) -#define gyroConfig(x) (&masterConfig.gyroConfig) -#define compassConfig(x) (&masterConfig.compassConfig) -#define accelerometerConfig(x) (&masterConfig.accelerometerConfig) -#define barometerConfig(x) (&masterConfig.barometerConfig) -#define throttleCorrectionConfig(x) (&masterConfig.throttleCorrectionConfig) -#define batteryConfig(x) (&masterConfig.batteryConfig) -#define rcControlsConfig(x) (&masterConfig.rcControlsConfig) -#define navigationConfig(x) (&masterConfig.navigationConfig) -#define gpsConfig(x) (&masterConfig.gpsConfig) -#define rxConfig(x) (&masterConfig.rxConfig) -#define armingConfig(x) (&masterConfig.armingConfig) -#define mixerConfig(x) (&masterConfig.mixerConfig) -#define airplaneConfig(x) (&masterConfig.airplaneConfig) -#define failsafeConfig(x) (&masterConfig.failsafeConfig) -#define serialPinConfig(x) (&masterConfig.serialPinConfig) -#define serialConfig(x) (&masterConfig.serialConfig) -#define telemetryConfig(x) (&masterConfig.telemetryConfig) -#define ibusTelemetryConfig(x) (&masterConfig.telemetryConfig) -#define ppmConfig(x) (&masterConfig.ppmConfig) -#define pwmConfig(x) (&masterConfig.pwmConfig) -#define adcConfig(x) (&masterConfig.adcConfig) -#define beeperDevConfig(x) (&masterConfig.beeperDevConfig) -#define sonarConfig(x) (&masterConfig.sonarConfig) -#define ledStripConfig(x) (&masterConfig.ledStripConfig) -#define statusLedConfig(x) (&masterConfig.statusLedConfig) -#define osdConfig(x) (&masterConfig.osdConfig) -#define vcdProfile(x) (&masterConfig.vcdProfile) -#define sdcardConfig(x) (&masterConfig.sdcardConfig) -#define blackboxConfig(x) (&masterConfig.blackboxConfig) -#define flashConfig(x) (&masterConfig.flashConfig) -#define pidConfig(x) (&masterConfig.pidConfig) -#define adjustmentProfile(x) (&masterConfig.adjustmentProfile) -#define modeActivationProfile(x) (&masterConfig.modeActivationProfile) -#define servoProfile(x) (&masterConfig.servoProfile) -#define customMotorMixer(i) (&masterConfig.customMotorMixer[i]) -#define customServoMixers(i) (&masterConfig.customServoMixer[i]) -#define displayPortProfileMsp(x) (&masterConfig.displayPortProfileMsp) -#define displayPortProfileMax7456(x) (&masterConfig.displayPortProfileMax7456) -#define displayPortProfileOled(x) (&masterConfig.displayPortProfileOled) -#define vtxConfig(x) (&masterConfig.vtxConfig) -#define beeperConfig(x) (&masterConfig.beeperConfig) -#define transponderConfig(x) (&masterConfig.transponderConfig) - -#define featureConfigMutable(x) (&masterConfig.featureConfig) -#define systemConfigMutable(x) (&masterConfig.systemConfig) -#define motorConfigMutable(x) (&masterConfig.motorConfig) -#define flight3DConfigMutable(x) (&masterConfig.flight3DConfig) -#define servoConfigMutable(x) (&masterConfig.servoConfig) -#define servoMixerConfigMutable(x) (&masterConfig.servoMixerConfig) -#define gimbalConfigMutable(x) (&masterConfig.gimbalConfig) -#define boardAlignmentMutable(x) (&masterConfig.boardAlignment) -#define imuConfigMutable(x) (&masterConfig.imuConfig) -#define gyroConfigMutable(x) (&masterConfig.gyroConfig) -#define compassConfigMutable(x) (&masterConfig.compassConfig) -#define accelerometerConfigMutable(x) (&masterConfig.accelerometerConfig) -#define barometerConfigMutable(x) (&masterConfig.barometerConfig) -#define throttleCorrectionConfigMutable(x) (&masterConfig.throttleCorrectionConfig) -#define batteryConfigMutable(x) (&masterConfig.batteryConfig) -#define rcControlsConfigMutable(x) (&masterConfig.rcControlsConfig) -#define navigationConfigMutable(x) (&masterConfig.navigationConfig) -#define gpsConfigMutable(x) (&masterConfig.gpsConfig) -#define rxConfigMutable(x) (&masterConfig.rxConfig) -#define armingConfigMutable(x) (&masterConfig.armingConfig) -#define mixerConfigMutable(x) (&masterConfig.mixerConfig) -#define airplaneConfigMutable(x) (&masterConfig.airplaneConfig) -#define failsafeConfigMutable(x) (&masterConfig.failsafeConfig) -#define serialConfigMutable(x) (&masterConfig.serialConfig) -#define telemetryConfigMutable(x) (&masterConfig.telemetryConfig) -#define ibusTelemetryConfigMutable(x) (&masterConfig.telemetryConfig) -#define ppmConfigMutable(x) (&masterConfig.ppmConfig) -#define pwmConfigMutable(x) (&masterConfig.pwmConfig) -#define adcConfigMutable(x) (&masterConfig.adcConfig) -#define beeperDevConfigMutable(x) (&masterConfig.beeperDevConfig) -#define sonarConfigMutable(x) (&masterConfig.sonarConfig) -#define ledStripConfigMutable(x) (&masterConfig.ledStripConfig) -#define statusLedConfigMutable(x) (&masterConfig.statusLedConfig) -#define osdConfigMutable(x) (&masterConfig.osdConfig) -#define vcdProfileMutable(x) (&masterConfig.vcdProfile) -#define sdcardConfigMutable(x) (&masterConfig.sdcardConfig) -#define blackboxConfigMutable(x) (&masterConfig.blackboxConfig) -#define flashConfigMutable(x) (&masterConfig.flashConfig) -#define pidConfigMutable(x) (&masterConfig.pidConfig) -#define adjustmentProfileMutable(x) (&masterConfig.adjustmentProfile) -#define modeActivationProfileMutable(x) (&masterConfig.modeActivationProfile) -#define servoProfileMutable(x) (&masterConfig.servoProfile) -#define customMotorMixerMutable(i) (&masterConfig.customMotorMixer[i]) -#define customServoMixersMutable(i) (&masterConfig.customServoMixer[i]) -#define displayPortProfileMspMutable(x) (&masterConfig.displayPortProfileMsp) -#define displayPortProfileMax7456Mutable(x) (&masterConfig.displayPortProfileMax7456) -#define displayPortProfileOledMutable(x) (&masterConfig.displayPortProfileOled) -#define vtxConfigMutable(x) (&masterConfig.vtxConfig) -#define beeperConfigMutable(x) (&masterConfig.beeperConfig) -#define transponderConfigMutable(x) (&masterConfig.transponderConfig) - -#define servoParams(i) (&servoProfile()->servoConf[i]) -#define adjustmentRanges(i) (&adjustmentProfile()->adjustmentRanges[i]) -#define rxFailsafeChannelConfigs(i) (&masterConfig.rxConfig.failsafe_channel_configurations[i]) -#define modeActivationConditions(i) (&masterConfig.modeActivationProfile.modeActivationConditions[i]) -#define controlRateProfiles(i) (&masterConfig.controlRateProfile[i]) -#define pidProfiles(i) (&masterConfig.profile[i].pidProfile) - -#define servoParamsMutable(i) (&servoProfile()->servoConf[i]) -#define adjustmentRangesMutable(i) (&masterConfig.adjustmentProfile.adjustmentRanges[i]) -#define rxFailsafeChannelConfigsMutable(i) (&masterConfig.rxConfig.>failsafe_channel_configurations[i]) -#define modeActivationConditionsMutable(i) (&masterConfig.modeActivationProfile.modeActivationConditions[i]) -#define controlRateProfilesMutable(i) (&masterConfig.controlRateProfile[i]) -#define pidProfilesMutable(i) (&masterConfig.profile[i].pidProfile) - -// System-wide -typedef struct master_s { - uint8_t version; - uint16_t size; - uint8_t magic_be; // magic number, should be 0xBE - - featureConfig_t featureConfig; - - systemConfig_t systemConfig; - - // motor/esc/servo related stuff - motorMixer_t customMotorMixer[MAX_SUPPORTED_MOTORS]; - motorConfig_t motorConfig; - flight3DConfig_t flight3DConfig; - -#ifdef USE_SERVOS - servoConfig_t servoConfig; - servoMixer_t customServoMixer[MAX_SERVO_RULES]; - // Servo-related stuff - servoProfile_t servoProfile; - // gimbal-related configuration - gimbalConfig_t gimbalConfig; -#endif - - boardAlignment_t boardAlignment; - - imuConfig_t imuConfig; - - pidConfig_t pidConfig; - - gyroConfig_t gyroConfig; - compassConfig_t compassConfig; - - accelerometerConfig_t accelerometerConfig; - - barometerConfig_t barometerConfig; - - throttleCorrectionConfig_t throttleCorrectionConfig; - - batteryConfig_t batteryConfig; - - // Radio/ESC-related configuration - rcControlsConfig_t rcControlsConfig; - -#ifdef GPS - navigationConfig_t navigationConfig; - gpsConfig_t gpsConfig; -#endif - - rxConfig_t rxConfig; - - armingConfig_t armingConfig; - - // mixer-related configuration - mixerConfig_t mixerConfig; - airplaneConfig_t airplaneConfig; - - failsafeConfig_t failsafeConfig; - serialPinConfig_t serialPinConfig; - serialConfig_t serialConfig; - telemetryConfig_t telemetryConfig; - - statusLedConfig_t statusLedConfig; - -#ifdef USE_PPM - ppmConfig_t ppmConfig; -#endif - -#ifdef USE_PWM - pwmConfig_t pwmConfig; -#endif - -#ifdef USE_ADC - adcConfig_t adcConfig; -#endif - -#ifdef BEEPER - beeperDevConfig_t beeperDevConfig; -#endif - -#ifdef SONAR - sonarConfig_t sonarConfig; -#endif - -#ifdef LED_STRIP - ledStripConfig_t ledStripConfig; -#endif - -#ifdef TRANSPONDER - transponderConfig_t transponderConfig; -#endif - -#ifdef OSD - osdConfig_t osdConfig; -#endif - -#ifdef USE_MAX7456 - vcdProfile_t vcdProfile; -#endif - -#ifdef USE_MSP_DISPLAYPORT - displayPortProfile_t displayPortProfileMsp; -#endif -#ifdef USE_MAX7456 - displayPortProfile_t displayPortProfileMax7456; -# endif - -#ifdef USE_SDCARD - sdcardConfig_t sdcardConfig; -#endif - - profile_t profile[MAX_PROFILE_COUNT]; - controlRateConfig_t controlRateProfile[CONTROL_RATE_PROFILE_COUNT]; - - modeActivationProfile_t modeActivationProfile; - adjustmentProfile_t adjustmentProfile; -#if defined(USE_RTC6705) || defined(VTX) - vtxConfig_t vtxConfig; -#endif -#ifdef BLACKBOX - blackboxConfig_t blackboxConfig; -#endif - -#ifdef USE_FLASHFS - flashConfig_t flashConfig; -#endif - - beeperConfig_t beeperConfig; - - uint8_t chk; // XOR checksum - /* - do not add properties after the MAGIC_EF and CHK - as it is assumed to exist at length-2 and length-1 - */ -} master_t; - -extern master_t masterConfig; - -void createDefaultConfig(master_t *config); -#endif // USE_PARAMETER_GROUPS diff --git a/src/main/config/parameter_group.h b/src/main/config/parameter_group.h index 75f5fb8e89..f08a83e8b9 100644 --- a/src/main/config/parameter_group.h +++ b/src/main/config/parameter_group.h @@ -100,7 +100,6 @@ extern const uint8_t __pg_resetdata_end[]; } while(0) \ /**/ -#ifdef USE_PARAMETER_GROUPS // Declare system config #define PG_DECLARE(_type, _name) \ extern _type _name ## _System; \ @@ -126,21 +125,7 @@ extern const uint8_t __pg_resetdata_end[]; struct _dummy \ /**/ -#else -#define PG_DECLARE(_type, _name) \ - extern _type _name ## _System - -#define PG_DECLARE_ARRAY(_type, _size, _name) \ - extern _type _name ## _SystemArray[_size] - -// Declare profile config -#define PG_DECLARE_PROFILE(_type, _name) \ - extern _type *_name ## _ProfileCurrent - -#endif // USE_PARAMETER_GROUPS - -#ifdef USE_PARAMETER_GROUPS // Register system config #define PG_REGISTER_I(_type, _name, _pgn, _version, _reset) \ _type _name ## _System; \ @@ -154,10 +139,6 @@ extern const uint8_t __pg_resetdata_end[]; _reset, \ } \ /**/ -#else -#define PG_REGISTER_I(_type, _name, _pgn, _version, _reset) \ - _type _name ## _System -#endif #define PG_REGISTER(_type, _name, _pgn, _version) \ PG_REGISTER_I(_type, _name, _pgn, _version, .reset = {.ptr = 0}) \ @@ -173,7 +154,6 @@ extern const uint8_t __pg_resetdata_end[]; PG_REGISTER_I(_type, _name, _pgn, _version, .reset = {.ptr = (void*)&pgResetTemplate_ ## _name}) \ /**/ -#ifdef USE_PARAMETER_GROUPS // Register system config array #define PG_REGISTER_ARRAY_I(_type, _size, _name, _pgn, _version, _reset) \ _type _name ## _SystemArray[_size]; \ @@ -186,10 +166,6 @@ extern const uint8_t __pg_resetdata_end[]; _reset, \ } \ /**/ -#else -#define PG_REGISTER_ARRAY_I(_type, _size, _name, _pgn, _version, _reset) \ - _type _name ## _SystemArray[_size] -#endif #define PG_REGISTER_ARRAY(_type, _size, _name, _pgn, _version) \ PG_REGISTER_ARRAY_I(_type, _size, _name, _pgn, _version, .reset = {.ptr = 0}) \ @@ -216,7 +192,6 @@ extern const uint8_t __pg_resetdata_end[]; _type *_name ## _ProfileCurrent; #endif -#ifdef USE_PARAMETER_GROUPS // register profile config #define PG_REGISTER_PROFILE_I(_type, _name, _pgn, _version, _reset) \ STATIC_UNIT_TESTED _type _name ## _Storage[MAX_PROFILE_COUNT]; \ @@ -230,10 +205,6 @@ extern const uint8_t __pg_resetdata_end[]; _reset, \ } \ /**/ -#else -#define PG_REGISTER_PROFILE_I(_type, _name, _pgn, _version, _reset) \ - STATIC_UNIT_TESTED _type _name ## _Storage[MAX_PROFILE_COUNT] -#endif #define PG_REGISTER_PROFILE(_type, _name, _pgn, _version) \ PG_REGISTER_PROFILE_I(_type, _name, _pgn, _version, .reset = {.ptr = 0}) \ diff --git a/src/main/config/parameter_group_ids.h b/src/main/config/parameter_group_ids.h index 5834504bfa..47eb1b7f2a 100644 --- a/src/main/config/parameter_group_ids.h +++ b/src/main/config/parameter_group_ids.h @@ -15,10 +15,6 @@ * along with Cleanflight. If not, see . */ -#ifndef USE_PARAMETER_GROUPS -#include "config/config_master.h" -#endif - // FC configuration #define PG_FAILSAFE_CONFIG 1 // struct OK #define PG_BOARD_ALIGNMENT 2 // struct OK diff --git a/src/main/drivers/serial_softserial.c b/src/main/drivers/serial_softserial.c index 3913cac703..cec09aec25 100644 --- a/src/main/drivers/serial_softserial.c +++ b/src/main/drivers/serial_softserial.c @@ -34,8 +34,6 @@ #include "common/utils.h" -#include "config/config_master.h" - #include "nvic.h" #include "system.h" #include "io.h" @@ -44,6 +42,8 @@ #include "serial.h" #include "serial_softserial.h" +#include "fc/config.h" //!!TODO remove this dependency + #define RX_TOTAL_BITS 10 #define TX_TOTAL_BITS 10 diff --git a/src/main/fc/cli.c b/src/main/fc/cli.c index 1a25c9f8a4..a04dca3e76 100755 --- a/src/main/fc/cli.c +++ b/src/main/fc/cli.c @@ -48,7 +48,6 @@ extern uint8_t __config_end; #include "common/typeconversion.h" #include "common/utils.h" -#include "config/config_master.h" #include "config/config_eeprom.h" #include "config/config_profile.h" #include "config/feature.h" @@ -77,10 +76,12 @@ extern uint8_t __config_end; #include "fc/cli.h" #include "fc/config.h" #include "fc/controlrate_profile.h" +#include "fc/fc_core.h" #include "fc/rc_adjustments.h" #include "fc/rc_controls.h" #include "fc/runtime_config.h" +#include "flight/altitudehold.h" #include "flight/failsafe.h" #include "flight/imu.h" #include "flight/mixer.h" diff --git a/src/main/fc/config.c b/src/main/fc/config.c index 51dd00128d..b95a69b52a 100755 --- a/src/main/fc/config.c +++ b/src/main/fc/config.c @@ -35,7 +35,6 @@ #include "common/maths.h" #include "config/config_eeprom.h" -#include "config/config_master.h" #include "config/config_profile.h" #include "config/feature.h" #include "config/parameter_group.h" @@ -44,6 +43,7 @@ #include "drivers/accgyro.h" #include "drivers/compass.h" #include "drivers/io.h" +#include "drivers/light_led.h" #include "drivers/light_ws2811strip.h" #include "drivers/max7456.h" #include "drivers/pwm_esc_detect.h" @@ -53,14 +53,18 @@ #include "drivers/sdcard.h" #include "drivers/sensor.h" #include "drivers/serial.h" +#include "drivers/sonar_hcsr04.h" #include "drivers/sound_beeper.h" #include "drivers/system.h" #include "drivers/timer.h" #include "drivers/vcd.h" #include "fc/config.h" -#include "fc/rc_controls.h" +#include "fc/controlrate_profile.h" +#include "fc/fc_core.h" #include "fc/fc_rc.h" +#include "fc/rc_adjustments.h" +#include "fc/rc_controls.h" #include "fc/runtime_config.h" #include "flight/altitudehold.h" @@ -94,9 +98,6 @@ #include "telemetry/telemetry.h" -#ifndef USE_PARAMETER_GROUPS -master_t masterConfig; // master config struct with data independent from profiles -#endif pidProfile_t *currentPidProfile; #ifndef DEFAULT_FEATURES @@ -1272,7 +1273,7 @@ void validateAndFixConfig(void) } #else if (!isSerialConfigValid(serialConfig())) { - pgResetFn_serialPinConfig(serialConfigMutable()); + pgResetFn_serialConfig(serialConfigMutable()); } #endif diff --git a/src/main/fc/config.h b/src/main/fc/config.h index 0f120fee11..254640b9b3 100644 --- a/src/main/fc/config.h +++ b/src/main/fc/config.h @@ -117,11 +117,5 @@ bool canSoftwareSerialBeUsed(void); uint16_t getCurrentMinthrottle(void); void resetConfigs(void); -#ifdef USE_PARAMETER_GROUPS void targetConfiguration(void); void targetValidateConfiguration(void); -#else -struct master_s; -void targetConfiguration(struct master_s *config); -void targetValidateConfiguration(struct master_s *config); -#endif diff --git a/src/main/fc/fc_msp.c b/src/main/fc/fc_msp.c index e3bf9c1d97..99799606c5 100755 --- a/src/main/fc/fc_msp.c +++ b/src/main/fc/fc_msp.c @@ -33,7 +33,6 @@ #include "common/maths.h" #include "common/streambuf.h" -#include "config/config_master.h" #include "config/config_eeprom.h" #include "config/config_profile.h" #include "config/feature.h" @@ -56,6 +55,7 @@ #include "drivers/vtx_soft_spi_rtc6705.h" #include "fc/config.h" +#include "fc/controlrate_profile.h" #include "fc/fc_core.h" #include "fc/fc_msp.h" #include "fc/fc_rc.h" diff --git a/src/main/flight/pid.c b/src/main/flight/pid.c index e5a612d3a1..302e9ec8b9 100644 --- a/src/main/flight/pid.c +++ b/src/main/flight/pid.c @@ -76,7 +76,6 @@ PG_RESET_TEMPLATE(pidConfig_t, pidConfig, PG_REGISTER_ARRAY_WITH_RESET_FN(pidProfile_t, MAX_PROFILE_COUNT, pidProfiles, PG_PID_PROFILE, 0); -#ifdef USE_PARAMETER_GROUPS void resetPidProfile(pidProfile_t *pidProfile) { RESET_CONFIG(const pidProfile_t, pidProfile, @@ -136,7 +135,6 @@ void pgResetFn_pidProfiles(pidProfile_t *pidProfiles) resetPidProfile(&pidProfiles[i]); } } -#endif void pidSetTargetLooptime(uint32_t pidLooptime) { diff --git a/src/main/io/osd.c b/src/main/io/osd.c index ed73538498..ac0b483d5e 100755 --- a/src/main/io/osd.c +++ b/src/main/io/osd.c @@ -472,11 +472,7 @@ void osdDrawElements(void) #endif // GPS } -#ifdef USE_PARAMETER_GROUPS void pgResetFn_osdConfig(osdConfig_t *osdProfile) -#else -void osdResetConfig(osdConfig_t *osdProfile) -#endif { osdProfile->item_pos[OSD_RSSI_VALUE] = OSD_POS(22, 0); osdProfile->item_pos[OSD_MAIN_BATT_VOLTAGE] = OSD_POS(12, 0) | VISIBLE_FLAG; diff --git a/src/main/io/serial.h b/src/main/io/serial.h index 300d03eb39..02ae9218c0 100644 --- a/src/main/io/serial.h +++ b/src/main/io/serial.h @@ -137,6 +137,7 @@ 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); +void pgResetFn_serialConfig(serialConfig_t *serialConfig); //!!TODO remove need for this serialPortUsage_t *findSerialPortUsageByIdentifier(serialPortIdentifier_e identifier); int findSerialPortIndexByIdentifier(serialPortIdentifier_e identifier); // diff --git a/src/main/rx/msp.h b/src/main/rx/msp.h index 69c2839282..dc3f5a7913 100644 --- a/src/main/rx/msp.h +++ b/src/main/rx/msp.h @@ -17,5 +17,7 @@ #pragma once -void rxMspInit(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig); +struct rxConfig_s; +struct rxRuntimeConfig_s; +void rxMspInit(const struct rxConfig_s *rxConfig, struct rxRuntimeConfig_s *rxRuntimeConfig); void rxMspFrameReceive(uint16_t *frame, int channelCount); diff --git a/src/main/sensors/acceleration.c b/src/main/sensors/acceleration.c index 57336843b0..d35c681bee 100644 --- a/src/main/sensors/acceleration.c +++ b/src/main/sensors/acceleration.c @@ -86,15 +86,10 @@ PG_REGISTER_WITH_RESET_FN(accelerometerConfig_t, accelerometerConfig, PG_ACCELER void resetRollAndPitchTrims(rollAndPitchTrims_t *rollAndPitchTrims) { -#ifdef USE_PARAMETER_GROUPS RESET_CONFIG_2(rollAndPitchTrims_t, rollAndPitchTrims, .values.roll = 0, .values.pitch = 0, ); -#else - rollAndPitchTrims->values.roll = 0; - rollAndPitchTrims->values.pitch = 0; -#endif } void accResetRollAndPitchTrims(void) @@ -114,7 +109,6 @@ void accResetFlightDynamicsTrims(void) resetFlightDynamicsTrims(&accelerometerConfigMutable()->accZero); } -#ifdef USE_PARAMETER_GROUPS void pgResetFn_accelerometerConfig(accelerometerConfig_t *instance) { RESET_CONFIG_2(accelerometerConfig_t, instance, @@ -125,7 +119,6 @@ void pgResetFn_accelerometerConfig(accelerometerConfig_t *instance) resetRollAndPitchTrims(&instance->accelerometerTrims); resetFlightDynamicsTrims(&instance->accZero); } -#endif bool accDetect(accDev_t *dev, accelerationSensor_e accHardwareToUse) { diff --git a/src/main/target/BLUEJAYF4/initialisation.c b/src/main/target/BLUEJAYF4/initialisation.c index 5226d475e5..9196d3ff8c 100644 --- a/src/main/target/BLUEJAYF4/initialisation.c +++ b/src/main/target/BLUEJAYF4/initialisation.c @@ -19,12 +19,20 @@ #include #include "platform.h" + +#include "config/feature.h" + #include "drivers/bus_i2c.h" #include "drivers/bus_spi.h" -#include "hardware_revision.h" -#include "config/config_master.h" #include "drivers/io.h" -#include "config/feature.h" + +#include "fc/config.h" + +#include "io/serial.h" + +#include "telemetry/telemetry.h" + +#include "hardware_revision.h" void targetPreInit(void) { diff --git a/src/main/target/COLIBRI_RACE/i2c_bst.c b/src/main/target/COLIBRI_RACE/i2c_bst.c index bc4695c2c0..87c180af9f 100644 --- a/src/main/target/COLIBRI_RACE/i2c_bst.c +++ b/src/main/target/COLIBRI_RACE/i2c_bst.c @@ -29,7 +29,9 @@ #include "drivers/rx_pwm.h" #include "fc/config.h" +#include "fc/controlrate_profile.h" #include "fc/fc_core.h" +#include "fc/rc_adjustments.h" #include "fc/rc_controls.h" #include "fc/runtime_config.h" @@ -58,16 +60,16 @@ #include "telemetry/telemetry.h" -#include "flight/mixer.h" -#include "flight/pid.h" -#include "flight/imu.h" -#include "flight/failsafe.h" -#include "flight/navigation.h" #include "flight/altitudehold.h" +#include "flight/failsafe.h" +#include "flight/imu.h" +#include "flight/mixer.h" +#include "flight/navigation.h" +#include "flight/pid.h" +#include "flight/servos.h" #include "config/config_eeprom.h" #include "config/config_profile.h" -#include "config/config_master.h" #include "config/feature.h" #include "bus_bst.h" diff --git a/src/main/target/RACEBASE/config.c b/src/main/target/RACEBASE/config.c index 663e8cc01a..6da7077aed 100755 --- a/src/main/target/RACEBASE/config.c +++ b/src/main/target/RACEBASE/config.c @@ -26,8 +26,6 @@ #include "rx/rx.h" -#include "config/config_master.h" - void targetConfiguration(void) { rxConfigMutable()->sbus_inversion = 0;