mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-23 16:25:31 +03:00
Graft of 'cli_diff_command' into 'master'.
This commit is contained in:
parent
271eb4c023
commit
f9354e53b3
10 changed files with 696 additions and 382 deletions
|
@ -273,7 +273,7 @@ void resetProfile(profile_t *profile)
|
|||
resetControlRateConfig(&profile->controlRateProfile[rI]);
|
||||
}
|
||||
|
||||
profile->activeRateProfile = 0;
|
||||
profile->activeRateProfile = 0;
|
||||
}
|
||||
|
||||
#ifdef GPS
|
||||
|
@ -440,263 +440,280 @@ uint16_t getCurrentMinthrottle(void)
|
|||
return masterConfig.escAndServoConfig.minthrottle;
|
||||
}
|
||||
|
||||
static void intFeatureClearAll(master_t *config);
|
||||
static void intFeatureSet(uint32_t mask, master_t *config);
|
||||
static void intFeatureClear(uint32_t mask, master_t *config);
|
||||
|
||||
// Default settings
|
||||
static void resetConf(void)
|
||||
void createDefaultConfig(master_t *config)
|
||||
{
|
||||
// Clear all configuration
|
||||
memset(&masterConfig, 0, sizeof(master_t));
|
||||
setProfile(0);
|
||||
memset(config, 0, sizeof(master_t));
|
||||
|
||||
featureClearAll();
|
||||
featureSet(DEFAULT_RX_FEATURE | FEATURE_FAILSAFE | FEATURE_SUPEREXPO_RATES);
|
||||
intFeatureClearAll(config);
|
||||
intFeatureSet(DEFAULT_RX_FEATURE | FEATURE_FAILSAFE | FEATURE_SUPEREXPO_RATES, config);
|
||||
#ifdef DEFAULT_FEATURES
|
||||
featureSet(DEFAULT_FEATURES);
|
||||
intFeatureSet(DEFAULT_FEATURES, config);
|
||||
#endif
|
||||
|
||||
#ifdef OSD
|
||||
resetOsdConfig();
|
||||
intFeatureSet(FEATURE_OSD, config);
|
||||
resetOsdConfig(&config->osdProfile);
|
||||
#endif
|
||||
|
||||
#ifdef BOARD_HAS_VOLTAGE_DIVIDER
|
||||
// only enable the VBAT feature by default if the board has a voltage divider otherwise
|
||||
// the user may see incorrect readings and unexpected issues with pin mappings may occur.
|
||||
featureSet(FEATURE_VBAT);
|
||||
intFeatureSet(FEATURE_VBAT, config);
|
||||
#endif
|
||||
|
||||
|
||||
masterConfig.version = EEPROM_CONF_VERSION;
|
||||
masterConfig.mixerMode = MIXER_QUADX;
|
||||
config->version = EEPROM_CONF_VERSION;
|
||||
config->mixerMode = MIXER_QUADX;
|
||||
|
||||
// global settings
|
||||
masterConfig.current_profile_index = 0; // default profile
|
||||
masterConfig.dcm_kp = 2500; // 1.0 * 10000
|
||||
masterConfig.dcm_ki = 0; // 0.003 * 10000
|
||||
masterConfig.gyro_lpf = 0; // 256HZ default
|
||||
config->current_profile_index = 0; // default profile
|
||||
config->dcm_kp = 2500; // 1.0 * 10000
|
||||
config->dcm_ki = 0; // 0.003 * 10000
|
||||
config->gyro_lpf = 0; // 256HZ default
|
||||
#ifdef STM32F10X
|
||||
masterConfig.gyro_sync_denom = 8;
|
||||
masterConfig.pid_process_denom = 1;
|
||||
config->gyro_sync_denom = 8;
|
||||
config->pid_process_denom = 1;
|
||||
#elif defined(USE_GYRO_SPI_MPU6000) || defined(USE_GYRO_SPI_MPU6500)
|
||||
masterConfig.gyro_sync_denom = 1;
|
||||
masterConfig.pid_process_denom = 4;
|
||||
config->gyro_sync_denom = 1;
|
||||
config->pid_process_denom = 4;
|
||||
#else
|
||||
masterConfig.gyro_sync_denom = 4;
|
||||
masterConfig.pid_process_denom = 2;
|
||||
config->gyro_sync_denom = 4;
|
||||
config->pid_process_denom = 2;
|
||||
#endif
|
||||
masterConfig.gyro_soft_type = FILTER_PT1;
|
||||
masterConfig.gyro_soft_lpf_hz = 90;
|
||||
masterConfig.gyro_soft_notch_hz = 0;
|
||||
masterConfig.gyro_soft_notch_cutoff = 150;
|
||||
config->gyro_soft_type = FILTER_PT1;
|
||||
config->gyro_soft_lpf_hz = 90;
|
||||
config->gyro_soft_notch_hz = 0;
|
||||
config->gyro_soft_notch_cutoff = 150;
|
||||
|
||||
masterConfig.debug_mode = DEBUG_NONE;
|
||||
config->debug_mode = DEBUG_NONE;
|
||||
|
||||
resetAccelerometerTrims(&masterConfig.accZero);
|
||||
resetAccelerometerTrims(&config->accZero);
|
||||
|
||||
resetSensorAlignment(&masterConfig.sensorAlignmentConfig);
|
||||
resetSensorAlignment(&config->sensorAlignmentConfig);
|
||||
|
||||
masterConfig.boardAlignment.rollDegrees = 0;
|
||||
masterConfig.boardAlignment.pitchDegrees = 0;
|
||||
masterConfig.boardAlignment.yawDegrees = 0;
|
||||
masterConfig.acc_hardware = ACC_DEFAULT; // default/autodetect
|
||||
masterConfig.max_angle_inclination = 700; // 70 degrees
|
||||
masterConfig.yaw_control_direction = 1;
|
||||
masterConfig.gyroConfig.gyroMovementCalibrationThreshold = 32;
|
||||
config->boardAlignment.rollDegrees = 0;
|
||||
config->boardAlignment.pitchDegrees = 0;
|
||||
config->boardAlignment.yawDegrees = 0;
|
||||
config->acc_hardware = ACC_DEFAULT; // default/autodetect
|
||||
config->max_angle_inclination = 700; // 70 degrees
|
||||
config->yaw_control_direction = 1;
|
||||
config->gyroConfig.gyroMovementCalibrationThreshold = 32;
|
||||
|
||||
// xxx_hardware: 0:default/autodetect, 1: disable
|
||||
masterConfig.mag_hardware = 0;
|
||||
config->mag_hardware = 0;
|
||||
|
||||
masterConfig.baro_hardware = 0;
|
||||
config->baro_hardware = 0;
|
||||
|
||||
resetBatteryConfig(&masterConfig.batteryConfig);
|
||||
resetBatteryConfig(&config->batteryConfig);
|
||||
|
||||
#ifdef TELEMETRY
|
||||
resetTelemetryConfig(&masterConfig.telemetryConfig);
|
||||
resetTelemetryConfig(&config->telemetryConfig);
|
||||
#endif
|
||||
|
||||
#ifdef SERIALRX_PROVIDER
|
||||
masterConfig.rxConfig.serialrx_provider = SERIALRX_PROVIDER;
|
||||
config->rxConfig.serialrx_provider = SERIALRX_PROVIDER;
|
||||
#else
|
||||
masterConfig.rxConfig.serialrx_provider = 0;
|
||||
config->rxConfig.serialrx_provider = 0;
|
||||
#endif
|
||||
masterConfig.rxConfig.sbus_inversion = 1;
|
||||
masterConfig.rxConfig.spektrum_sat_bind = 0;
|
||||
masterConfig.rxConfig.spektrum_sat_bind_autoreset = 1;
|
||||
masterConfig.rxConfig.midrc = 1500;
|
||||
masterConfig.rxConfig.mincheck = 1100;
|
||||
masterConfig.rxConfig.maxcheck = 1900;
|
||||
masterConfig.rxConfig.rx_min_usec = 885; // any of first 4 channels below this value will trigger rx loss detection
|
||||
masterConfig.rxConfig.rx_max_usec = 2115; // any of first 4 channels above this value will trigger rx loss detection
|
||||
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++) {
|
||||
rxFailsafeChannelConfiguration_t *channelFailsafeConfiguration = &masterConfig.rxConfig.failsafe_channel_configurations[i];
|
||||
rxFailsafeChannelConfiguration_t *channelFailsafeConfiguration = &config->rxConfig.failsafe_channel_configurations[i];
|
||||
channelFailsafeConfiguration->mode = (i < NON_AUX_CHANNEL_COUNT) ? RX_FAILSAFE_MODE_AUTO : RX_FAILSAFE_MODE_HOLD;
|
||||
channelFailsafeConfiguration->step = (i == THROTTLE) ? CHANNEL_VALUE_TO_RXFAIL_STEP(masterConfig.rxConfig.rx_min_usec) : CHANNEL_VALUE_TO_RXFAIL_STEP(masterConfig.rxConfig.midrc);
|
||||
channelFailsafeConfiguration->step = (i == THROTTLE) ? CHANNEL_VALUE_TO_RXFAIL_STEP(config->rxConfig.rx_min_usec) : CHANNEL_VALUE_TO_RXFAIL_STEP(config->rxConfig.midrc);
|
||||
}
|
||||
|
||||
masterConfig.rxConfig.rssi_channel = 0;
|
||||
masterConfig.rxConfig.rssi_scale = RSSI_SCALE_DEFAULT;
|
||||
masterConfig.rxConfig.rssi_ppm_invert = 0;
|
||||
masterConfig.rxConfig.rcInterpolation = RC_SMOOTHING_AUTO;
|
||||
masterConfig.rxConfig.rcInterpolationInterval = 19;
|
||||
masterConfig.rxConfig.fpvCamAngleDegrees = 0;
|
||||
masterConfig.rxConfig.max_aux_channel = MAX_AUX_CHANNELS;
|
||||
masterConfig.rxConfig.airModeActivateThreshold = 1350;
|
||||
config->rxConfig.rssi_channel = 0;
|
||||
config->rxConfig.rssi_scale = RSSI_SCALE_DEFAULT;
|
||||
config->rxConfig.rssi_ppm_invert = 0;
|
||||
config->rxConfig.rcInterpolation = RC_SMOOTHING_AUTO;
|
||||
config->rxConfig.rcInterpolationInterval = 19;
|
||||
config->rxConfig.fpvCamAngleDegrees = 0;
|
||||
config->rxConfig.max_aux_channel = MAX_AUX_CHANNELS;
|
||||
config->rxConfig.airModeActivateThreshold = 1350;
|
||||
|
||||
resetAllRxChannelRangeConfigurations(masterConfig.rxConfig.channelRanges);
|
||||
resetAllRxChannelRangeConfigurations(config->rxConfig.channelRanges);
|
||||
|
||||
masterConfig.inputFilteringMode = INPUT_FILTERING_DISABLED;
|
||||
config->inputFilteringMode = INPUT_FILTERING_DISABLED;
|
||||
|
||||
masterConfig.gyro_cal_on_first_arm = 0; // TODO - Cleanup retarded arm support
|
||||
masterConfig.disarm_kill_switch = 1;
|
||||
masterConfig.auto_disarm_delay = 5;
|
||||
masterConfig.small_angle = 25;
|
||||
config->gyro_cal_on_first_arm = 0; // TODO - Cleanup retarded arm support
|
||||
config->disarm_kill_switch = 1;
|
||||
config->auto_disarm_delay = 5;
|
||||
config->small_angle = 25;
|
||||
|
||||
resetMixerConfig(&masterConfig.mixerConfig);
|
||||
resetMixerConfig(&config->mixerConfig);
|
||||
|
||||
masterConfig.airplaneConfig.fixedwing_althold_dir = 1;
|
||||
config->airplaneConfig.fixedwing_althold_dir = 1;
|
||||
|
||||
// Motor/ESC/Servo
|
||||
resetEscAndServoConfig(&masterConfig.escAndServoConfig);
|
||||
resetFlight3DConfig(&masterConfig.flight3DConfig);
|
||||
resetEscAndServoConfig(&config->escAndServoConfig);
|
||||
resetFlight3DConfig(&config->flight3DConfig);
|
||||
|
||||
#ifdef BRUSHED_MOTORS
|
||||
masterConfig.motor_pwm_rate = BRUSHED_MOTORS_PWM_RATE;
|
||||
masterConfig.motor_pwm_protocol = PWM_TYPE_BRUSHED;
|
||||
masterConfig.use_unsyncedPwm = true;
|
||||
config->motor_pwm_rate = BRUSHED_MOTORS_PWM_RATE;
|
||||
config->motor_pwm_protocol = PWM_TYPE_BRUSHED;
|
||||
config->use_unsyncedPwm = true;
|
||||
#else
|
||||
masterConfig.motor_pwm_rate = BRUSHLESS_MOTORS_PWM_RATE;
|
||||
masterConfig.motor_pwm_protocol = PWM_TYPE_ONESHOT125;
|
||||
config->motor_pwm_rate = BRUSHLESS_MOTORS_PWM_RATE;
|
||||
config->motor_pwm_protocol = PWM_TYPE_ONESHOT125;
|
||||
#endif
|
||||
masterConfig.servo_pwm_rate = 50;
|
||||
|
||||
config->servo_pwm_rate = 50;
|
||||
|
||||
#ifdef CC3D
|
||||
masterConfig.use_buzzer_p6 = 0;
|
||||
config->use_buzzer_p6 = 0;
|
||||
#endif
|
||||
|
||||
#ifdef GPS
|
||||
// gps/nav stuff
|
||||
masterConfig.gpsConfig.provider = GPS_NMEA;
|
||||
masterConfig.gpsConfig.sbasMode = SBAS_AUTO;
|
||||
masterConfig.gpsConfig.autoConfig = GPS_AUTOCONFIG_ON;
|
||||
masterConfig.gpsConfig.autoBaud = GPS_AUTOBAUD_OFF;
|
||||
config->gpsConfig.provider = GPS_NMEA;
|
||||
config->gpsConfig.sbasMode = SBAS_AUTO;
|
||||
config->gpsConfig.autoConfig = GPS_AUTOCONFIG_ON;
|
||||
config->gpsConfig.autoBaud = GPS_AUTOBAUD_OFF;
|
||||
#endif
|
||||
|
||||
resetSerialConfig(&masterConfig.serialConfig);
|
||||
resetSerialConfig(&config->serialConfig);
|
||||
|
||||
masterConfig.emf_avoidance = 0; // TODO - needs removal
|
||||
config->emf_avoidance = 0; // TODO - needs removal
|
||||
|
||||
resetProfile(currentProfile);
|
||||
resetProfile(&config->profile[0]);
|
||||
|
||||
resetRollAndPitchTrims(&masterConfig.accelerometerTrims);
|
||||
resetRollAndPitchTrims(&config->accelerometerTrims);
|
||||
|
||||
masterConfig.mag_declination = 0;
|
||||
masterConfig.acc_lpf_hz = 10.0f;
|
||||
masterConfig.accDeadband.xy = 40;
|
||||
masterConfig.accDeadband.z = 40;
|
||||
masterConfig.acc_unarmedcal = 1;
|
||||
config->mag_declination = 0;
|
||||
config->acc_lpf_hz = 10.0f;
|
||||
config->accDeadband.xy = 40;
|
||||
config->accDeadband.z = 40;
|
||||
config->acc_unarmedcal = 1;
|
||||
|
||||
#ifdef BARO
|
||||
resetBarometerConfig(&masterConfig.barometerConfig);
|
||||
resetBarometerConfig(&config->barometerConfig);
|
||||
#endif
|
||||
|
||||
// Radio
|
||||
#ifdef RX_CHANNELS_TAER
|
||||
parseRcChannels("TAER1234", &masterConfig.rxConfig);
|
||||
parseRcChannels("TAER1234", &config->rxConfig);
|
||||
#else
|
||||
parseRcChannels("AETR1234", &masterConfig.rxConfig);
|
||||
parseRcChannels("AETR1234", &config->rxConfig);
|
||||
#endif
|
||||
|
||||
resetRcControlsConfig(&masterConfig.rcControlsConfig);
|
||||
resetRcControlsConfig(&config->rcControlsConfig);
|
||||
|
||||
masterConfig.throttle_correction_value = 0; // could 10 with althold or 40 for fpv
|
||||
masterConfig.throttle_correction_angle = 800; // could be 80.0 deg with atlhold or 45.0 for fpv
|
||||
config->throttle_correction_value = 0; // could 10 with althold or 40 for fpv
|
||||
config->throttle_correction_angle = 800; // could be 80.0 deg with atlhold or 45.0 for fpv
|
||||
|
||||
// Failsafe Variables
|
||||
masterConfig.failsafeConfig.failsafe_delay = 10; // 1sec
|
||||
masterConfig.failsafeConfig.failsafe_off_delay = 10; // 1sec
|
||||
masterConfig.failsafeConfig.failsafe_throttle = 1000; // default throttle off.
|
||||
masterConfig.failsafeConfig.failsafe_kill_switch = 0; // default failsafe switch action is identical to rc link loss
|
||||
masterConfig.failsafeConfig.failsafe_throttle_low_delay = 100; // default throttle low delay for "just disarm" on failsafe condition
|
||||
masterConfig.failsafeConfig.failsafe_procedure = 0; // default full failsafe procedure is 0: auto-landing
|
||||
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 = 0; // default full failsafe procedure is 0: auto-landing
|
||||
|
||||
#ifdef USE_SERVOS
|
||||
// servos
|
||||
for (int i = 0; i < MAX_SUPPORTED_SERVOS; i++) {
|
||||
masterConfig.servoConf[i].min = DEFAULT_SERVO_MIN;
|
||||
masterConfig.servoConf[i].max = DEFAULT_SERVO_MAX;
|
||||
masterConfig.servoConf[i].middle = DEFAULT_SERVO_MIDDLE;
|
||||
masterConfig.servoConf[i].rate = 100;
|
||||
masterConfig.servoConf[i].angleAtMin = DEFAULT_SERVO_MIN_ANGLE;
|
||||
masterConfig.servoConf[i].angleAtMax = DEFAULT_SERVO_MAX_ANGLE;
|
||||
masterConfig.servoConf[i].forwardFromChannel = CHANNEL_FORWARDING_DISABLED;
|
||||
config->servoConf[i].min = DEFAULT_SERVO_MIN;
|
||||
config->servoConf[i].max = DEFAULT_SERVO_MAX;
|
||||
config->servoConf[i].middle = DEFAULT_SERVO_MIDDLE;
|
||||
config->servoConf[i].rate = 100;
|
||||
config->servoConf[i].angleAtMin = DEFAULT_SERVO_MIN_ANGLE;
|
||||
config->servoConf[i].angleAtMax = DEFAULT_SERVO_MAX_ANGLE;
|
||||
config->servoConf[i].forwardFromChannel = CHANNEL_FORWARDING_DISABLED;
|
||||
}
|
||||
|
||||
// gimbal
|
||||
masterConfig.gimbalConfig.mode = GIMBAL_MODE_NORMAL;
|
||||
config->gimbalConfig.mode = GIMBAL_MODE_NORMAL;
|
||||
#endif
|
||||
|
||||
#ifdef GPS
|
||||
resetGpsProfile(&masterConfig.gpsProfile);
|
||||
resetGpsProfile(&config->gpsProfile);
|
||||
#endif
|
||||
|
||||
// custom mixer. clear by defaults.
|
||||
for (int i = 0; i < MAX_SUPPORTED_MOTORS; i++) {
|
||||
masterConfig.customMotorMixer[i].throttle = 0.0f;
|
||||
config->customMotorMixer[i].throttle = 0.0f;
|
||||
}
|
||||
|
||||
#ifdef LED_STRIP
|
||||
applyDefaultColors(masterConfig.colors);
|
||||
applyDefaultLedStripConfig(masterConfig.ledConfigs);
|
||||
applyDefaultModeColors(masterConfig.modeColors);
|
||||
applyDefaultSpecialColors(&(masterConfig.specialColors));
|
||||
masterConfig.ledstrip_visual_beeper = 0;
|
||||
applyDefaultColors(config->colors);
|
||||
applyDefaultLedStripConfig(config->ledConfigs);
|
||||
applyDefaultModeColors(config->modeColors);
|
||||
applyDefaultSpecialColors(&(config->specialColors));
|
||||
config->ledstrip_visual_beeper = 0;
|
||||
#endif
|
||||
|
||||
#ifdef VTX
|
||||
masterConfig.vtx_band = 4; //Fatshark/Airwaves
|
||||
masterConfig.vtx_channel = 1; //CH1
|
||||
masterConfig.vtx_mode = 0; //CH+BAND mode
|
||||
masterConfig.vtx_mhz = 5740; //F0
|
||||
config->vtx_band = 4; //Fatshark/Airwaves
|
||||
config->vtx_channel = 1; //CH1
|
||||
config->vtx_mode = 0; //CH+BAND mode
|
||||
config->vtx_mhz = 5740; //F0
|
||||
#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(masterConfig.transponderData, &defaultTransponderData, sizeof(defaultTransponderData));
|
||||
memcpy(config->transponderData, &defaultTransponderData, sizeof(defaultTransponderData));
|
||||
#endif
|
||||
|
||||
#ifdef BLACKBOX
|
||||
|
||||
#if defined(ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT)
|
||||
featureSet(FEATURE_BLACKBOX);
|
||||
masterConfig.blackbox_device = BLACKBOX_DEVICE_FLASH;
|
||||
intFeatureSet(FEATURE_BLACKBOX, config);
|
||||
config->blackbox_device = BLACKBOX_DEVICE_FLASH;
|
||||
#elif defined(ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT)
|
||||
featureSet(FEATURE_BLACKBOX);
|
||||
masterConfig.blackbox_device = BLACKBOX_DEVICE_SDCARD;
|
||||
intFeatureSet(FEATURE_BLACKBOX, config);
|
||||
config->blackbox_device = BLACKBOX_DEVICE_SDCARD;
|
||||
#else
|
||||
masterConfig.blackbox_device = BLACKBOX_DEVICE_SERIAL;
|
||||
config->blackbox_device = BLACKBOX_DEVICE_SERIAL;
|
||||
#endif
|
||||
|
||||
masterConfig.blackbox_rate_num = 1;
|
||||
masterConfig.blackbox_rate_denom = 1;
|
||||
|
||||
config->blackbox_rate_num = 1;
|
||||
config->blackbox_rate_denom = 1;
|
||||
#endif // BLACKBOX
|
||||
|
||||
#ifdef SERIALRX_UART
|
||||
if (featureConfigured(FEATURE_RX_SERIAL)) {
|
||||
masterConfig.serialConfig.portConfigs[SERIALRX_UART].functionMask = FUNCTION_RX_SERIAL;
|
||||
config->serialConfig.portConfigs[SERIALRX_UART].functionMask = FUNCTION_RX_SERIAL;
|
||||
}
|
||||
#endif
|
||||
|
||||
#if defined(TARGET_CONFIG)
|
||||
targetConfiguration();
|
||||
// Don't look at target specific config settings when getting default
|
||||
// values for a CLI diff. This is suboptimal, but it doesn't break the
|
||||
// public API
|
||||
if (config == &masterConfig) {
|
||||
targetConfiguration();
|
||||
}
|
||||
#endif
|
||||
|
||||
|
||||
// copy first profile into remaining profile
|
||||
for (int i = 1; i < MAX_PROFILE_COUNT; i++) {
|
||||
memcpy(&masterConfig.profile[i], currentProfile, sizeof(profile_t));
|
||||
memcpy(&config->profile[i], &config->profile[0], sizeof(profile_t));
|
||||
}
|
||||
}
|
||||
|
||||
static void resetConf(void)
|
||||
{
|
||||
createDefaultConfig(&masterConfig);
|
||||
|
||||
setProfile(0);
|
||||
|
||||
#ifdef LED_STRIP
|
||||
reevaluateLedConfig();
|
||||
#endif
|
||||
}
|
||||
|
||||
static uint8_t calculateChecksum(const uint8_t *data, uint32_t length)
|
||||
|
@ -1067,17 +1084,32 @@ bool feature(uint32_t mask)
|
|||
|
||||
void featureSet(uint32_t mask)
|
||||
{
|
||||
masterConfig.enabledFeatures |= mask;
|
||||
intFeatureSet(mask, &masterConfig);
|
||||
}
|
||||
|
||||
static void intFeatureSet(uint32_t mask, master_t *config)
|
||||
{
|
||||
config->enabledFeatures |= mask;
|
||||
}
|
||||
|
||||
void featureClear(uint32_t mask)
|
||||
{
|
||||
masterConfig.enabledFeatures &= ~(mask);
|
||||
intFeatureClear(mask, &masterConfig);
|
||||
}
|
||||
|
||||
static void intFeatureClear(uint32_t mask, master_t *config)
|
||||
{
|
||||
config->enabledFeatures &= ~(mask);
|
||||
}
|
||||
|
||||
void featureClearAll()
|
||||
{
|
||||
masterConfig.enabledFeatures = 0;
|
||||
intFeatureClearAll(&masterConfig);
|
||||
}
|
||||
|
||||
static void intFeatureClearAll(master_t *config)
|
||||
{
|
||||
config->enabledFeatures = 0;
|
||||
}
|
||||
|
||||
uint32_t featureMask(void)
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue