mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-18 13:55:18 +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]);
|
resetControlRateConfig(&profile->controlRateProfile[rI]);
|
||||||
}
|
}
|
||||||
|
|
||||||
profile->activeRateProfile = 0;
|
profile->activeRateProfile = 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
#ifdef GPS
|
#ifdef GPS
|
||||||
|
@ -440,263 +440,280 @@ uint16_t getCurrentMinthrottle(void)
|
||||||
return masterConfig.escAndServoConfig.minthrottle;
|
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
|
// Default settings
|
||||||
static void resetConf(void)
|
void createDefaultConfig(master_t *config)
|
||||||
{
|
{
|
||||||
// Clear all configuration
|
// Clear all configuration
|
||||||
memset(&masterConfig, 0, sizeof(master_t));
|
memset(config, 0, sizeof(master_t));
|
||||||
setProfile(0);
|
|
||||||
|
|
||||||
featureClearAll();
|
intFeatureClearAll(config);
|
||||||
featureSet(DEFAULT_RX_FEATURE | FEATURE_FAILSAFE | FEATURE_SUPEREXPO_RATES);
|
intFeatureSet(DEFAULT_RX_FEATURE | FEATURE_FAILSAFE | FEATURE_SUPEREXPO_RATES, config);
|
||||||
#ifdef DEFAULT_FEATURES
|
#ifdef DEFAULT_FEATURES
|
||||||
featureSet(DEFAULT_FEATURES);
|
intFeatureSet(DEFAULT_FEATURES, config);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef OSD
|
#ifdef OSD
|
||||||
resetOsdConfig();
|
intFeatureSet(FEATURE_OSD, config);
|
||||||
|
resetOsdConfig(&config->osdProfile);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef BOARD_HAS_VOLTAGE_DIVIDER
|
#ifdef BOARD_HAS_VOLTAGE_DIVIDER
|
||||||
// only enable the VBAT feature by default if the board has a voltage divider otherwise
|
// 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.
|
// the user may see incorrect readings and unexpected issues with pin mappings may occur.
|
||||||
featureSet(FEATURE_VBAT);
|
intFeatureSet(FEATURE_VBAT, config);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
config->version = EEPROM_CONF_VERSION;
|
||||||
masterConfig.version = EEPROM_CONF_VERSION;
|
config->mixerMode = MIXER_QUADX;
|
||||||
masterConfig.mixerMode = MIXER_QUADX;
|
|
||||||
|
|
||||||
// global settings
|
// global settings
|
||||||
masterConfig.current_profile_index = 0; // default profile
|
config->current_profile_index = 0; // default profile
|
||||||
masterConfig.dcm_kp = 2500; // 1.0 * 10000
|
config->dcm_kp = 2500; // 1.0 * 10000
|
||||||
masterConfig.dcm_ki = 0; // 0.003 * 10000
|
config->dcm_ki = 0; // 0.003 * 10000
|
||||||
masterConfig.gyro_lpf = 0; // 256HZ default
|
config->gyro_lpf = 0; // 256HZ default
|
||||||
#ifdef STM32F10X
|
#ifdef STM32F10X
|
||||||
masterConfig.gyro_sync_denom = 8;
|
config->gyro_sync_denom = 8;
|
||||||
masterConfig.pid_process_denom = 1;
|
config->pid_process_denom = 1;
|
||||||
#elif defined(USE_GYRO_SPI_MPU6000) || defined(USE_GYRO_SPI_MPU6500)
|
#elif defined(USE_GYRO_SPI_MPU6000) || defined(USE_GYRO_SPI_MPU6500)
|
||||||
masterConfig.gyro_sync_denom = 1;
|
config->gyro_sync_denom = 1;
|
||||||
masterConfig.pid_process_denom = 4;
|
config->pid_process_denom = 4;
|
||||||
#else
|
#else
|
||||||
masterConfig.gyro_sync_denom = 4;
|
config->gyro_sync_denom = 4;
|
||||||
masterConfig.pid_process_denom = 2;
|
config->pid_process_denom = 2;
|
||||||
#endif
|
#endif
|
||||||
masterConfig.gyro_soft_type = FILTER_PT1;
|
config->gyro_soft_type = FILTER_PT1;
|
||||||
masterConfig.gyro_soft_lpf_hz = 90;
|
config->gyro_soft_lpf_hz = 90;
|
||||||
masterConfig.gyro_soft_notch_hz = 0;
|
config->gyro_soft_notch_hz = 0;
|
||||||
masterConfig.gyro_soft_notch_cutoff = 150;
|
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;
|
config->boardAlignment.rollDegrees = 0;
|
||||||
masterConfig.boardAlignment.pitchDegrees = 0;
|
config->boardAlignment.pitchDegrees = 0;
|
||||||
masterConfig.boardAlignment.yawDegrees = 0;
|
config->boardAlignment.yawDegrees = 0;
|
||||||
masterConfig.acc_hardware = ACC_DEFAULT; // default/autodetect
|
config->acc_hardware = ACC_DEFAULT; // default/autodetect
|
||||||
masterConfig.max_angle_inclination = 700; // 70 degrees
|
config->max_angle_inclination = 700; // 70 degrees
|
||||||
masterConfig.yaw_control_direction = 1;
|
config->yaw_control_direction = 1;
|
||||||
masterConfig.gyroConfig.gyroMovementCalibrationThreshold = 32;
|
config->gyroConfig.gyroMovementCalibrationThreshold = 32;
|
||||||
|
|
||||||
// xxx_hardware: 0:default/autodetect, 1: disable
|
// 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
|
#ifdef TELEMETRY
|
||||||
resetTelemetryConfig(&masterConfig.telemetryConfig);
|
resetTelemetryConfig(&config->telemetryConfig);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef SERIALRX_PROVIDER
|
#ifdef SERIALRX_PROVIDER
|
||||||
masterConfig.rxConfig.serialrx_provider = SERIALRX_PROVIDER;
|
config->rxConfig.serialrx_provider = SERIALRX_PROVIDER;
|
||||||
#else
|
#else
|
||||||
masterConfig.rxConfig.serialrx_provider = 0;
|
config->rxConfig.serialrx_provider = 0;
|
||||||
#endif
|
#endif
|
||||||
masterConfig.rxConfig.sbus_inversion = 1;
|
config->rxConfig.sbus_inversion = 1;
|
||||||
masterConfig.rxConfig.spektrum_sat_bind = 0;
|
config->rxConfig.spektrum_sat_bind = 0;
|
||||||
masterConfig.rxConfig.spektrum_sat_bind_autoreset = 1;
|
config->rxConfig.spektrum_sat_bind_autoreset = 1;
|
||||||
masterConfig.rxConfig.midrc = 1500;
|
config->rxConfig.midrc = 1500;
|
||||||
masterConfig.rxConfig.mincheck = 1100;
|
config->rxConfig.mincheck = 1100;
|
||||||
masterConfig.rxConfig.maxcheck = 1900;
|
config->rxConfig.maxcheck = 1900;
|
||||||
masterConfig.rxConfig.rx_min_usec = 885; // any of first 4 channels below this value will trigger rx loss detection
|
config->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.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++) {
|
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->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;
|
config->rxConfig.rssi_channel = 0;
|
||||||
masterConfig.rxConfig.rssi_scale = RSSI_SCALE_DEFAULT;
|
config->rxConfig.rssi_scale = RSSI_SCALE_DEFAULT;
|
||||||
masterConfig.rxConfig.rssi_ppm_invert = 0;
|
config->rxConfig.rssi_ppm_invert = 0;
|
||||||
masterConfig.rxConfig.rcInterpolation = RC_SMOOTHING_AUTO;
|
config->rxConfig.rcInterpolation = RC_SMOOTHING_AUTO;
|
||||||
masterConfig.rxConfig.rcInterpolationInterval = 19;
|
config->rxConfig.rcInterpolationInterval = 19;
|
||||||
masterConfig.rxConfig.fpvCamAngleDegrees = 0;
|
config->rxConfig.fpvCamAngleDegrees = 0;
|
||||||
masterConfig.rxConfig.max_aux_channel = MAX_AUX_CHANNELS;
|
config->rxConfig.max_aux_channel = MAX_AUX_CHANNELS;
|
||||||
masterConfig.rxConfig.airModeActivateThreshold = 1350;
|
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
|
config->gyro_cal_on_first_arm = 0; // TODO - Cleanup retarded arm support
|
||||||
masterConfig.disarm_kill_switch = 1;
|
config->disarm_kill_switch = 1;
|
||||||
masterConfig.auto_disarm_delay = 5;
|
config->auto_disarm_delay = 5;
|
||||||
masterConfig.small_angle = 25;
|
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
|
// Motor/ESC/Servo
|
||||||
resetEscAndServoConfig(&masterConfig.escAndServoConfig);
|
resetEscAndServoConfig(&config->escAndServoConfig);
|
||||||
resetFlight3DConfig(&masterConfig.flight3DConfig);
|
resetFlight3DConfig(&config->flight3DConfig);
|
||||||
|
|
||||||
#ifdef BRUSHED_MOTORS
|
#ifdef BRUSHED_MOTORS
|
||||||
masterConfig.motor_pwm_rate = BRUSHED_MOTORS_PWM_RATE;
|
config->motor_pwm_rate = BRUSHED_MOTORS_PWM_RATE;
|
||||||
masterConfig.motor_pwm_protocol = PWM_TYPE_BRUSHED;
|
config->motor_pwm_protocol = PWM_TYPE_BRUSHED;
|
||||||
masterConfig.use_unsyncedPwm = true;
|
config->use_unsyncedPwm = true;
|
||||||
#else
|
#else
|
||||||
masterConfig.motor_pwm_rate = BRUSHLESS_MOTORS_PWM_RATE;
|
config->motor_pwm_rate = BRUSHLESS_MOTORS_PWM_RATE;
|
||||||
masterConfig.motor_pwm_protocol = PWM_TYPE_ONESHOT125;
|
config->motor_pwm_protocol = PWM_TYPE_ONESHOT125;
|
||||||
#endif
|
#endif
|
||||||
masterConfig.servo_pwm_rate = 50;
|
|
||||||
|
config->servo_pwm_rate = 50;
|
||||||
|
|
||||||
#ifdef CC3D
|
#ifdef CC3D
|
||||||
masterConfig.use_buzzer_p6 = 0;
|
config->use_buzzer_p6 = 0;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef GPS
|
#ifdef GPS
|
||||||
// gps/nav stuff
|
// gps/nav stuff
|
||||||
masterConfig.gpsConfig.provider = GPS_NMEA;
|
config->gpsConfig.provider = GPS_NMEA;
|
||||||
masterConfig.gpsConfig.sbasMode = SBAS_AUTO;
|
config->gpsConfig.sbasMode = SBAS_AUTO;
|
||||||
masterConfig.gpsConfig.autoConfig = GPS_AUTOCONFIG_ON;
|
config->gpsConfig.autoConfig = GPS_AUTOCONFIG_ON;
|
||||||
masterConfig.gpsConfig.autoBaud = GPS_AUTOBAUD_OFF;
|
config->gpsConfig.autoBaud = GPS_AUTOBAUD_OFF;
|
||||||
#endif
|
#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;
|
config->mag_declination = 0;
|
||||||
masterConfig.acc_lpf_hz = 10.0f;
|
config->acc_lpf_hz = 10.0f;
|
||||||
masterConfig.accDeadband.xy = 40;
|
config->accDeadband.xy = 40;
|
||||||
masterConfig.accDeadband.z = 40;
|
config->accDeadband.z = 40;
|
||||||
masterConfig.acc_unarmedcal = 1;
|
config->acc_unarmedcal = 1;
|
||||||
|
|
||||||
#ifdef BARO
|
#ifdef BARO
|
||||||
resetBarometerConfig(&masterConfig.barometerConfig);
|
resetBarometerConfig(&config->barometerConfig);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// Radio
|
// Radio
|
||||||
#ifdef RX_CHANNELS_TAER
|
#ifdef RX_CHANNELS_TAER
|
||||||
parseRcChannels("TAER1234", &masterConfig.rxConfig);
|
parseRcChannels("TAER1234", &config->rxConfig);
|
||||||
#else
|
#else
|
||||||
parseRcChannels("AETR1234", &masterConfig.rxConfig);
|
parseRcChannels("AETR1234", &config->rxConfig);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
resetRcControlsConfig(&masterConfig.rcControlsConfig);
|
resetRcControlsConfig(&config->rcControlsConfig);
|
||||||
|
|
||||||
masterConfig.throttle_correction_value = 0; // could 10 with althold or 40 for fpv
|
config->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_angle = 800; // could be 80.0 deg with atlhold or 45.0 for fpv
|
||||||
|
|
||||||
// Failsafe Variables
|
// Failsafe Variables
|
||||||
masterConfig.failsafeConfig.failsafe_delay = 10; // 1sec
|
config->failsafeConfig.failsafe_delay = 10; // 1sec
|
||||||
masterConfig.failsafeConfig.failsafe_off_delay = 10; // 1sec
|
config->failsafeConfig.failsafe_off_delay = 10; // 1sec
|
||||||
masterConfig.failsafeConfig.failsafe_throttle = 1000; // default throttle off.
|
config->failsafeConfig.failsafe_throttle = 1000; // default throttle off.
|
||||||
masterConfig.failsafeConfig.failsafe_kill_switch = 0; // default failsafe switch action is identical to rc link loss
|
config->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
|
config->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_procedure = 0; // default full failsafe procedure is 0: auto-landing
|
||||||
|
|
||||||
#ifdef USE_SERVOS
|
#ifdef USE_SERVOS
|
||||||
// servos
|
// servos
|
||||||
for (int i = 0; i < MAX_SUPPORTED_SERVOS; i++) {
|
for (int i = 0; i < MAX_SUPPORTED_SERVOS; i++) {
|
||||||
masterConfig.servoConf[i].min = DEFAULT_SERVO_MIN;
|
config->servoConf[i].min = DEFAULT_SERVO_MIN;
|
||||||
masterConfig.servoConf[i].max = DEFAULT_SERVO_MAX;
|
config->servoConf[i].max = DEFAULT_SERVO_MAX;
|
||||||
masterConfig.servoConf[i].middle = DEFAULT_SERVO_MIDDLE;
|
config->servoConf[i].middle = DEFAULT_SERVO_MIDDLE;
|
||||||
masterConfig.servoConf[i].rate = 100;
|
config->servoConf[i].rate = 100;
|
||||||
masterConfig.servoConf[i].angleAtMin = DEFAULT_SERVO_MIN_ANGLE;
|
config->servoConf[i].angleAtMin = DEFAULT_SERVO_MIN_ANGLE;
|
||||||
masterConfig.servoConf[i].angleAtMax = DEFAULT_SERVO_MAX_ANGLE;
|
config->servoConf[i].angleAtMax = DEFAULT_SERVO_MAX_ANGLE;
|
||||||
masterConfig.servoConf[i].forwardFromChannel = CHANNEL_FORWARDING_DISABLED;
|
config->servoConf[i].forwardFromChannel = CHANNEL_FORWARDING_DISABLED;
|
||||||
}
|
}
|
||||||
|
|
||||||
// gimbal
|
// gimbal
|
||||||
masterConfig.gimbalConfig.mode = GIMBAL_MODE_NORMAL;
|
config->gimbalConfig.mode = GIMBAL_MODE_NORMAL;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef GPS
|
#ifdef GPS
|
||||||
resetGpsProfile(&masterConfig.gpsProfile);
|
resetGpsProfile(&config->gpsProfile);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// custom mixer. clear by defaults.
|
// custom mixer. clear by defaults.
|
||||||
for (int i = 0; i < MAX_SUPPORTED_MOTORS; i++) {
|
for (int i = 0; i < MAX_SUPPORTED_MOTORS; i++) {
|
||||||
masterConfig.customMotorMixer[i].throttle = 0.0f;
|
config->customMotorMixer[i].throttle = 0.0f;
|
||||||
}
|
}
|
||||||
|
|
||||||
#ifdef LED_STRIP
|
#ifdef LED_STRIP
|
||||||
applyDefaultColors(masterConfig.colors);
|
applyDefaultColors(config->colors);
|
||||||
applyDefaultLedStripConfig(masterConfig.ledConfigs);
|
applyDefaultLedStripConfig(config->ledConfigs);
|
||||||
applyDefaultModeColors(masterConfig.modeColors);
|
applyDefaultModeColors(config->modeColors);
|
||||||
applyDefaultSpecialColors(&(masterConfig.specialColors));
|
applyDefaultSpecialColors(&(config->specialColors));
|
||||||
masterConfig.ledstrip_visual_beeper = 0;
|
config->ledstrip_visual_beeper = 0;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef VTX
|
#ifdef VTX
|
||||||
masterConfig.vtx_band = 4; //Fatshark/Airwaves
|
config->vtx_band = 4; //Fatshark/Airwaves
|
||||||
masterConfig.vtx_channel = 1; //CH1
|
config->vtx_channel = 1; //CH1
|
||||||
masterConfig.vtx_mode = 0; //CH+BAND mode
|
config->vtx_mode = 0; //CH+BAND mode
|
||||||
masterConfig.vtx_mhz = 5740; //F0
|
config->vtx_mhz = 5740; //F0
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef TRANSPONDER
|
#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
|
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
|
#endif
|
||||||
|
|
||||||
#ifdef BLACKBOX
|
#ifdef BLACKBOX
|
||||||
|
|
||||||
#if defined(ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT)
|
#if defined(ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT)
|
||||||
featureSet(FEATURE_BLACKBOX);
|
intFeatureSet(FEATURE_BLACKBOX, config);
|
||||||
masterConfig.blackbox_device = BLACKBOX_DEVICE_FLASH;
|
config->blackbox_device = BLACKBOX_DEVICE_FLASH;
|
||||||
#elif defined(ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT)
|
#elif defined(ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT)
|
||||||
featureSet(FEATURE_BLACKBOX);
|
intFeatureSet(FEATURE_BLACKBOX, config);
|
||||||
masterConfig.blackbox_device = BLACKBOX_DEVICE_SDCARD;
|
config->blackbox_device = BLACKBOX_DEVICE_SDCARD;
|
||||||
#else
|
#else
|
||||||
masterConfig.blackbox_device = BLACKBOX_DEVICE_SERIAL;
|
config->blackbox_device = BLACKBOX_DEVICE_SERIAL;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
masterConfig.blackbox_rate_num = 1;
|
config->blackbox_rate_num = 1;
|
||||||
masterConfig.blackbox_rate_denom = 1;
|
config->blackbox_rate_denom = 1;
|
||||||
|
|
||||||
#endif // BLACKBOX
|
#endif // BLACKBOX
|
||||||
|
|
||||||
#ifdef SERIALRX_UART
|
#ifdef SERIALRX_UART
|
||||||
if (featureConfigured(FEATURE_RX_SERIAL)) {
|
if (featureConfigured(FEATURE_RX_SERIAL)) {
|
||||||
masterConfig.serialConfig.portConfigs[SERIALRX_UART].functionMask = FUNCTION_RX_SERIAL;
|
config->serialConfig.portConfigs[SERIALRX_UART].functionMask = FUNCTION_RX_SERIAL;
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if defined(TARGET_CONFIG)
|
#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
|
#endif
|
||||||
|
|
||||||
|
|
||||||
// copy first profile into remaining profile
|
// copy first profile into remaining profile
|
||||||
for (int i = 1; i < MAX_PROFILE_COUNT; i++) {
|
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)
|
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)
|
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)
|
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()
|
void featureClearAll()
|
||||||
{
|
{
|
||||||
masterConfig.enabledFeatures = 0;
|
intFeatureClearAll(&masterConfig);
|
||||||
|
}
|
||||||
|
|
||||||
|
static void intFeatureClearAll(master_t *config)
|
||||||
|
{
|
||||||
|
config->enabledFeatures = 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
uint32_t featureMask(void)
|
uint32_t featureMask(void)
|
||||||
|
|
|
@ -26,7 +26,6 @@
|
||||||
#define ONESHOT_FEATURE_CHANGED_DELAY_ON_BOOT_MS 1500
|
#define ONESHOT_FEATURE_CHANGED_DELAY_ON_BOOT_MS 1500
|
||||||
#define MAX_NAME_LENGTH 16
|
#define MAX_NAME_LENGTH 16
|
||||||
|
|
||||||
|
|
||||||
typedef enum {
|
typedef enum {
|
||||||
FEATURE_RX_PPM = 1 << 0,
|
FEATURE_RX_PPM = 1 << 0,
|
||||||
FEATURE_VBAT = 1 << 1,
|
FEATURE_VBAT = 1 << 1,
|
||||||
|
|
|
@ -174,3 +174,5 @@ typedef struct master_t {
|
||||||
extern master_t masterConfig;
|
extern master_t masterConfig;
|
||||||
extern profile_t *currentProfile;
|
extern profile_t *currentProfile;
|
||||||
extern controlRateConfig_t *currentControlRateProfile;
|
extern controlRateConfig_t *currentControlRateProfile;
|
||||||
|
|
||||||
|
void createDefaultConfig(master_t *config);
|
||||||
|
|
|
@ -1223,9 +1223,6 @@ void pgResetFn_specialColors(specialColorIndexes_t *instance)
|
||||||
void applyDefaultLedStripConfig(ledConfig_t *ledConfigs)
|
void applyDefaultLedStripConfig(ledConfig_t *ledConfigs)
|
||||||
{
|
{
|
||||||
memset(ledConfigs, 0, LED_MAX_STRIP_LENGTH * sizeof(ledConfig_t));
|
memset(ledConfigs, 0, LED_MAX_STRIP_LENGTH * sizeof(ledConfig_t));
|
||||||
memcpy(ledConfigs, &defaultLedStripConfig, sizeof(defaultLedStripConfig));
|
|
||||||
|
|
||||||
reevaluateLedConfig();
|
|
||||||
}
|
}
|
||||||
|
|
||||||
void applyDefaultColors(hsvColor_t *colors)
|
void applyDefaultColors(hsvColor_t *colors)
|
||||||
|
|
|
@ -831,24 +831,22 @@ void osdInit(void)
|
||||||
max7456_draw_screen();
|
max7456_draw_screen();
|
||||||
}
|
}
|
||||||
|
|
||||||
void resetOsdConfig(void)
|
void resetOsdConfig(osd_profile *osdProfile)
|
||||||
{
|
{
|
||||||
featureSet(FEATURE_OSD);
|
osdProfile->video_system = AUTO;
|
||||||
masterConfig.osdProfile.video_system = AUTO;
|
osdProfile->item_pos[OSD_MAIN_BATT_VOLTAGE] = -29;
|
||||||
masterConfig.osdProfile.item_pos[OSD_MAIN_BATT_VOLTAGE] = -29;
|
osdProfile->item_pos[OSD_RSSI_VALUE] = -59;
|
||||||
masterConfig.osdProfile.item_pos[OSD_RSSI_VALUE] = -59;
|
osdProfile->item_pos[OSD_TIMER] = -39;
|
||||||
masterConfig.osdProfile.item_pos[OSD_TIMER] = -39;
|
osdProfile->item_pos[OSD_THROTTLE_POS] = -9;
|
||||||
masterConfig.osdProfile.item_pos[OSD_THROTTLE_POS] = -9;
|
osdProfile->item_pos[OSD_CPU_LOAD] = 26;
|
||||||
masterConfig.osdProfile.item_pos[OSD_CPU_LOAD] = 26;
|
osdProfile->item_pos[OSD_VTX_CHANNEL] = 1;
|
||||||
masterConfig.osdProfile.item_pos[OSD_VTX_CHANNEL] = 1;
|
osdProfile->item_pos[OSD_VOLTAGE_WARNING] = -80;
|
||||||
masterConfig.osdProfile.item_pos[OSD_VOLTAGE_WARNING] = -80;
|
osdProfile->item_pos[OSD_ARMED] = -107;
|
||||||
masterConfig.osdProfile.item_pos[OSD_ARMED] = -107;
|
osdProfile->item_pos[OSD_DISARMED] = -109;
|
||||||
masterConfig.osdProfile.item_pos[OSD_DISARMED] = -109;
|
osdProfile->item_pos[OSD_ARTIFICIAL_HORIZON] = -1;
|
||||||
masterConfig.osdProfile.item_pos[OSD_ARTIFICIAL_HORIZON] = -1;
|
osdProfile->item_pos[OSD_HORIZON_SIDEBARS] = -1;
|
||||||
masterConfig.osdProfile.item_pos[OSD_HORIZON_SIDEBARS] = -1;
|
osdProfile->item_pos[OSD_CURRENT_DRAW] = -23;
|
||||||
masterConfig.osdProfile.item_pos[OSD_CURRENT_DRAW] = -23;
|
osdProfile->item_pos[OSD_MAH_DRAWN] = -18;
|
||||||
masterConfig.osdProfile.item_pos[OSD_MAH_DRAWN] = -18;
|
osdProfile->item_pos[OSD_CRAFT_NAME] = 1;
|
||||||
masterConfig.osdProfile.item_pos[OSD_CRAFT_NAME] = 1;
|
|
||||||
}
|
}
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
|
@ -65,4 +65,4 @@ typedef struct {
|
||||||
|
|
||||||
void updateOsd(void);
|
void updateOsd(void);
|
||||||
void osdInit(void);
|
void osdInit(void);
|
||||||
void resetOsdConfig(void);
|
void resetOsdConfig(osd_profile *osdProfile);
|
||||||
|
|
File diff suppressed because it is too large
Load diff
|
@ -91,7 +91,7 @@
|
||||||
#define VBAT_ADC_PIN PA0
|
#define VBAT_ADC_PIN PA0
|
||||||
#define RSSI_ADC_PIN PB0
|
#define RSSI_ADC_PIN PB0
|
||||||
|
|
||||||
#define LED_STRIP
|
//#define LED_STRIP
|
||||||
#define WS2811_PIN PB4
|
#define WS2811_PIN PB4
|
||||||
#define WS2811_TIMER TIM3
|
#define WS2811_TIMER TIM3
|
||||||
#define WS2811_DMA_TC_FLAG DMA1_FLAG_TC6
|
#define WS2811_DMA_TC_FLAG DMA1_FLAG_TC6
|
||||||
|
@ -103,20 +103,20 @@
|
||||||
|
|
||||||
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
|
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
|
||||||
|
|
||||||
#define SONAR
|
//#define SONAR
|
||||||
#define SONAR_ECHO_PIN PB0
|
//#define SONAR_ECHO_PIN PB0
|
||||||
#define SONAR_TRIGGER_PIN PB5
|
//#define SONAR_TRIGGER_PIN PB5
|
||||||
|
|
||||||
#undef GPS
|
#undef GPS
|
||||||
|
|
||||||
#ifdef CC3D_OPBL
|
#ifdef CC3D_OPBL
|
||||||
//#undef LED_STRIP
|
#undef LED_STRIP
|
||||||
#define SKIP_CLI_COMMAND_HELP
|
#define SKIP_CLI_COMMAND_HELP
|
||||||
#define SKIP_PID_FLOAT
|
#define SKIP_PID_FLOAT
|
||||||
#undef BARO
|
#undef BARO
|
||||||
#undef MAG
|
#undef MAG
|
||||||
#undef SONAR
|
#undef SONAR
|
||||||
#undef LED_STRIP
|
#undef USE_SOFTSERIAL1
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#define DEFAULT_RX_FEATURE FEATURE_RX_PPM
|
#define DEFAULT_RX_FEATURE FEATURE_RX_PPM
|
||||||
|
|
|
@ -110,7 +110,7 @@
|
||||||
#define SONAR_TRIGGER_PIN_PWM PB8
|
#define SONAR_TRIGGER_PIN_PWM PB8
|
||||||
#define SONAR_ECHO_PIN_PWM PB9
|
#define SONAR_ECHO_PIN_PWM PB9
|
||||||
|
|
||||||
#define DISPLAY
|
//#define DISPLAY
|
||||||
|
|
||||||
#define USE_UART1
|
#define USE_UART1
|
||||||
#define USE_UART2
|
#define USE_UART2
|
||||||
|
|
|
@ -81,13 +81,13 @@
|
||||||
#define USE_FLASHTOOLS
|
#define USE_FLASHTOOLS
|
||||||
#define USE_FLASH_M25P16
|
#define USE_FLASH_M25P16
|
||||||
|
|
||||||
#define SONAR
|
//#define SONAR
|
||||||
#define SONAR_TRIGGER_PIN PB0
|
#define SONAR_TRIGGER_PIN PB0
|
||||||
#define SONAR_ECHO_PIN PB1
|
#define SONAR_ECHO_PIN PB1
|
||||||
#define SONAR_TRIGGER_PIN_PWM PB8
|
#define SONAR_TRIGGER_PIN_PWM PB8
|
||||||
#define SONAR_ECHO_PIN_PWM PB9
|
#define SONAR_ECHO_PIN_PWM PB9
|
||||||
|
|
||||||
#define DISPLAY
|
//#define DISPLAY
|
||||||
|
|
||||||
#define USE_UART1
|
#define USE_UART1
|
||||||
#define USE_UART2
|
#define USE_UART2
|
||||||
|
@ -115,6 +115,12 @@
|
||||||
#define RSSI_ADC_PIN PA1
|
#define RSSI_ADC_PIN PA1
|
||||||
#define EXTERNAL1_ADC_PIN PA5
|
#define EXTERNAL1_ADC_PIN PA5
|
||||||
|
|
||||||
|
//#define LED_STRIP
|
||||||
|
//#define LED_STRIP_TIMER TIM3
|
||||||
|
|
||||||
|
#define SKIP_CLI_COMMAND_HELP
|
||||||
|
#define SKIP_PID_LUXFLOAT
|
||||||
|
|
||||||
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
|
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
|
||||||
|
|
||||||
// IO - stm32f103RCT6 in 64pin package
|
// IO - stm32f103RCT6 in 64pin package
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue