Merge pull request #2793 from DieHertz/clean-non-pg-remains
Cleaned USE_PARAMETER_GROUPS remainders
This commit is contained in:
commit
806742262b
|
@ -1102,8 +1102,6 @@ static void printValuePointer(const clivalue_t *var, const void *valuePointer, u
|
|||
}
|
||||
}
|
||||
|
||||
#ifdef USE_PARAMETER_GROUPS
|
||||
|
||||
static bool valuePtrEqualsDefault(uint8_t type, const void *ptr, const void *ptrDefault)
|
||||
{
|
||||
bool result = false;
|
||||
|
@ -1443,94 +1441,6 @@ static void dumpAllValues(uint16_t valueSection, uint8_t dumpMask)
|
|||
}
|
||||
}
|
||||
|
||||
#else
|
||||
|
||||
void *getValuePointer(const clivalue_t *value)
|
||||
{
|
||||
uint8_t *ptr = value->ptr;
|
||||
|
||||
if ((value->type & VALUE_SECTION_MASK) == PROFILE_VALUE) {
|
||||
ptr += sizeof(pidProfile_t) * getCurrentPidProfileIndex();
|
||||
} else if ((value->type & VALUE_SECTION_MASK) == PROFILE_RATE_VALUE) {
|
||||
ptr += sizeof(controlRateConfig_t) * getCurrentControlRateProfileIndex();
|
||||
}
|
||||
|
||||
return ptr;
|
||||
}
|
||||
|
||||
static void *getDefaultPointer(void *valuePointer, const master_t *defaultConfig)
|
||||
{
|
||||
return ((uint8_t *)valuePointer) - (uint32_t)&masterConfig + (uint32_t)defaultConfig;
|
||||
}
|
||||
|
||||
static bool valueEqualsDefault(const clivalue_t *value, const master_t *defaultConfig)
|
||||
{
|
||||
void *ptr = getValuePointer(value);
|
||||
|
||||
void *ptrDefault = getDefaultPointer(ptr, defaultConfig);
|
||||
|
||||
bool result = false;
|
||||
switch (value->type & VALUE_TYPE_MASK) {
|
||||
case VAR_UINT8:
|
||||
result = *(uint8_t *)ptr == *(uint8_t *)ptrDefault;
|
||||
break;
|
||||
|
||||
case VAR_INT8:
|
||||
result = *(int8_t *)ptr == *(int8_t *)ptrDefault;
|
||||
break;
|
||||
|
||||
case VAR_UINT16:
|
||||
result = *(uint16_t *)ptr == *(uint16_t *)ptrDefault;
|
||||
break;
|
||||
|
||||
case VAR_INT16:
|
||||
result = *(int16_t *)ptr == *(int16_t *)ptrDefault;
|
||||
break;
|
||||
|
||||
/* not currently used
|
||||
case VAR_UINT32:
|
||||
result = *(uint32_t *)ptr == *(uint32_t *)ptrDefault;
|
||||
break; */
|
||||
|
||||
case VAR_FLOAT:
|
||||
result = *(float *)ptr == *(float *)ptrDefault;
|
||||
break;
|
||||
}
|
||||
return result;
|
||||
}
|
||||
|
||||
static void cliPrintVarDefault(const clivalue_t *var, uint32_t full, const master_t *defaultConfig)
|
||||
{
|
||||
void *ptr = getValuePointer(var);
|
||||
|
||||
void *defaultPtr = getDefaultPointer(ptr, defaultConfig);
|
||||
|
||||
printValuePointer(var, defaultPtr, full);
|
||||
}
|
||||
|
||||
static void dumpValues(uint16_t valueSection, uint8_t dumpMask, const master_t *defaultConfig)
|
||||
{
|
||||
const clivalue_t *value;
|
||||
for (uint32_t i = 0; i < ARRAYLEN(valueTable); i++) {
|
||||
value = &valueTable[i];
|
||||
|
||||
if ((value->type & VALUE_SECTION_MASK) != valueSection) {
|
||||
continue;
|
||||
}
|
||||
|
||||
const char *format = "set %s = ";
|
||||
if (cliDefaultPrintf(dumpMask, valueEqualsDefault(value, defaultConfig), format, valueTable[i].name)) {
|
||||
cliPrintVarDefault(value, 0, defaultConfig);
|
||||
cliPrint("\r\n");
|
||||
}
|
||||
if (cliDumpPrintf(dumpMask, valueEqualsDefault(value, defaultConfig), format, valueTable[i].name)) {
|
||||
cliPrintVar(value, 0);
|
||||
cliPrint("\r\n");
|
||||
}
|
||||
}
|
||||
}
|
||||
#endif // USE_PARAMETER_GROUPS
|
||||
|
||||
static void cliPrintVar(const clivalue_t *var, uint32_t full)
|
||||
{
|
||||
const void *ptr = getValuePointer(var);
|
||||
|
@ -2644,11 +2554,7 @@ static void cliServoMix(char *cmdline)
|
|||
printServoMix(DUMP_MASTER, customServoMixers(0), NULL);
|
||||
} else if (strncasecmp(cmdline, "reset", 5) == 0) {
|
||||
// erase custom mixer
|
||||
#ifdef USE_PARAMETER_GROUPS
|
||||
memset(customServoMixers_array(), 0, sizeof(*customServoMixers_array()));
|
||||
#else
|
||||
memset(masterConfig.customServoMixer, 0, sizeof(masterConfig.customServoMixer));
|
||||
#endif
|
||||
for (uint32_t i = 0; i < MAX_SUPPORTED_SERVOS; i++) {
|
||||
servoParamsMutable(i)->reversedSources = 0;
|
||||
}
|
||||
|
@ -3577,7 +3483,6 @@ static void cliRateProfile(char *cmdline)
|
|||
}
|
||||
}
|
||||
|
||||
#ifdef USE_PARAMETER_GROUPS
|
||||
static void cliDumpPidProfile(uint8_t pidProfileIndex, uint8_t dumpMask)
|
||||
{
|
||||
if (pidProfileIndex >= MAX_PROFILE_COUNT) {
|
||||
|
@ -3603,33 +3508,6 @@ static void cliDumpRateProfile(uint8_t rateProfileIndex, uint8_t dumpMask)
|
|||
cliPrint("\r\n");
|
||||
dumpAllValues(PROFILE_RATE_VALUE, dumpMask);
|
||||
}
|
||||
#else
|
||||
static void cliDumpPidProfile(uint8_t pidProfileIndex, uint8_t dumpMask, const master_t *defaultConfig)
|
||||
{
|
||||
if (pidProfileIndex >= MAX_PROFILE_COUNT) {
|
||||
// Faulty values
|
||||
return;
|
||||
}
|
||||
changePidProfile(pidProfileIndex);
|
||||
cliPrintHashLine("profile");
|
||||
cliProfile("");
|
||||
cliPrint("\r\n");
|
||||
dumpValues(PROFILE_VALUE, dumpMask, defaultConfig);
|
||||
}
|
||||
|
||||
static void cliDumpRateProfile(uint8_t rateProfileIndex, uint8_t dumpMask, const master_t *defaultConfig)
|
||||
{
|
||||
if (rateProfileIndex >= CONTROL_RATE_PROFILE_COUNT) {
|
||||
// Faulty values
|
||||
return;
|
||||
}
|
||||
changeControlRateProfile(rateProfileIndex);
|
||||
cliPrintHashLine("rateprofile");
|
||||
cliRateProfile("");
|
||||
cliPrint("\r\n");
|
||||
dumpValues(PROFILE_RATE_VALUE, dumpMask, defaultConfig);
|
||||
}
|
||||
#endif
|
||||
|
||||
static void cliSave(char *cmdline)
|
||||
{
|
||||
|
@ -3810,11 +3688,7 @@ static void cliStatus(char *cmdline)
|
|||
#endif
|
||||
cliPrintf("Stack size: %d, Stack address: 0x%x\r\n", stackTotalSize(), stackHighMem());
|
||||
|
||||
#ifdef USE_PARAMETER_GROUPS
|
||||
cliPrintf("I2C Errors: %d, config size: %d, max available config: %d\r\n", i2cErrorCounter, getEEPROMConfigSize(), &__config_end - &__config_start);
|
||||
#else
|
||||
cliPrintf("I2C Errors: %d, config size: %d\r\n", i2cErrorCounter, sizeof(master_t));
|
||||
#endif
|
||||
|
||||
const int gyroRate = getTaskDeltaTime(TASK_GYROPID) == 0 ? 0 : (int)(1000000.0f / ((float)getTaskDeltaTime(TASK_GYROPID)));
|
||||
const int rxRate = getTaskDeltaTime(TASK_RX) == 0 ? 0 : (int)(1000000.0f / ((float)getTaskDeltaTime(TASK_RX)));
|
||||
|
@ -4148,7 +4022,6 @@ static void cliResource(char *cmdline)
|
|||
}
|
||||
#endif /* USE_RESOURCE_MGMT */
|
||||
|
||||
#ifdef USE_PARAMETER_GROUPS
|
||||
static void backupConfigs(void)
|
||||
{
|
||||
// make copies of configs to do differencing
|
||||
|
@ -4187,7 +4060,6 @@ static void restoreConfigs(void)
|
|||
}
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
static void printConfig(char *cmdline, bool doDiff)
|
||||
{
|
||||
|
@ -4337,10 +4209,8 @@ static void printConfig(char *cmdline, bool doDiff)
|
|||
if (dumpMask & DUMP_RATES) {
|
||||
cliDumpRateProfile(systemConfigCopy.activeRateProfile, dumpMask);
|
||||
}
|
||||
#ifdef USE_PARAMETER_GROUPS
|
||||
// restore configs from copies
|
||||
restoreConfigs();
|
||||
#endif
|
||||
}
|
||||
|
||||
static void cliDump(char *cmdline)
|
||||
|
|
|
@ -471,327 +471,8 @@ uint16_t getCurrentMinthrottle(void)
|
|||
return motorConfig()->minthrottle;
|
||||
}
|
||||
|
||||
#ifndef USE_PARAMETER_GROUPS
|
||||
void createDefaultConfig(master_t *config)
|
||||
{
|
||||
// Clear all configuration
|
||||
memset(config, 0, sizeof(master_t));
|
||||
|
||||
uint32_t *featuresPtr = &config->featureConfig.enabledFeatures;
|
||||
|
||||
intFeatureClearAll(featuresPtr);
|
||||
intFeatureSet(DEFAULT_RX_FEATURE | FEATURE_FAILSAFE , featuresPtr);
|
||||
|
||||
#ifdef DEFAULT_FEATURES
|
||||
intFeatureSet(DEFAULT_FEATURES, featuresPtr);
|
||||
#endif
|
||||
|
||||
#ifndef USE_PARAMETER_GROUPS
|
||||
#ifdef USE_MSP_DISPLAYPORT
|
||||
resetDisplayPortProfile(&config->displayPortProfileMsp);
|
||||
#endif
|
||||
#ifdef USE_MAX7456
|
||||
resetDisplayPortProfile(&config->displayPortProfileMax7456);
|
||||
#endif
|
||||
|
||||
#ifdef USE_MAX7456
|
||||
resetMax7456Config(&config->vcdProfile);
|
||||
#endif
|
||||
|
||||
#ifdef OSD
|
||||
osdResetConfig(&config->osdConfig);
|
||||
#endif
|
||||
#endif // USE_PARAMETER_GROUPS
|
||||
|
||||
config->version = EEPROM_CONF_VERSION;
|
||||
|
||||
// global settings
|
||||
#ifndef USE_PARAMETER_GROUPS
|
||||
config->systemConfig.pidProfileIndex = 0; // default profile
|
||||
config->systemConfig.debug_mode = DEBUG_MODE;
|
||||
config->systemConfig.task_statistics = true;
|
||||
#endif
|
||||
|
||||
|
||||
#ifndef USE_PARAMETER_GROUPS
|
||||
config->imuConfig.dcm_kp = 2500; // 1.0 * 10000
|
||||
config->imuConfig.dcm_ki = 0; // 0.003 * 10000
|
||||
config->imuConfig.small_angle = 25;
|
||||
config->imuConfig.accDeadband.xy = 40;
|
||||
config->imuConfig.accDeadband.z = 40;
|
||||
config->imuConfig.acc_unarmedcal = 1;
|
||||
#endif
|
||||
#ifndef USE_PARAMETER_GROUPS
|
||||
config->gyroConfig.gyro_lpf = GYRO_LPF_256HZ; // 256HZ default
|
||||
#ifdef STM32F10X
|
||||
config->gyroConfig.gyro_sync_denom = 8;
|
||||
config->pidConfig.pid_process_denom = 1;
|
||||
#elif defined(USE_GYRO_SPI_MPU6000) || defined(USE_GYRO_SPI_MPU6500) || defined(USE_GYRO_SPI_ICM20689)
|
||||
config->gyroConfig.gyro_sync_denom = 1;
|
||||
config->pidConfig.pid_process_denom = 4;
|
||||
#else
|
||||
config->gyroConfig.gyro_sync_denom = 4;
|
||||
config->pidConfig.pid_process_denom = 2;
|
||||
#endif
|
||||
config->gyroConfig.gyro_soft_lpf_type = FILTER_PT1;
|
||||
config->gyroConfig.gyro_soft_lpf_hz = 90;
|
||||
config->gyroConfig.gyro_soft_notch_hz_1 = 400;
|
||||
config->gyroConfig.gyro_soft_notch_cutoff_1 = 300;
|
||||
config->gyroConfig.gyro_soft_notch_hz_2 = 200;
|
||||
config->gyroConfig.gyro_soft_notch_cutoff_2 = 100;
|
||||
config->gyroConfig.gyro_align = ALIGN_DEFAULT;
|
||||
config->gyroConfig.gyroMovementCalibrationThreshold = 48;
|
||||
#endif
|
||||
|
||||
#ifndef USE_PARAMETER_GROUPS
|
||||
resetCompassConfig(&config->compassConfig);
|
||||
#endif
|
||||
|
||||
#ifndef USE_PARAMETER_GROUPS
|
||||
resetAccelerometerTrims(&config->accelerometerConfig.accZero);
|
||||
config->accelerometerConfig.acc_align = ALIGN_DEFAULT;
|
||||
config->accelerometerConfig.acc_hardware = ACC_DEFAULT; // default/autodetect
|
||||
resetRollAndPitchTrims(&config->accelerometerConfig.accelerometerTrims);
|
||||
config->accelerometerConfig.acc_lpf_hz = 10.0f;
|
||||
#endif
|
||||
#ifndef USE_PARAMETER_GROUPS
|
||||
config->boardAlignment.rollDegrees = 0;
|
||||
config->boardAlignment.pitchDegrees = 0;
|
||||
config->boardAlignment.yawDegrees = 0;
|
||||
#endif
|
||||
config->rcControlsConfig.yaw_control_reversed = false;
|
||||
|
||||
// xxx_hardware: 0:default/autodetect, 1: disable
|
||||
config->compassConfig.mag_hardware = 1;
|
||||
|
||||
config->barometerConfig.baro_hardware = 1;
|
||||
|
||||
#ifndef USE_PARAMETER_GROUPS
|
||||
resetBatteryConfig(&config->batteryConfig);
|
||||
|
||||
#if defined(USE_PWM) || defined(USE_PPM)
|
||||
resetPpmConfig(&config->ppmConfig);
|
||||
resetPwmConfig(&config->pwmConfig);
|
||||
#endif
|
||||
#ifdef USE_PWM
|
||||
config->pwmConfig.inputFilteringMode = INPUT_FILTERING_DISABLED;
|
||||
#endif
|
||||
|
||||
#ifdef TELEMETRY
|
||||
resetTelemetryConfig(&config->telemetryConfig);
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#ifndef USE_PARAMETER_GROUPS
|
||||
#ifdef USE_ADC
|
||||
resetAdcConfig(&config->adcConfig);
|
||||
#endif
|
||||
|
||||
#ifdef BEEPER
|
||||
resetBeeperDevConfig(&config->beeperDevConfig);
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#ifdef SONAR
|
||||
resetSonarConfig(&config->sonarConfig);
|
||||
#endif
|
||||
|
||||
#ifndef USE_PARAMETER_GROUPS
|
||||
#ifdef USE_SDCARD
|
||||
resetsdcardConfig(&config->sdcardConfig);
|
||||
#endif
|
||||
|
||||
#ifdef SERIALRX_PROVIDER
|
||||
config->rxConfig.serialrx_provider = SERIALRX_PROVIDER;
|
||||
#else
|
||||
config->rxConfig.serialrx_provider = 0;
|
||||
#endif
|
||||
config->rxConfig.halfDuplex = 0;
|
||||
config->rxConfig.rx_spi_protocol = RX_SPI_DEFAULT_PROTOCOL;
|
||||
config->rxConfig.sbus_inversion = 1;
|
||||
config->rxConfig.spektrum_sat_bind = 0;
|
||||
config->rxConfig.spektrum_sat_bind_autoreset = 1;
|
||||
config->rxConfig.midrc = 1500;
|
||||
config->rxConfig.mincheck = 1100;
|
||||
config->rxConfig.maxcheck = 1900;
|
||||
config->rxConfig.rx_min_usec = 885; // any of first 4 channels below this value will trigger rx loss detection
|
||||
config->rxConfig.rx_max_usec = 2115; // any of first 4 channels above this value will trigger rx loss detection
|
||||
|
||||
for (int i = 0; i < MAX_SUPPORTED_RC_CHANNEL_COUNT; i++) {
|
||||
rxFailsafeChannelConfig_t *channelFailsafeConfig = &config->rxConfig.failsafe_channel_configurations[i];
|
||||
channelFailsafeConfig->mode = (i < NON_AUX_CHANNEL_COUNT) ? RX_FAILSAFE_MODE_AUTO : RX_FAILSAFE_MODE_HOLD;
|
||||
channelFailsafeConfig->step = (i == THROTTLE) ? CHANNEL_VALUE_TO_RXFAIL_STEP(config->rxConfig.rx_min_usec) : CHANNEL_VALUE_TO_RXFAIL_STEP(config->rxConfig.midrc);
|
||||
}
|
||||
|
||||
config->rxConfig.rssi_channel = 0;
|
||||
config->rxConfig.rssi_scale = RSSI_SCALE_DEFAULT;
|
||||
config->rxConfig.rssi_invert = 0;
|
||||
config->rxConfig.rcInterpolation = RC_SMOOTHING_AUTO;
|
||||
config->rxConfig.rcInterpolationChannels = 0;
|
||||
config->rxConfig.rcInterpolationInterval = 19;
|
||||
config->rxConfig.fpvCamAngleDegrees = 0;
|
||||
config->rxConfig.max_aux_channel = DEFAULT_AUX_CHANNEL_COUNT;
|
||||
config->rxConfig.airModeActivateThreshold = 1350;
|
||||
|
||||
resetAllRxChannelRangeConfigurations(config->rxConfig.channelRanges);
|
||||
#endif
|
||||
|
||||
#ifndef USE_PARAMETER_GROUPS
|
||||
config->armingConfig.gyro_cal_on_first_arm = 0; // TODO - Cleanup retarded arm support
|
||||
config->armingConfig.disarm_kill_switch = 1;
|
||||
config->armingConfig.auto_disarm_delay = 5;
|
||||
|
||||
config->airplaneConfig.fixedwing_althold_reversed = false;
|
||||
|
||||
// Motor/ESC/Servo
|
||||
resetMixerConfig(&config->mixerConfig);
|
||||
resetMotorConfig(&config->motorConfig);
|
||||
#ifdef USE_SERVOS
|
||||
resetServoConfig(&config->servoConfig);
|
||||
#endif
|
||||
resetFlight3DConfig(&config->flight3DConfig);
|
||||
|
||||
#ifdef LED_STRIP
|
||||
resetLedStripConfig(&config->ledStripConfig);
|
||||
#endif
|
||||
|
||||
#ifdef GPS
|
||||
// gps/nav stuff
|
||||
config->gpsConfig.provider = GPS_NMEA;
|
||||
config->gpsConfig.sbasMode = SBAS_AUTO;
|
||||
config->gpsConfig.autoConfig = GPS_AUTOCONFIG_ON;
|
||||
config->gpsConfig.autoBaud = GPS_AUTOBAUD_OFF;
|
||||
#endif
|
||||
|
||||
resetSerialPinConfig(&config->serialPinConfig);
|
||||
|
||||
resetSerialConfig(&config->serialConfig);
|
||||
|
||||
for (int ii = 0; ii < MAX_PROFILE_COUNT; ++ii) {
|
||||
resetProfile(&config->profile[ii]);
|
||||
}
|
||||
for (int ii = 0; ii < CONTROL_RATE_PROFILE_COUNT; ++ii) {
|
||||
resetControlRateProfile(&config->controlRateProfile[ii]);
|
||||
}
|
||||
#endif
|
||||
|
||||
config->compassConfig.mag_declination = 0;
|
||||
|
||||
#ifdef BARO
|
||||
#ifndef USE_PARAMETER_GROUPS
|
||||
resetBarometerConfig(&config->barometerConfig);
|
||||
#endif
|
||||
#endif
|
||||
|
||||
// Radio
|
||||
#ifdef RX_CHANNELS_TAER
|
||||
parseRcChannels("TAER1234", &config->rxConfig);
|
||||
#else
|
||||
parseRcChannels("AETR1234", &config->rxConfig);
|
||||
#endif
|
||||
|
||||
#ifndef USE_PARAMETER_GROUPS
|
||||
resetRcControlsConfig(&config->rcControlsConfig);
|
||||
|
||||
config->throttleCorrectionConfig.throttle_correction_value = 0; // could 10 with althold or 40 for fpv
|
||||
config->throttleCorrectionConfig.throttle_correction_angle = 800; // could be 80.0 deg with atlhold or 45.0 for fpv
|
||||
|
||||
// Failsafe Variables
|
||||
config->failsafeConfig.failsafe_delay = 10; // 1sec
|
||||
config->failsafeConfig.failsafe_off_delay = 10; // 1sec
|
||||
config->failsafeConfig.failsafe_throttle = 1000; // default throttle off.
|
||||
config->failsafeConfig.failsafe_kill_switch = 0; // default failsafe switch action is identical to rc link loss
|
||||
config->failsafeConfig.failsafe_throttle_low_delay = 100; // default throttle low delay for "just disarm" on failsafe condition
|
||||
config->failsafeConfig.failsafe_procedure = FAILSAFE_PROCEDURE_DROP_IT;// default full failsafe procedure is 0: auto-landing
|
||||
#endif
|
||||
|
||||
#ifdef USE_SERVOS
|
||||
#ifndef USE_PARAMETER_GROUPS
|
||||
// servos
|
||||
for (int i = 0; i < MAX_SUPPORTED_SERVOS; i++) {
|
||||
config->servoProfile.servoConf[i].min = DEFAULT_SERVO_MIN;
|
||||
config->servoProfile.servoConf[i].max = DEFAULT_SERVO_MAX;
|
||||
config->servoProfile.servoConf[i].middle = DEFAULT_SERVO_MIDDLE;
|
||||
config->servoProfile.servoConf[i].rate = 100;
|
||||
config->servoProfile.servoConf[i].angleAtMin = DEFAULT_SERVO_MIN_ANGLE;
|
||||
config->servoProfile.servoConf[i].angleAtMax = DEFAULT_SERVO_MAX_ANGLE;
|
||||
config->servoProfile.servoConf[i].forwardFromChannel = CHANNEL_FORWARDING_DISABLED;
|
||||
}
|
||||
|
||||
// gimbal
|
||||
config->gimbalConfig.mode = GIMBAL_MODE_NORMAL;
|
||||
#endif
|
||||
|
||||
// Channel forwarding;
|
||||
config->servoConfig.channelForwardingStartChannel = AUX1;
|
||||
#endif
|
||||
|
||||
#ifndef USE_PARAMETER_GROUPS
|
||||
#ifdef GPS
|
||||
resetNavigationConfig(&config->navigationConfig);
|
||||
#endif
|
||||
#endif
|
||||
|
||||
// custom mixer. clear by defaults.
|
||||
for (int i = 0; i < MAX_SUPPORTED_MOTORS; i++) {
|
||||
config->customMotorMixer[i].throttle = 0.0f;
|
||||
}
|
||||
|
||||
#ifndef USE_PARAMETER_GROUPS
|
||||
#ifdef VTX
|
||||
config->vtxConfig.vtx_band = 4; //Fatshark/Airwaves
|
||||
config->vtxConfig.vtx_channel = 1; //CH1
|
||||
config->vtxConfig.vtx_mode = 0; //CH+BAND mode
|
||||
config->vtxConfig.vtx_mhz = 5740; //F0
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#ifdef TRANSPONDER
|
||||
static const uint8_t defaultTransponderData[6] = { 0x12, 0x34, 0x56, 0x78, 0x9A, 0xBC }; // Note, this is NOT a valid transponder code, it's just for testing production hardware
|
||||
|
||||
memcpy(config->transponderConfig.data, &defaultTransponderData, sizeof(defaultTransponderData));
|
||||
#endif
|
||||
|
||||
#ifndef USE_PARAMETER_GROUPS
|
||||
#ifdef BLACKBOX
|
||||
#if defined(ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT)
|
||||
config->blackboxConfig.device = BLACKBOX_DEVICE_FLASH;
|
||||
#elif defined(ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT)
|
||||
config->blackboxConfig.device = BLACKBOX_DEVICE_SDCARD;
|
||||
#else
|
||||
config->blackboxConfig.device = BLACKBOX_DEVICE_SERIAL;
|
||||
#endif
|
||||
config->blackboxConfig.rate_num = 1;
|
||||
config->blackboxConfig.rate_denom = 1;
|
||||
config->blackboxConfig.on_motor_test = 0; // default off
|
||||
#endif // BLACKBOX
|
||||
#endif
|
||||
|
||||
#ifdef SERIALRX_UART
|
||||
if (featureConfigured(FEATURE_RX_SERIAL)) {
|
||||
int serialIndex = findSerialPortIndexByIdentifier(SERIALRX_UART);
|
||||
if (serialIndex >= 0) {
|
||||
config->serialConfig.portConfigs[serialIndex].functionMask = FUNCTION_RX_SERIAL;
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
#ifndef USE_PARAMETER_GROUPS
|
||||
#ifdef USE_FLASHFS
|
||||
resetFlashConfig(&config->flashConfig);
|
||||
#endif
|
||||
|
||||
resetStatusLedConfig(&config->statusLedConfig);
|
||||
#endif
|
||||
|
||||
}
|
||||
#endif
|
||||
|
||||
void resetConfigs(void)
|
||||
{
|
||||
#ifndef USE_PARAMETER_GROUPS
|
||||
createDefaultConfig(&masterConfig);
|
||||
#endif
|
||||
pgResetAll(MAX_PROFILE_COUNT);
|
||||
|
||||
#if defined(TARGET_CONFIG)
|
||||
|
@ -890,16 +571,9 @@ void validateAndFixConfig(void)
|
|||
}
|
||||
#endif
|
||||
|
||||
#ifndef USE_PARAMETER_GROUPS
|
||||
serialConfig_t *serialConfig = &masterConfig.serialConfig;
|
||||
if (!isSerialConfigValid(serialConfig)) {
|
||||
resetSerialConfig(serialConfig);
|
||||
}
|
||||
#else
|
||||
if (!isSerialConfigValid(serialConfig())) {
|
||||
pgResetFn_serialConfig(serialConfigMutable());
|
||||
}
|
||||
#endif
|
||||
|
||||
// Prevent invalid notch cutoff
|
||||
if (currentPidProfile->dterm_notch_cutoff >= currentPidProfile->dterm_notch_hz) {
|
||||
|
|
Loading…
Reference in New Issue