mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-16 04:45:24 +03:00
Added CLI 'diff' command.
This commit is contained in:
parent
6a02cde5be
commit
31c3790a5d
10 changed files with 696 additions and 381 deletions
|
@ -442,263 +442,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)
|
||||
// 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)
|
||||
|
@ -1069,17 +1086,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)
|
||||
|
|
|
@ -25,7 +25,6 @@
|
|||
#define MAX_RATEPROFILES 3
|
||||
#define MAX_NAME_LENGTH 16
|
||||
|
||||
|
||||
typedef enum {
|
||||
FEATURE_RX_PPM = 1 << 0,
|
||||
FEATURE_VBAT = 1 << 1,
|
||||
|
|
|
@ -174,3 +174,5 @@ typedef struct master_t {
|
|||
extern master_t masterConfig;
|
||||
extern profile_t *currentProfile;
|
||||
extern controlRateConfig_t *currentControlRateProfile;
|
||||
|
||||
void createDefaultConfig(master_t *config);
|
||||
|
|
|
@ -1068,8 +1068,6 @@ void pgResetFn_specialColors(specialColorIndexes_t *instance)
|
|||
void applyDefaultLedStripConfig(ledConfig_t *ledConfigs)
|
||||
{
|
||||
memset(ledConfigs, 0, LED_MAX_STRIP_LENGTH * sizeof(ledConfig_t));
|
||||
|
||||
reevaluateLedConfig();
|
||||
}
|
||||
|
||||
void applyDefaultColors(hsvColor_t *colors)
|
||||
|
|
|
@ -833,24 +833,22 @@ void osdInit(void)
|
|||
max7456_draw_screen();
|
||||
}
|
||||
|
||||
void resetOsdConfig(void)
|
||||
void resetOsdConfig(osd_profile *osdProfile)
|
||||
{
|
||||
featureSet(FEATURE_OSD);
|
||||
masterConfig.osdProfile.video_system = AUTO;
|
||||
masterConfig.osdProfile.item_pos[OSD_MAIN_BATT_VOLTAGE] = -29;
|
||||
masterConfig.osdProfile.item_pos[OSD_RSSI_VALUE] = -59;
|
||||
masterConfig.osdProfile.item_pos[OSD_TIMER] = -39;
|
||||
masterConfig.osdProfile.item_pos[OSD_THROTTLE_POS] = -9;
|
||||
masterConfig.osdProfile.item_pos[OSD_CPU_LOAD] = 26;
|
||||
masterConfig.osdProfile.item_pos[OSD_VTX_CHANNEL] = 1;
|
||||
masterConfig.osdProfile.item_pos[OSD_VOLTAGE_WARNING] = -80;
|
||||
masterConfig.osdProfile.item_pos[OSD_ARMED] = -107;
|
||||
masterConfig.osdProfile.item_pos[OSD_DISARMED] = -109;
|
||||
masterConfig.osdProfile.item_pos[OSD_ARTIFICIAL_HORIZON] = -1;
|
||||
masterConfig.osdProfile.item_pos[OSD_HORIZON_SIDEBARS] = -1;
|
||||
masterConfig.osdProfile.item_pos[OSD_CURRENT_DRAW] = -23;
|
||||
masterConfig.osdProfile.item_pos[OSD_MAH_DRAWN] = -18;
|
||||
masterConfig.osdProfile.item_pos[OSD_CRAFT_NAME] = 1;
|
||||
osdProfile->video_system = AUTO;
|
||||
osdProfile->item_pos[OSD_MAIN_BATT_VOLTAGE] = -29;
|
||||
osdProfile->item_pos[OSD_RSSI_VALUE] = -59;
|
||||
osdProfile->item_pos[OSD_TIMER] = -39;
|
||||
osdProfile->item_pos[OSD_THROTTLE_POS] = -9;
|
||||
osdProfile->item_pos[OSD_CPU_LOAD] = 26;
|
||||
osdProfile->item_pos[OSD_VTX_CHANNEL] = 1;
|
||||
osdProfile->item_pos[OSD_VOLTAGE_WARNING] = -80;
|
||||
osdProfile->item_pos[OSD_ARMED] = -107;
|
||||
osdProfile->item_pos[OSD_DISARMED] = -109;
|
||||
osdProfile->item_pos[OSD_ARTIFICIAL_HORIZON] = -1;
|
||||
osdProfile->item_pos[OSD_HORIZON_SIDEBARS] = -1;
|
||||
osdProfile->item_pos[OSD_CURRENT_DRAW] = -23;
|
||||
osdProfile->item_pos[OSD_MAH_DRAWN] = -18;
|
||||
osdProfile->item_pos[OSD_CRAFT_NAME] = 1;
|
||||
}
|
||||
|
||||
#endif
|
||||
|
|
|
@ -65,4 +65,4 @@ typedef struct {
|
|||
|
||||
void updateOsd(void);
|
||||
void osdInit(void);
|
||||
void resetOsdConfig(void);
|
||||
void resetOsdConfig(osd_profile *osdProfile);
|
||||
|
|
|
@ -115,8 +115,10 @@ static void cliMotorMix(char *cmdline);
|
|||
static void cliDefaults(char *cmdline);
|
||||
void cliDfu(char *cmdLine);
|
||||
static void cliDump(char *cmdLine);
|
||||
void cliDumpProfile(uint8_t profileIndex);
|
||||
void cliDumpRateProfile(uint8_t rateProfileIndex) ;
|
||||
static void cliDiff(char *cmdLine);
|
||||
static void printConfig(char *cmdLine, bool doDiff);
|
||||
static void cliDumpProfile(uint8_t profileIndex, uint8_t dumpMask, master_t *defaultProfile);
|
||||
static void cliDumpRateProfile(uint8_t rateProfileIndex, uint8_t dumpMask, master_t *defaultProfile) ;
|
||||
static void cliExit(char *cmdline);
|
||||
static void cliFeature(char *cmdline);
|
||||
static void cliMotor(char *cmdline);
|
||||
|
@ -190,6 +192,17 @@ static void cliBeeper(char *cmdline);
|
|||
static char cliBuffer[48];
|
||||
static uint32_t bufferIndex = 0;
|
||||
|
||||
typedef enum {
|
||||
DUMP_MASTER = (1 << 0),
|
||||
DUMP_PROFILE = (1 << 1),
|
||||
DUMP_RATES = (1 << 2),
|
||||
DUMP_ALL = (1 << 3),
|
||||
DO_DIFF = (1 << 4),
|
||||
DIFF_COMMENTED = (1 << 5),
|
||||
} dumpFlags_e;
|
||||
|
||||
static const char* const sectionBreak = "\r\n";
|
||||
|
||||
#ifndef USE_QUAD_MIXER_ONLY
|
||||
// sync this with mixerMode_e
|
||||
static const char * const mixerNames[] = {
|
||||
|
@ -270,7 +283,10 @@ const clicmd_t cmdTable[] = {
|
|||
#endif
|
||||
CLI_COMMAND_DEF("defaults", "reset to defaults and reboot", NULL, cliDefaults),
|
||||
CLI_COMMAND_DEF("dfu", "DFU mode on reboot", NULL, cliDfu),
|
||||
CLI_COMMAND_DEF("dump", "dump configuration", "[master|profile]", cliDump),
|
||||
CLI_COMMAND_DEF("diff", "list configuration changes from default",
|
||||
"[master|profile|rates|all] {commented}", cliDiff),
|
||||
CLI_COMMAND_DEF("dump", "dump configuration",
|
||||
"[master|profile|rates|all]", cliDump),
|
||||
CLI_COMMAND_DEF("exit", NULL, NULL, cliExit),
|
||||
CLI_COMMAND_DEF("feature", "configure features",
|
||||
"list\r\n"
|
||||
|
@ -924,6 +940,11 @@ static void cliPrint(const char *str);
|
|||
static void cliPrintf(const char *fmt, ...);
|
||||
static void cliWrite(uint8_t ch);
|
||||
|
||||
#define printSectionBreak() cliPrintf((char *)sectionBreak)
|
||||
|
||||
#define COMPARE_CONFIG(value) (masterConfig.value == defaultConfig.value)
|
||||
static bool cliDumpPrintf(uint8_t dumpMask, bool equalsDefault, const char *format, ...);
|
||||
|
||||
static void cliPrompt(void)
|
||||
{
|
||||
cliPrint("\r\n# ");
|
||||
|
@ -969,6 +990,36 @@ static bool isEmpty(const char *string)
|
|||
return *string == '\0';
|
||||
}
|
||||
|
||||
static void printRxFail(uint8_t dumpMask, master_t *defaultConfig)
|
||||
{
|
||||
// print out rxConfig failsafe settings
|
||||
rxFailsafeChannelConfiguration_t *channelFailsafeConfiguration;
|
||||
rxFailsafeChannelConfiguration_t *channelFailsafeConfigurationDefault;
|
||||
bool equalsDefault;
|
||||
bool requireValue;
|
||||
char modeCharacter;
|
||||
for (uint8_t channel = 0; channel < MAX_SUPPORTED_RC_CHANNEL_COUNT; channel++) {
|
||||
channelFailsafeConfiguration = &masterConfig.rxConfig.failsafe_channel_configurations[channel];
|
||||
channelFailsafeConfigurationDefault = &defaultConfig->rxConfig.failsafe_channel_configurations[channel];
|
||||
equalsDefault = channelFailsafeConfiguration->mode == channelFailsafeConfigurationDefault->mode
|
||||
&& channelFailsafeConfiguration->step == channelFailsafeConfigurationDefault->step;
|
||||
requireValue = channelFailsafeConfiguration->mode == RX_FAILSAFE_MODE_SET;
|
||||
modeCharacter = rxFailsafeModeCharacters[channelFailsafeConfiguration->mode];
|
||||
if (requireValue) {
|
||||
cliDumpPrintf(dumpMask, equalsDefault, "rxfail %u %c %d\r\n",
|
||||
channel,
|
||||
modeCharacter,
|
||||
RXFAIL_STEP_TO_CHANNEL_VALUE(channelFailsafeConfiguration->step)
|
||||
);
|
||||
} else {
|
||||
cliDumpPrintf(dumpMask, equalsDefault, "rxfail %u %c\r\n",
|
||||
channel,
|
||||
modeCharacter
|
||||
);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
static void cliRxFail(char *cmdline)
|
||||
{
|
||||
uint8_t channel;
|
||||
|
@ -1031,10 +1082,9 @@ static void cliRxFail(char *cmdline)
|
|||
|
||||
char modeCharacter = rxFailsafeModeCharacters[channelFailsafeConfiguration->mode];
|
||||
|
||||
// triple use of cliPrintf below
|
||||
// double use of cliPrintf below
|
||||
// 1. acknowledge interpretation on command,
|
||||
// 2. query current setting on single item,
|
||||
// 3. recursive use for full list.
|
||||
|
||||
if (requireValue) {
|
||||
cliPrintf("rxfail %u %c %d\r\n",
|
||||
|
@ -1054,16 +1104,20 @@ static void cliRxFail(char *cmdline)
|
|||
}
|
||||
}
|
||||
|
||||
static void cliAux(char *cmdline)
|
||||
static void printAux(uint8_t dumpMask, master_t *defaultConfig)
|
||||
{
|
||||
int i, val = 0;
|
||||
char *ptr;
|
||||
|
||||
if (isEmpty(cmdline)) {
|
||||
// print out aux channel settings
|
||||
for (i = 0; i < MAX_MODE_ACTIVATION_CONDITION_COUNT; i++) {
|
||||
modeActivationCondition_t *mac = &masterConfig.modeActivationConditions[i];
|
||||
cliPrintf("aux %u %u %u %u %u\r\n",
|
||||
modeActivationCondition_t *mac;
|
||||
modeActivationCondition_t *macDefault;
|
||||
bool equalsDefault;
|
||||
for (int i = 0; i < MAX_MODE_ACTIVATION_CONDITION_COUNT; i++) {
|
||||
mac = &masterConfig.modeActivationConditions[i];
|
||||
macDefault = &defaultConfig->modeActivationConditions[i];
|
||||
equalsDefault = mac->modeId == macDefault->modeId
|
||||
&& mac->auxChannelIndex == macDefault->auxChannelIndex
|
||||
&& mac->range.startStep == macDefault->range.startStep
|
||||
&& mac->range.endStep == macDefault->range.endStep;
|
||||
cliDumpPrintf(dumpMask, equalsDefault, "aux %u %u %u %u %u\r\n",
|
||||
i,
|
||||
mac->modeId,
|
||||
mac->auxChannelIndex,
|
||||
|
@ -1071,6 +1125,15 @@ static void cliAux(char *cmdline)
|
|||
MODE_STEP_TO_CHANNEL_VALUE(mac->range.endStep)
|
||||
);
|
||||
}
|
||||
}
|
||||
|
||||
static void cliAux(char *cmdline)
|
||||
{
|
||||
int i, val = 0;
|
||||
char *ptr;
|
||||
|
||||
if (isEmpty(cmdline)) {
|
||||
printAux(DUMP_MASTER, &masterConfig);
|
||||
} else {
|
||||
ptr = cmdline;
|
||||
i = atoi(ptr++);
|
||||
|
@ -1104,28 +1167,44 @@ static void cliAux(char *cmdline)
|
|||
}
|
||||
}
|
||||
|
||||
static void printSerial(uint8_t dumpMask, master_t *defaultConfig)
|
||||
{
|
||||
serialConfig_t *serialConfig;
|
||||
serialConfig_t *serialConfigDefault;
|
||||
bool equalsDefault;
|
||||
for (int i = 0; i < SERIAL_PORT_COUNT; i++) {
|
||||
serialConfig = &masterConfig.serialConfig;
|
||||
if (!serialIsPortAvailable(serialConfig->portConfigs[i].identifier)) {
|
||||
continue;
|
||||
};
|
||||
serialConfigDefault = &defaultConfig->serialConfig;
|
||||
equalsDefault = serialConfig->portConfigs[i].identifier == serialConfigDefault->portConfigs[i].identifier
|
||||
&& serialConfig->portConfigs[i].functionMask == serialConfigDefault->portConfigs[i].functionMask
|
||||
&& serialConfig->portConfigs[i].msp_baudrateIndex == serialConfigDefault->portConfigs[i].msp_baudrateIndex
|
||||
&& serialConfig->portConfigs[i].gps_baudrateIndex == serialConfigDefault->portConfigs[i].gps_baudrateIndex
|
||||
&& serialConfig->portConfigs[i].telemetry_baudrateIndex == serialConfigDefault->portConfigs[i].telemetry_baudrateIndex
|
||||
&& serialConfig->portConfigs[i].blackbox_baudrateIndex == serialConfigDefault->portConfigs[i].blackbox_baudrateIndex;
|
||||
cliDumpPrintf(dumpMask, equalsDefault, "serial %d %d %ld %ld %ld %ld\r\n" ,
|
||||
serialConfig->portConfigs[i].identifier,
|
||||
serialConfig->portConfigs[i].functionMask,
|
||||
baudRates[serialConfig->portConfigs[i].msp_baudrateIndex],
|
||||
baudRates[serialConfig->portConfigs[i].gps_baudrateIndex],
|
||||
baudRates[serialConfig->portConfigs[i].telemetry_baudrateIndex],
|
||||
baudRates[serialConfig->portConfigs[i].blackbox_baudrateIndex]
|
||||
);
|
||||
}
|
||||
}
|
||||
|
||||
static void cliSerial(char *cmdline)
|
||||
{
|
||||
int i, val;
|
||||
char *ptr;
|
||||
|
||||
if (isEmpty(cmdline)) {
|
||||
for (i = 0; i < SERIAL_PORT_COUNT; i++) {
|
||||
if (!serialIsPortAvailable(masterConfig.serialConfig.portConfigs[i].identifier)) {
|
||||
continue;
|
||||
};
|
||||
cliPrintf("serial %d %d %ld %ld %ld %ld\r\n" ,
|
||||
masterConfig.serialConfig.portConfigs[i].identifier,
|
||||
masterConfig.serialConfig.portConfigs[i].functionMask,
|
||||
baudRates[masterConfig.serialConfig.portConfigs[i].msp_baudrateIndex],
|
||||
baudRates[masterConfig.serialConfig.portConfigs[i].gps_baudrateIndex],
|
||||
baudRates[masterConfig.serialConfig.portConfigs[i].telemetry_baudrateIndex],
|
||||
baudRates[masterConfig.serialConfig.portConfigs[i].blackbox_baudrateIndex]
|
||||
);
|
||||
}
|
||||
printSerial(DUMP_MASTER, &masterConfig);
|
||||
|
||||
return;
|
||||
}
|
||||
|
||||
serialPortConfig_t portConfig;
|
||||
memset(&portConfig, 0 , sizeof(portConfig));
|
||||
|
||||
|
@ -1271,16 +1350,22 @@ static void cliSerialPassthrough(char *cmdline)
|
|||
}
|
||||
#endif
|
||||
|
||||
static void cliAdjustmentRange(char *cmdline)
|
||||
static void printAdjustmentRange(uint8_t dumpMask, master_t *defaultConfig)
|
||||
{
|
||||
int i, val = 0;
|
||||
char *ptr;
|
||||
|
||||
if (isEmpty(cmdline)) {
|
||||
// print out adjustment ranges channel settings
|
||||
for (i = 0; i < MAX_ADJUSTMENT_RANGE_COUNT; i++) {
|
||||
adjustmentRange_t *ar = &masterConfig.adjustmentRanges[i];
|
||||
cliPrintf("adjrange %u %u %u %u %u %u %u\r\n",
|
||||
adjustmentRange_t *ar;
|
||||
adjustmentRange_t *arDefault;
|
||||
bool equalsDefault;
|
||||
for (int i = 0; i < MAX_ADJUSTMENT_RANGE_COUNT; i++) {
|
||||
ar = &masterConfig.adjustmentRanges[i];
|
||||
arDefault = &defaultConfig->adjustmentRanges[i];
|
||||
equalsDefault = ar->auxChannelIndex == arDefault->auxChannelIndex
|
||||
&& ar->range.startStep == arDefault->range.startStep
|
||||
&& ar->range.endStep == arDefault->range.endStep
|
||||
&& ar->adjustmentFunction == arDefault->adjustmentFunction
|
||||
&& ar->auxSwitchChannelIndex == arDefault->auxSwitchChannelIndex
|
||||
&& ar->adjustmentIndex == arDefault->adjustmentIndex;
|
||||
cliDumpPrintf(dumpMask, equalsDefault, "adjrange %u %u %u %u %u %u %u\r\n",
|
||||
i,
|
||||
ar->adjustmentIndex,
|
||||
ar->auxChannelIndex,
|
||||
|
@ -1290,6 +1375,15 @@ static void cliAdjustmentRange(char *cmdline)
|
|||
ar->auxSwitchChannelIndex
|
||||
);
|
||||
}
|
||||
}
|
||||
|
||||
static void cliAdjustmentRange(char *cmdline)
|
||||
{
|
||||
int i, val = 0;
|
||||
char *ptr;
|
||||
|
||||
if (isEmpty(cmdline)) {
|
||||
printAdjustmentRange(DUMP_MASTER, &masterConfig);
|
||||
} else {
|
||||
ptr = cmdline;
|
||||
i = atoi(ptr++);
|
||||
|
@ -1424,16 +1518,27 @@ static void cliMotorMix(char *cmdline)
|
|||
#endif
|
||||
}
|
||||
|
||||
static void printRxRange(uint8_t dumpMask, master_t *defaultConfig)
|
||||
{
|
||||
rxChannelRangeConfiguration_t *channelRangeConfiguration;
|
||||
rxChannelRangeConfiguration_t *channelRangeConfigurationDefault;
|
||||
bool equalsDefault;
|
||||
for (int i = 0; i < NON_AUX_CHANNEL_COUNT; i++) {
|
||||
channelRangeConfiguration = &masterConfig.rxConfig.channelRanges[i];
|
||||
channelRangeConfigurationDefault = &defaultConfig->rxConfig.channelRanges[i];
|
||||
equalsDefault = channelRangeConfiguration->min == channelRangeConfigurationDefault->min
|
||||
&& channelRangeConfiguration->max == channelRangeConfigurationDefault->max;
|
||||
cliDumpPrintf(dumpMask, equalsDefault, "rxrange %u %u %u\r\n", i, channelRangeConfiguration->min, channelRangeConfiguration->max);
|
||||
}
|
||||
}
|
||||
|
||||
static void cliRxRange(char *cmdline)
|
||||
{
|
||||
int i, validArgumentCount = 0;
|
||||
char *ptr;
|
||||
|
||||
if (isEmpty(cmdline)) {
|
||||
for (i = 0; i < NON_AUX_CHANNEL_COUNT; i++) {
|
||||
rxChannelRangeConfiguration_t *channelRangeConfiguration = &masterConfig.rxConfig.channelRanges[i];
|
||||
cliPrintf("rxrange %u %u %u\r\n", i, channelRangeConfiguration->min, channelRangeConfiguration->max);
|
||||
}
|
||||
printRxRange(DUMP_MASTER, &masterConfig);
|
||||
} else if (strcasecmp(cmdline, "reset") == 0) {
|
||||
resetAllRxChannelRangeConfigurations(masterConfig.rxConfig.channelRanges);
|
||||
} else {
|
||||
|
@ -1470,17 +1575,28 @@ static void cliRxRange(char *cmdline)
|
|||
}
|
||||
|
||||
#ifdef LED_STRIP
|
||||
static void printLed(uint8_t dumpMask, master_t *defaultConfig)
|
||||
{
|
||||
bool equalsDefault;
|
||||
ledConfig_t ledConfig;
|
||||
ledConfig_t ledConfigDefault;
|
||||
char ledConfigBuffer[20];
|
||||
for (int i = 0; i < LED_MAX_STRIP_LENGTH; i++) {
|
||||
ledConfig = masterConfig.ledConfigs[i];
|
||||
ledConfigDefault = defaultConfig->ledConfigs[i];
|
||||
equalsDefault = ledConfig == ledConfigDefault;
|
||||
generateLedConfig(i, ledConfigBuffer, sizeof(ledConfigBuffer));
|
||||
cliDumpPrintf(dumpMask, equalsDefault, "led %u %s\r\n", i, ledConfigBuffer);
|
||||
}
|
||||
}
|
||||
|
||||
static void cliLed(char *cmdline)
|
||||
{
|
||||
int i;
|
||||
char *ptr;
|
||||
char ledConfigBuffer[20];
|
||||
|
||||
if (isEmpty(cmdline)) {
|
||||
for (i = 0; i < LED_MAX_STRIP_LENGTH; i++) {
|
||||
generateLedConfig(i, ledConfigBuffer, sizeof(ledConfigBuffer));
|
||||
cliPrintf("led %u %s\r\n", i, ledConfigBuffer);
|
||||
}
|
||||
printLed(DUMP_MASTER, &masterConfig);
|
||||
} else {
|
||||
ptr = cmdline;
|
||||
i = atoi(ptr);
|
||||
|
@ -1495,20 +1611,33 @@ static void cliLed(char *cmdline)
|
|||
}
|
||||
}
|
||||
|
||||
static void printColor(uint8_t dumpMask, master_t *defaultConfig)
|
||||
{
|
||||
hsvColor_t *color;
|
||||
hsvColor_t *colorDefault;
|
||||
bool equalsDefault;
|
||||
for (int i = 0; i < LED_CONFIGURABLE_COLOR_COUNT; i++) {
|
||||
color = &masterConfig.colors[i];
|
||||
colorDefault = &defaultConfig->colors[i];
|
||||
equalsDefault = color->h == colorDefault->h
|
||||
&& color->s == colorDefault->s
|
||||
&& color->v == colorDefault->v;
|
||||
cliDumpPrintf(dumpMask, equalsDefault, "color %u %d,%u,%u\r\n",
|
||||
i,
|
||||
color->h,
|
||||
color->s,
|
||||
color->v
|
||||
);
|
||||
}
|
||||
}
|
||||
|
||||
static void cliColor(char *cmdline)
|
||||
{
|
||||
int i;
|
||||
char *ptr;
|
||||
|
||||
if (isEmpty(cmdline)) {
|
||||
for (i = 0; i < LED_CONFIGURABLE_COLOR_COUNT; i++) {
|
||||
cliPrintf("color %u %d,%u,%u\r\n",
|
||||
i,
|
||||
masterConfig.colors[i].h,
|
||||
masterConfig.colors[i].s,
|
||||
masterConfig.colors[i].v
|
||||
);
|
||||
}
|
||||
printColor(DUMP_MASTER, &masterConfig);
|
||||
} else {
|
||||
ptr = cmdline;
|
||||
i = atoi(ptr);
|
||||
|
@ -1523,20 +1652,27 @@ static void cliColor(char *cmdline)
|
|||
}
|
||||
}
|
||||
|
||||
static void cliModeColor(char *cmdline)
|
||||
static void printModeColor(uint8_t dumpMask, master_t *defaultConfig)
|
||||
{
|
||||
if (isEmpty(cmdline)) {
|
||||
for (int i = 0; i < LED_MODE_COUNT; i++) {
|
||||
for (int j = 0; j < LED_DIRECTION_COUNT; j++) {
|
||||
int colorIndex = modeColors[i].color[j];
|
||||
cliPrintf("mode_color %u %u %u\r\n", i, j, colorIndex);
|
||||
int colorIndex = masterConfig.modeColors[i].color[j];
|
||||
int colorIndexDefault = defaultConfig->modeColors[i].color[j];
|
||||
cliDumpPrintf(dumpMask, colorIndex == colorIndexDefault, "mode_color %u %u %u\r\n", i, j, colorIndex);
|
||||
}
|
||||
}
|
||||
|
||||
for (int j = 0; j < LED_SPECIAL_COLOR_COUNT; j++) {
|
||||
int colorIndex = specialColors.color[j];
|
||||
cliPrintf("mode_color %u %u %u\r\n", LED_SPECIAL, j, colorIndex);
|
||||
int colorIndex = masterConfig.specialColors.color[j];
|
||||
int colorIndexDefault = defaultConfig->specialColors.color[j];
|
||||
cliDumpPrintf(dumpMask, colorIndex == colorIndexDefault, "mode_color %u %u %u\r\n", LED_SPECIAL, j, colorIndex);
|
||||
}
|
||||
}
|
||||
|
||||
static void cliModeColor(char *cmdline)
|
||||
{
|
||||
if (isEmpty(cmdline)) {
|
||||
printModeColor(DUMP_MASTER, &masterConfig);
|
||||
} else {
|
||||
enum {MODE = 0, FUNCTION, COLOR, ARGS_COUNT};
|
||||
int args[ARGS_COUNT];
|
||||
|
@ -1566,6 +1702,52 @@ static void cliModeColor(char *cmdline)
|
|||
#endif
|
||||
|
||||
#ifdef USE_SERVOS
|
||||
static void printServo(uint8_t dumpMask, master_t *defaultConfig)
|
||||
{
|
||||
// print out servo settings
|
||||
int i;
|
||||
servoParam_t *servoConf;
|
||||
servoParam_t *servoConfDefault;
|
||||
bool equalsDefault;
|
||||
for (i = 0; i < MAX_SUPPORTED_SERVOS; i++) {
|
||||
servoConf = &masterConfig.servoConf[i];
|
||||
servoConfDefault = &defaultConfig->servoConf[i];
|
||||
equalsDefault = servoConf->min == servoConfDefault->min
|
||||
&& servoConf->max == servoConfDefault->max
|
||||
&& servoConf->middle == servoConfDefault->middle
|
||||
&& servoConf->angleAtMin == servoConfDefault->angleAtMax
|
||||
&& servoConf->rate == servoConfDefault->rate
|
||||
&& servoConf->forwardFromChannel == servoConfDefault->forwardFromChannel;
|
||||
|
||||
cliDumpPrintf(dumpMask, equalsDefault, "servo %u %d %d %d %d %d %d %d\r\n",
|
||||
i,
|
||||
servoConf->min,
|
||||
servoConf->max,
|
||||
servoConf->middle,
|
||||
servoConf->angleAtMin,
|
||||
servoConf->angleAtMax,
|
||||
servoConf->rate,
|
||||
servoConf->forwardFromChannel
|
||||
);
|
||||
}
|
||||
|
||||
printSectionBreak();
|
||||
|
||||
// print servo directions
|
||||
unsigned int channel;
|
||||
for (i = 0; i < MAX_SUPPORTED_SERVOS; i++) {
|
||||
servoConf = &masterConfig.servoConf[i];
|
||||
servoConfDefault = &defaultConfig->servoConf[i];
|
||||
equalsDefault = servoConf->reversedSources == servoConfDefault->reversedSources;
|
||||
for (channel = 0; channel < INPUT_SOURCE_COUNT; channel++) {
|
||||
if (servoConf->reversedSources & (1 << channel)) {
|
||||
equalsDefault = ~(servoConf->reversedSources ^ servoConfDefault->reversedSources) & (1 << channel);
|
||||
cliDumpPrintf(dumpMask, equalsDefault, "smix reverse %d %d r\r\n", i , channel);
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
static void cliServo(char *cmdline)
|
||||
{
|
||||
enum { SERVO_ARGUMENT_COUNT = 8 };
|
||||
|
@ -1577,21 +1759,7 @@ static void cliServo(char *cmdline)
|
|||
char *ptr;
|
||||
|
||||
if (isEmpty(cmdline)) {
|
||||
// print out servo settings
|
||||
for (i = 0; i < MAX_SUPPORTED_SERVOS; i++) {
|
||||
servo = &masterConfig.servoConf[i];
|
||||
|
||||
cliPrintf("servo %u %d %d %d %d %d %d %d\r\n",
|
||||
i,
|
||||
servo->min,
|
||||
servo->max,
|
||||
servo->middle,
|
||||
servo->angleAtMin,
|
||||
servo->angleAtMax,
|
||||
servo->rate,
|
||||
servo->forwardFromChannel
|
||||
);
|
||||
}
|
||||
printServo(DUMP_MASTER, &masterConfig);
|
||||
} else {
|
||||
int validArgumentCount = 0;
|
||||
|
||||
|
@ -1948,16 +2116,21 @@ static void cliFlashRead(char *cmdline)
|
|||
#endif
|
||||
|
||||
#ifdef VTX
|
||||
static void cliVtx(char *cmdline)
|
||||
static void printVtx(uint8_t dumpMask, master_t *defaultConfig)
|
||||
{
|
||||
int i, val = 0;
|
||||
char *ptr;
|
||||
|
||||
if (isEmpty(cmdline)) {
|
||||
// print out vtx channel settings
|
||||
for (i = 0; i < MAX_CHANNEL_ACTIVATION_CONDITION_COUNT; i++) {
|
||||
vtxChannelActivationCondition_t *cac = &masterConfig.vtxChannelActivationConditions[i];
|
||||
printf("vtx %u %u %u %u %u %u\r\n",
|
||||
vtxChannelActivationCondition_t *cac;
|
||||
vtxChannelActivationCondition_t *cacDefault;
|
||||
bool equalsDefault;
|
||||
for (int i = 0; i < MAX_CHANNEL_ACTIVATION_CONDITION_COUNT; i++) {
|
||||
cac = &masterConfig.vtxChannelActivationConditions[i];
|
||||
cacDefault = &defaultConfig->vtxChannelActivationConditions[i];
|
||||
equalsDefault = cac->auxChannelIndex == cacDefault->auxChannelIndex
|
||||
&& cac->band == cacDefault->band
|
||||
&& cac->channel == cacDefault->channel
|
||||
&& cac->range.startStep == cacDefault->range.startStep
|
||||
&& cac->range.endStep == cacDefault->range.endStep;
|
||||
cliDumpPrintf(dumpMask, equalsDefault, "vtx %u %u %u %u %u %u\r\n",
|
||||
i,
|
||||
cac->auxChannelIndex,
|
||||
cac->band,
|
||||
|
@ -1966,6 +2139,15 @@ static void cliVtx(char *cmdline)
|
|||
MODE_STEP_TO_CHANNEL_VALUE(cac->range.endStep)
|
||||
);
|
||||
}
|
||||
}
|
||||
|
||||
static void cliVtx(char *cmdline)
|
||||
{
|
||||
int i, val = 0;
|
||||
char *ptr;
|
||||
|
||||
if (isEmpty(cmdline)) {
|
||||
printVtx(DUMP_MASTER, &masterConfig);
|
||||
} else {
|
||||
ptr = cmdline;
|
||||
i = atoi(ptr++);
|
||||
|
@ -2008,7 +2190,72 @@ static void cliVtx(char *cmdline)
|
|||
}
|
||||
#endif
|
||||
|
||||
static void dumpValues(uint16_t valueSection)
|
||||
static void printName(uint8_t dumpMask)
|
||||
{
|
||||
cliDumpPrintf(dumpMask, strlen(masterConfig.name) == 0, "name %s\r\n", strlen(masterConfig.name) > 0 ? masterConfig.name : "-");
|
||||
}
|
||||
|
||||
static void cliName(char *cmdline)
|
||||
{
|
||||
uint32_t len = strlen(cmdline);
|
||||
if (len > 0) {
|
||||
memset(masterConfig.name, 0, ARRAYLEN(masterConfig.name));
|
||||
strncpy(masterConfig.name, cmdline, MIN(len, MAX_NAME_LENGTH));
|
||||
}
|
||||
printName(DUMP_MASTER);
|
||||
}
|
||||
|
||||
void *getValuePointer(const clivalue_t *value)
|
||||
{
|
||||
void *ptr = value->ptr;
|
||||
|
||||
if ((value->type & VALUE_SECTION_MASK) == PROFILE_VALUE) {
|
||||
ptr = ((uint8_t *)ptr) + (sizeof(profile_t) * masterConfig.current_profile_index);
|
||||
}
|
||||
|
||||
if ((value->type & VALUE_SECTION_MASK) == PROFILE_RATE_VALUE) {
|
||||
ptr = ((uint8_t *)ptr) + (sizeof(profile_t) * masterConfig.current_profile_index) + (sizeof(controlRateConfig_t) * getCurrentControlRateProfile());
|
||||
}
|
||||
|
||||
return ptr;
|
||||
}
|
||||
|
||||
static bool valueEqualsDefault(const clivalue_t *value, master_t *defaultConfig)
|
||||
{
|
||||
void *ptr = getValuePointer(value);
|
||||
|
||||
void *ptrDefault = ((uint8_t *)ptr) - (uint32_t)&masterConfig + (uint32_t)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;
|
||||
|
||||
case VAR_UINT32:
|
||||
result = *(uint32_t *)ptr == *(uint32_t *)ptrDefault;
|
||||
break;
|
||||
|
||||
case VAR_FLOAT:
|
||||
result = *(float *)ptr == *(float *)ptrDefault;
|
||||
break;
|
||||
}
|
||||
return result;
|
||||
}
|
||||
|
||||
static void dumpValues(uint16_t valueSection, uint8_t dumpMask, master_t *defaultConfig)
|
||||
{
|
||||
uint32_t i;
|
||||
const clivalue_t *value;
|
||||
|
@ -2019,64 +2266,83 @@ static void dumpValues(uint16_t valueSection)
|
|||
continue;
|
||||
}
|
||||
|
||||
cliPrintf("set %s = ", valueTable[i].name);
|
||||
if (cliDumpPrintf(dumpMask, valueEqualsDefault(value, defaultConfig), "set %s = ", valueTable[i].name)) {
|
||||
cliPrintVar(value, 0);
|
||||
cliPrint("\r\n");
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
typedef enum {
|
||||
DUMP_MASTER = (1 << 0),
|
||||
DUMP_PROFILE = (1 << 1),
|
||||
DUMP_RATES = (1 << 2),
|
||||
DUMP_ALL = (1 << 3),
|
||||
} dumpFlags_e;
|
||||
|
||||
static const char* const sectionBreak = "\r\n";
|
||||
|
||||
#define printSectionBreak() cliPrintf((char *)sectionBreak)
|
||||
|
||||
static void cliDump(char *cmdline)
|
||||
{
|
||||
printConfig(cmdline, false);
|
||||
}
|
||||
|
||||
static void cliDiff(char *cmdline)
|
||||
{
|
||||
printConfig(cmdline, true);
|
||||
}
|
||||
|
||||
char *checkCommand(char *cmdLine, const char *command)
|
||||
{
|
||||
if(!strncasecmp(cmdLine, command, strlen(command)) // command names match
|
||||
&& !isalnum((unsigned)cmdLine[strlen(command)])) { // next characted in bufffer is not alphanumeric (command is correctly terminated)
|
||||
return cmdLine + strlen(command) + 1;
|
||||
} else {
|
||||
return 0;
|
||||
}
|
||||
}
|
||||
|
||||
static void printConfig(char *cmdline, bool doDiff)
|
||||
{
|
||||
unsigned int i;
|
||||
char buf[16];
|
||||
uint32_t mask;
|
||||
|
||||
#ifndef USE_QUAD_MIXER_ONLY
|
||||
float thr, roll, pitch, yaw;
|
||||
#endif
|
||||
uint32_t defaultMask;
|
||||
bool equalsDefault;
|
||||
|
||||
uint8_t dumpMask = DUMP_MASTER;
|
||||
if (strcasecmp(cmdline, "master") == 0) {
|
||||
char *options;
|
||||
if ((options = checkCommand(cmdline, "master"))) {
|
||||
dumpMask = DUMP_MASTER; // only
|
||||
}
|
||||
if (strcasecmp(cmdline, "profile") == 0) {
|
||||
} else if ((options = checkCommand(cmdline, "profile"))) {
|
||||
dumpMask = DUMP_PROFILE; // only
|
||||
}
|
||||
if (strcasecmp(cmdline, "rates") == 0) {
|
||||
dumpMask = DUMP_RATES;
|
||||
} else if ((options = checkCommand(cmdline, "rates"))) {
|
||||
dumpMask = DUMP_RATES; // only
|
||||
} else if ((options = checkCommand(cmdline, "all"))) {
|
||||
dumpMask = DUMP_ALL; // all profiles and rates
|
||||
}
|
||||
|
||||
if (strcasecmp(cmdline, "all") == 0) {
|
||||
dumpMask = DUMP_ALL; // All profiles and rates
|
||||
master_t defaultConfig;
|
||||
if (doDiff) {
|
||||
dumpMask = dumpMask | DO_DIFF;
|
||||
createDefaultConfig(&defaultConfig);
|
||||
}
|
||||
|
||||
if (checkCommand(options, "commented")) {
|
||||
dumpMask = dumpMask | DIFF_COMMENTED; // add unchanged values as comments for diff
|
||||
}
|
||||
|
||||
if ((dumpMask & DUMP_MASTER) || (dumpMask & DUMP_ALL)) {
|
||||
|
||||
cliPrint("\r\n# version\r\n");
|
||||
cliVersion(NULL);
|
||||
cliPrint("\r\n");
|
||||
|
||||
if ((dumpMask & (DUMP_ALL | DO_DIFF)) == (DUMP_ALL | DO_DIFF)) {
|
||||
cliPrint("\r\n# reset configuration to default settings\r\ndefaults\r\n");
|
||||
}
|
||||
|
||||
printSectionBreak();
|
||||
cliPrint("\r\n# name\r\n");
|
||||
cliName(NULL);
|
||||
cliPrint("# name\r\n");
|
||||
printName(dumpMask);
|
||||
|
||||
cliPrint("\r\n# mixer\r\n");
|
||||
|
||||
#ifndef USE_QUAD_MIXER_ONLY
|
||||
cliPrintf("mixer %s\r\n", mixerNames[masterConfig.mixerMode - 1]);
|
||||
cliDumpPrintf(dumpMask, COMPARE_CONFIG(mixerMode), "mixer %s\r\n", mixerNames[masterConfig.mixerMode - 1]);
|
||||
|
||||
cliPrintf("mmix reset\r\n");
|
||||
cliDumpPrintf(dumpMask, masterConfig.customMotorMixer[0].throttle == 0.0f, "mmix reset\r\n");
|
||||
|
||||
float thr, roll, pitch, yaw, thrDefault, rollDefault, pitchDefault, yawDefault;
|
||||
for (i = 0; i < MAX_SUPPORTED_MOTORS; i++) {
|
||||
if (masterConfig.customMotorMixer[i].throttle == 0.0f)
|
||||
break;
|
||||
|
@ -2084,7 +2350,13 @@ static void cliDump(char *cmdline)
|
|||
roll = masterConfig.customMotorMixer[i].roll;
|
||||
pitch = masterConfig.customMotorMixer[i].pitch;
|
||||
yaw = masterConfig.customMotorMixer[i].yaw;
|
||||
cliPrintf("mmix %d", i);
|
||||
thrDefault = defaultConfig.customMotorMixer[i].throttle;
|
||||
rollDefault = defaultConfig.customMotorMixer[i].roll;
|
||||
pitchDefault = defaultConfig.customMotorMixer[i].pitch;
|
||||
yawDefault = defaultConfig.customMotorMixer[i].yaw;
|
||||
equalsDefault = thr == thrDefault && roll == rollDefault && pitch == pitchDefault && yaw == yawDefault;
|
||||
|
||||
if (cliDumpPrintf(dumpMask, equalsDefault, "mmix %d", i)) {
|
||||
if (thr < 0)
|
||||
cliWrite(' ');
|
||||
cliPrintf("%s", ftoa(thr, buf));
|
||||
|
@ -2098,17 +2370,25 @@ static void cliDump(char *cmdline)
|
|||
cliWrite(' ');
|
||||
cliPrintf("%s\r\n", ftoa(yaw, buf));
|
||||
}
|
||||
}
|
||||
|
||||
#ifdef USE_SERVOS
|
||||
// print custom servo mixer if exists
|
||||
cliPrintf("smix reset\r\n");
|
||||
cliDumpPrintf(dumpMask, masterConfig.customServoMixer[i].rate == 0, "smix reset\r\n");
|
||||
|
||||
for (i = 0; i < MAX_SERVO_RULES; i++) {
|
||||
|
||||
if (masterConfig.customServoMixer[i].rate == 0)
|
||||
break;
|
||||
|
||||
cliPrintf("smix %d %d %d %d %d %d %d %d\r\n",
|
||||
equalsDefault = masterConfig.customServoMixer[i].targetChannel == defaultConfig.customServoMixer[i].targetChannel
|
||||
&& masterConfig.customServoMixer[i].inputSource == defaultConfig.customServoMixer[i].inputSource
|
||||
&& masterConfig.customServoMixer[i].rate == defaultConfig.customServoMixer[i].rate
|
||||
&& masterConfig.customServoMixer[i].speed == defaultConfig.customServoMixer[i].speed
|
||||
&& masterConfig.customServoMixer[i].min == defaultConfig.customServoMixer[i].min
|
||||
&& masterConfig.customServoMixer[i].max == defaultConfig.customServoMixer[i].max
|
||||
&& masterConfig.customServoMixer[i].box == masterConfig.customServoMixer[i].box;
|
||||
|
||||
cliDumpPrintf(dumpMask, equalsDefault,"smix %d %d %d %d %d %d %d %d\r\n",
|
||||
i,
|
||||
masterConfig.customServoMixer[i].targetChannel,
|
||||
masterConfig.customServoMixer[i].inputSource,
|
||||
|
@ -2119,102 +2399,96 @@ static void cliDump(char *cmdline)
|
|||
masterConfig.customServoMixer[i].box
|
||||
);
|
||||
}
|
||||
|
||||
#endif
|
||||
#endif
|
||||
|
||||
cliPrint("\r\n# feature\r\n");
|
||||
|
||||
mask = featureMask();
|
||||
defaultMask = defaultConfig.enabledFeatures;
|
||||
for (i = 0; ; i++) { // disable all feature first
|
||||
if (featureNames[i] == NULL)
|
||||
break;
|
||||
cliPrintf("feature -%s\r\n", featureNames[i]);
|
||||
cliDumpPrintf(dumpMask, (mask | ~defaultMask) & (1 << i), "feature -%s\r\n", featureNames[i]);
|
||||
}
|
||||
for (i = 0; ; i++) { // reenable what we want.
|
||||
if (featureNames[i] == NULL)
|
||||
break;
|
||||
if (mask & (1 << i))
|
||||
cliPrintf("feature %s\r\n", featureNames[i]);
|
||||
cliDumpPrintf(dumpMask, defaultMask & (1 << i), "feature %s\r\n", featureNames[i]);
|
||||
}
|
||||
|
||||
#ifdef BEEPER
|
||||
cliPrint("\r\n# beeper\r\n");
|
||||
uint8_t beeperCount = beeperTableEntryCount();
|
||||
mask = getBeeperOffMask();
|
||||
defaultMask = defaultConfig.beeper_off_flags;
|
||||
for (int i = 0; i < (beeperCount-2); i++) {
|
||||
if (mask & (1 << i))
|
||||
cliPrintf("beeper -%s\r\n", beeperNameForTableIndex(i));
|
||||
cliDumpPrintf(dumpMask, (~(mask ^ defaultMask) & (1 << i)), "beeper -%s\r\n", beeperNameForTableIndex(i));
|
||||
else
|
||||
cliPrintf("beeper %s\r\n", beeperNameForTableIndex(i));
|
||||
cliDumpPrintf(dumpMask, (~(mask ^ defaultMask) & (1 << i)), "beeper %s\r\n", beeperNameForTableIndex(i));
|
||||
}
|
||||
#endif
|
||||
|
||||
cliPrint("\r\n# map\r\n");
|
||||
for (i = 0; i < 8; i++)
|
||||
equalsDefault = true;
|
||||
for (i = 0; i < MAX_MAPPABLE_RX_INPUTS; i++) {
|
||||
buf[masterConfig.rxConfig.rcmap[i]] = rcChannelLetters[i];
|
||||
equalsDefault = equalsDefault && (masterConfig.rxConfig.rcmap[i] == defaultConfig.rxConfig.rcmap[i]);
|
||||
}
|
||||
buf[i] = '\0';
|
||||
cliPrintf("map %s\r\n", buf);
|
||||
cliDumpPrintf(dumpMask, equalsDefault, "map %s\r\n", buf);
|
||||
|
||||
cliPrint("\r\n# serial\r\n");
|
||||
cliSerial("");
|
||||
printSerial(dumpMask, &defaultConfig);
|
||||
|
||||
#ifdef LED_STRIP
|
||||
cliPrint("\r\n# led\r\n");
|
||||
cliLed("");
|
||||
printLed(dumpMask, &defaultConfig);
|
||||
|
||||
cliPrint("\r\n# color\r\n");
|
||||
cliColor("");
|
||||
printColor(dumpMask, &defaultConfig);
|
||||
|
||||
cliPrint("\r\n# mode_color\r\n");
|
||||
cliModeColor("");
|
||||
printModeColor(dumpMask, &defaultConfig);
|
||||
#endif
|
||||
|
||||
cliPrint("\r\n# aux\r\n");
|
||||
cliAux("");
|
||||
printAux(dumpMask, &defaultConfig);
|
||||
|
||||
cliPrint("\r\n# adjrange\r\n");
|
||||
cliAdjustmentRange("");
|
||||
printAdjustmentRange(dumpMask, &defaultConfig);
|
||||
|
||||
cliPrintf("\r\n# rxrange\r\n");
|
||||
cliRxRange("");
|
||||
printRxRange(dumpMask, &defaultConfig);
|
||||
|
||||
#ifdef USE_SERVOS
|
||||
cliPrint("\r\n# servo\r\n");
|
||||
cliServo("");
|
||||
|
||||
// print servo directions
|
||||
unsigned int channel;
|
||||
|
||||
for (i = 0; i < MAX_SUPPORTED_SERVOS; i++) {
|
||||
for (channel = 0; channel < INPUT_SOURCE_COUNT; channel++) {
|
||||
if (servoDirection(i, channel) < 0) {
|
||||
cliPrintf("smix reverse %d %d r\r\n", i , channel);
|
||||
}
|
||||
}
|
||||
}
|
||||
printServo(dumpMask, &defaultConfig);
|
||||
#endif
|
||||
|
||||
#ifdef VTX
|
||||
cliPrint("\r\n# vtx\r\n");
|
||||
cliVtx("");
|
||||
printVtx(dumpMask, &defaultConfig);
|
||||
#endif
|
||||
|
||||
cliPrint("\r\n# master\r\n");
|
||||
dumpValues(MASTER_VALUE);
|
||||
|
||||
cliPrint("\r\n# rxfail\r\n");
|
||||
cliRxFail("");
|
||||
printRxFail(dumpMask, &defaultConfig);
|
||||
|
||||
cliPrint("\r\n# master\r\n");
|
||||
dumpValues(MASTER_VALUE, dumpMask, &defaultConfig);
|
||||
|
||||
if (dumpMask & DUMP_ALL) {
|
||||
uint8_t activeProfile = masterConfig.current_profile_index;
|
||||
uint8_t profileCount;
|
||||
for (profileCount=0; profileCount<MAX_PROFILE_COUNT;profileCount++) {
|
||||
cliDumpProfile(profileCount);
|
||||
cliDumpProfile(profileCount, dumpMask, &defaultConfig);
|
||||
|
||||
uint8_t currentRateIndex = currentProfile->activeRateProfile;
|
||||
uint8_t rateCount;
|
||||
for (rateCount=0; rateCount<MAX_RATEPROFILES; rateCount++)
|
||||
cliDumpRateProfile(rateCount);
|
||||
cliDumpRateProfile(rateCount, dumpMask, &defaultConfig);
|
||||
|
||||
cliPrint("\r\n# restore original rateprofile selection\r\n");
|
||||
changeControlRateProfile(currentRateIndex);
|
||||
|
@ -2224,36 +2498,39 @@ static void cliDump(char *cmdline)
|
|||
cliPrint("\r\n# restore original profile selection\r\n");
|
||||
changeProfile(activeProfile);
|
||||
cliProfile("");
|
||||
printSectionBreak();
|
||||
|
||||
cliPrint("\r\n# save configuration\r\nsave\r\n");
|
||||
} else {
|
||||
cliDumpProfile(masterConfig.current_profile_index);
|
||||
cliDumpRateProfile(currentProfile->activeRateProfile);
|
||||
cliDumpProfile(masterConfig.current_profile_index, dumpMask, &defaultConfig);
|
||||
cliDumpRateProfile(currentProfile->activeRateProfile, dumpMask, &defaultConfig);
|
||||
}
|
||||
}
|
||||
|
||||
if (dumpMask & DUMP_PROFILE) {
|
||||
cliDumpProfile(masterConfig.current_profile_index);
|
||||
cliDumpProfile(masterConfig.current_profile_index, dumpMask, &defaultConfig);
|
||||
}
|
||||
|
||||
if (dumpMask & DUMP_RATES) {
|
||||
cliDumpRateProfile(currentProfile->activeRateProfile);
|
||||
cliDumpRateProfile(currentProfile->activeRateProfile, dumpMask, &defaultConfig);
|
||||
}
|
||||
}
|
||||
|
||||
void cliDumpProfile(uint8_t profileIndex)
|
||||
static void cliDumpProfile(uint8_t profileIndex, uint8_t dumpMask, master_t *defaultConfig)
|
||||
{
|
||||
if (profileIndex >= MAX_PROFILE_COUNT) // Faulty values
|
||||
return;
|
||||
|
||||
changeProfile(profileIndex);
|
||||
cliPrint("\r\n# profile\r\n");
|
||||
cliProfile("");
|
||||
|
||||
printSectionBreak();
|
||||
dumpValues(PROFILE_VALUE);
|
||||
dumpValues(PROFILE_VALUE, dumpMask, defaultConfig);
|
||||
|
||||
cliRateProfile("");
|
||||
}
|
||||
|
||||
void cliDumpRateProfile(uint8_t rateProfileIndex)
|
||||
static void cliDumpRateProfile(uint8_t rateProfileIndex, uint8_t dumpMask, master_t *defaultConfig)
|
||||
{
|
||||
if (rateProfileIndex >= MAX_RATEPROFILES) // Faulty values
|
||||
return;
|
||||
|
@ -2261,7 +2538,8 @@ void cliDumpRateProfile(uint8_t rateProfileIndex)
|
|||
cliPrint("\r\n# rateprofile\r\n");
|
||||
cliRateProfile("");
|
||||
printSectionBreak();
|
||||
dumpValues(PROFILE_RATE_VALUE);
|
||||
|
||||
dumpValues(PROFILE_RATE_VALUE, dumpMask, defaultConfig);
|
||||
}
|
||||
|
||||
void cliEnter(serialPort_t *serialPort)
|
||||
|
@ -2575,18 +2853,6 @@ static void cliMotor(char *cmdline)
|
|||
cliPrintf("motor %d: %d\r\n", motor_index, motor_disarmed[motor_index]);
|
||||
}
|
||||
|
||||
static void cliName(char *cmdline)
|
||||
{
|
||||
uint32_t len = strlen(cmdline);
|
||||
if (len > 0) {
|
||||
memset(masterConfig.name, 0, ARRAYLEN(masterConfig.name));
|
||||
strncpy(masterConfig.name, cmdline, MIN(len, MAX_NAME_LENGTH));
|
||||
}
|
||||
cliPrintf("name %s\r\n", strlen(masterConfig.name) > 0 ? masterConfig.name : "-");
|
||||
|
||||
return;
|
||||
}
|
||||
|
||||
static void cliPlaySound(char *cmdline)
|
||||
{
|
||||
#if FLASH_SIZE <= 64
|
||||
|
@ -2710,6 +2976,26 @@ static void cliPutp(void *p, char ch)
|
|||
bufWriterAppend(p, ch);
|
||||
}
|
||||
|
||||
static bool cliDumpPrintf(uint8_t dumpMask, bool equalsDefault, const char *format, ...)
|
||||
{
|
||||
bool printValue = !((dumpMask & DO_DIFF) && equalsDefault);
|
||||
bool printComment = (dumpMask & DIFF_COMMENTED);
|
||||
if (printValue || printComment) {
|
||||
if (printComment && !printValue) {
|
||||
cliWrite('#');
|
||||
}
|
||||
|
||||
va_list va;
|
||||
va_start(va, format);
|
||||
tfp_format(cliWriter, cliPutp, format, va);
|
||||
va_end(va);
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
return false;
|
||||
}
|
||||
|
||||
static void cliPrintf(const char *fmt, ...)
|
||||
{
|
||||
va_list va;
|
||||
|
@ -2732,14 +3018,7 @@ static void cliPrintVar(const clivalue_t *var, uint32_t full)
|
|||
int32_t value = 0;
|
||||
char buf[8];
|
||||
|
||||
void *ptr = var->ptr;
|
||||
if ((var->type & VALUE_SECTION_MASK) == PROFILE_VALUE) {
|
||||
ptr = ((uint8_t *)ptr) + (sizeof(profile_t) * masterConfig.current_profile_index);
|
||||
}
|
||||
|
||||
if ((var->type & VALUE_SECTION_MASK) == PROFILE_RATE_VALUE) {
|
||||
ptr = ((uint8_t *)ptr) + (sizeof(profile_t) * masterConfig.current_profile_index) + (sizeof(controlRateConfig_t) * getCurrentControlRateProfile());
|
||||
}
|
||||
void *ptr = getValuePointer(var);
|
||||
|
||||
switch (var->type & VALUE_TYPE_MASK) {
|
||||
case VAR_UINT8:
|
||||
|
@ -3143,13 +3422,14 @@ void cliProcess(void)
|
|||
cliBuffer[bufferIndex] = 0; // null terminate
|
||||
|
||||
const clicmd_t *cmd;
|
||||
char *options;
|
||||
for (cmd = cmdTable; cmd < cmdTable + CMD_COUNT; cmd++) {
|
||||
if(!strncasecmp(cliBuffer, cmd->name, strlen(cmd->name)) // command names match
|
||||
&& !isalnum((unsigned)cliBuffer[strlen(cmd->name)])) // next characted in bufffer is not alphanumeric (command is correctly terminated)
|
||||
if ((options = checkCommand(cliBuffer, cmd->name))) {
|
||||
break;
|
||||
}
|
||||
}
|
||||
if(cmd < cmdTable + CMD_COUNT)
|
||||
cmd->func(cliBuffer + strlen(cmd->name) + 1);
|
||||
cmd->func(options);
|
||||
else
|
||||
cliPrint("Unknown command, try 'help'");
|
||||
bufferIndex = 0;
|
||||
|
|
|
@ -91,7 +91,7 @@
|
|||
#define VBAT_ADC_PIN PA0
|
||||
#define RSSI_ADC_PIN PB0
|
||||
|
||||
#define LED_STRIP
|
||||
//#define LED_STRIP
|
||||
#define WS2811_PIN PB4
|
||||
#define WS2811_TIMER TIM3
|
||||
#define WS2811_DMA_TC_FLAG DMA1_FLAG_TC6
|
||||
|
@ -103,20 +103,20 @@
|
|||
|
||||
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
|
||||
|
||||
#define SONAR
|
||||
#define SONAR_ECHO_PIN PB0
|
||||
#define SONAR_TRIGGER_PIN PB5
|
||||
//#define SONAR
|
||||
//#define SONAR_ECHO_PIN PB0
|
||||
//#define SONAR_TRIGGER_PIN PB5
|
||||
|
||||
#undef GPS
|
||||
|
||||
#ifdef CC3D_OPBL
|
||||
//#undef LED_STRIP
|
||||
#undef LED_STRIP
|
||||
#define SKIP_CLI_COMMAND_HELP
|
||||
#define SKIP_PID_FLOAT
|
||||
#undef BARO
|
||||
#undef MAG
|
||||
#undef SONAR
|
||||
#undef LED_STRIP
|
||||
#undef USE_SOFTSERIAL1
|
||||
#endif
|
||||
|
||||
#define DEFAULT_RX_FEATURE FEATURE_RX_PPM
|
||||
|
|
|
@ -110,7 +110,7 @@
|
|||
#define SONAR_TRIGGER_PIN_PWM PB8
|
||||
#define SONAR_ECHO_PIN_PWM PB9
|
||||
|
||||
#define DISPLAY
|
||||
//#define DISPLAY
|
||||
|
||||
#define USE_UART1
|
||||
#define USE_UART2
|
||||
|
|
|
@ -81,13 +81,13 @@
|
|||
#define USE_FLASHTOOLS
|
||||
#define USE_FLASH_M25P16
|
||||
|
||||
#define SONAR
|
||||
//#define SONAR
|
||||
#define SONAR_TRIGGER_PIN PB0
|
||||
#define SONAR_ECHO_PIN PB1
|
||||
#define SONAR_TRIGGER_PIN_PWM PB8
|
||||
#define SONAR_ECHO_PIN_PWM PB9
|
||||
|
||||
#define DISPLAY
|
||||
//#define DISPLAY
|
||||
|
||||
#define USE_UART1
|
||||
#define USE_UART2
|
||||
|
@ -115,6 +115,12 @@
|
|||
#define RSSI_ADC_PIN PA1
|
||||
#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
|
||||
|
||||
// IO - stm32f103RCT6 in 64pin package
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue