1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-19 06:15:16 +03:00

Further config restructuring, moved rates to profile

This commit is contained in:
KiteAnton 2016-01-29 21:59:13 +01:00
parent 41a2a3767f
commit a24b02b90f
7 changed files with 35 additions and 120 deletions

View file

@ -1136,7 +1136,7 @@ static bool blackboxWriteSysinfo()
blackboxPrintfHeaderLine("P interval:%d/%d", masterConfig.blackbox_rate_num, masterConfig.blackbox_rate_denom); blackboxPrintfHeaderLine("P interval:%d/%d", masterConfig.blackbox_rate_num, masterConfig.blackbox_rate_denom);
break; break;
case 4: case 4:
blackboxPrintfHeaderLine("rcRate:%d", masterConfig.controlRateProfiles[masterConfig.current_profile_index].rcRate8); blackboxPrintfHeaderLine("rcRate:%d", masterConfig.profile[masterConfig.current_profile_index].controlRateProfile.rcRate8);
break; break;
case 5: case 5:
blackboxPrintfHeaderLine("minthrottle:%d", masterConfig.escAndServoConfig.minthrottle); blackboxPrintfHeaderLine("minthrottle:%d", masterConfig.escAndServoConfig.minthrottle);

View file

@ -347,6 +347,7 @@ uint8_t getCurrentProfile(void)
static void setProfile(uint8_t profileIndex) static void setProfile(uint8_t profileIndex)
{ {
currentProfile = &masterConfig.profile[profileIndex]; currentProfile = &masterConfig.profile[profileIndex];
currentControlRateProfile = &currentProfile->controlRateProfile;
} }
uint8_t getCurrentControlRateProfile(void) uint8_t getCurrentControlRateProfile(void)
@ -355,13 +356,7 @@ uint8_t getCurrentControlRateProfile(void)
} }
controlRateConfig_t *getControlRateConfig(uint8_t profileIndex) { controlRateConfig_t *getControlRateConfig(uint8_t profileIndex) {
return &masterConfig.controlRateProfiles[profileIndex]; return &masterConfig.profile[profileIndex].controlRateProfile;
}
static void setControlRateProfile(uint8_t profileIndex)
{
currentControlRateProfileIndex = profileIndex;
currentControlRateProfile = &masterConfig.controlRateProfiles[profileIndex];
} }
uint16_t getCurrentMinthrottle(void) uint16_t getCurrentMinthrottle(void)
@ -377,7 +372,6 @@ static void resetConf(void)
// Clear all configuration // Clear all configuration
memset(&masterConfig, 0, sizeof(master_t)); memset(&masterConfig, 0, sizeof(master_t));
setProfile(0); setProfile(0);
setControlRateProfile(0);
masterConfig.beeper_off.flags = BEEPER_OFF_FLAGS_MIN; masterConfig.beeper_off.flags = BEEPER_OFF_FLAGS_MIN;
masterConfig.version = EEPROM_CONF_VERSION; masterConfig.version = EEPROM_CONF_VERSION;
@ -490,7 +484,7 @@ static void resetConf(void)
resetPidProfile(&currentProfile->pidProfile); resetPidProfile(&currentProfile->pidProfile);
resetControlRateConfig(&masterConfig.controlRateProfiles[0]); resetControlRateConfig(&masterConfig.profile[0].controlRateProfile);
resetRollAndPitchTrims(&masterConfig.accelerometerTrims); resetRollAndPitchTrims(&masterConfig.accelerometerTrims);
@ -704,14 +698,6 @@ static void resetConf(void)
memcpy(&masterConfig.profile[i], currentProfile, sizeof(profile_t)); memcpy(&masterConfig.profile[i], currentProfile, sizeof(profile_t));
} }
// copy first control rate config into remaining profile
for (i = 1; i < MAX_CONTROL_RATE_PROFILE_COUNT; i++) {
memcpy(&masterConfig.controlRateProfiles[i], currentControlRateProfile, sizeof(controlRateConfig_t));
}
for (i = 1; i < MAX_PROFILE_COUNT; i++) {
masterConfig.profile[i].defaultRateProfileIndex = i % MAX_CONTROL_RATE_PROFILE_COUNT;
}
} }
static uint8_t calculateChecksum(const uint8_t *data, uint32_t length) static uint8_t calculateChecksum(const uint8_t *data, uint32_t length)
@ -948,11 +934,6 @@ void readEEPROM(void)
setProfile(masterConfig.current_profile_index); setProfile(masterConfig.current_profile_index);
if (currentProfile->defaultRateProfileIndex > MAX_CONTROL_RATE_PROFILE_COUNT - 1) // sanity check
currentProfile->defaultRateProfileIndex = 0;
setControlRateProfile(currentProfile->defaultRateProfileIndex);
validateAndFixConfig(); validateAndFixConfig();
activateConfig(); activateConfig();
@ -1051,15 +1032,6 @@ void changeProfile(uint8_t profileIndex)
beeperConfirmationBeeps(profileIndex + 1); beeperConfirmationBeeps(profileIndex + 1);
} }
void changeControlRateProfile(uint8_t profileIndex)
{
if (profileIndex > MAX_CONTROL_RATE_PROFILE_COUNT) {
profileIndex = MAX_CONTROL_RATE_PROFILE_COUNT - 1;
}
setControlRateProfile(profileIndex);
activateControlRateConfig();
}
void handleOneshotFeatureChangeOnRestart(void) void handleOneshotFeatureChangeOnRestart(void)
{ {
// Shutdown PWM on all motors prior to soft restart // Shutdown PWM on all motors prior to soft restart

View file

@ -18,7 +18,6 @@
#pragma once #pragma once
#define MAX_PROFILE_COUNT 2 #define MAX_PROFILE_COUNT 2
#define MAX_CONTROL_RATE_PROFILE_COUNT 3
#define ONESHOT_FEATURE_CHANGED_DELAY_ON_BOOT_MS 1500 #define ONESHOT_FEATURE_CHANGED_DELAY_ON_BOOT_MS 1500
typedef enum { typedef enum {
@ -68,7 +67,6 @@ uint8_t getCurrentProfile(void);
void changeProfile(uint8_t profileIndex); void changeProfile(uint8_t profileIndex);
uint8_t getCurrentControlRateProfile(void); uint8_t getCurrentControlRateProfile(void);
void changeControlRateProfile(uint8_t profileIndex);
bool canSoftwareSerialBeUsed(void); bool canSoftwareSerialBeUsed(void);

View file

@ -27,23 +27,30 @@ typedef struct master_t {
uint32_t enabledFeatures; uint32_t enabledFeatures;
uint8_t emf_avoidance; // change pll settings to avoid noise in the uhf band uint8_t emf_avoidance; // change pll settings to avoid noise in the uhf band
motorMixer_t customMotorMixer[MAX_SUPPORTED_MOTORS]; beeperOffConditions_t beeper_off;
#ifdef USE_SERVOS
servoMixer_t customServoMixer[MAX_SERVO_RULES];
#endif
// motor/esc/servo related stuff // motor/esc/servo related stuff
motorMixer_t customMotorMixer[MAX_SUPPORTED_MOTORS];
escAndServoConfig_t escAndServoConfig; escAndServoConfig_t escAndServoConfig;
flight3DConfig_t flight3DConfig; flight3DConfig_t flight3DConfig;
uint16_t motor_pwm_rate; // The update rate of motor outputs (50-498Hz) uint16_t motor_pwm_rate; // The update rate of motor outputs (50-498Hz)
uint16_t servo_pwm_rate; // The update rate of servo outputs (50-498Hz) uint16_t servo_pwm_rate; // The update rate of servo outputs (50-498Hz)
uint8_t use_fast_pwm; // Use fast PWM implementation when oneshot enabled uint8_t use_fast_pwm; // Use fast PWM implementation when oneshot enabled
#ifdef USE_SERVOS
servoMixer_t customServoMixer[MAX_SERVO_RULES];
// Servo-related stuff
servoParam_t servoConf[MAX_SUPPORTED_SERVOS]; // servo configuration
// gimbal-related configuration
gimbalConfig_t gimbalConfig;
#endif
#ifdef CC3D #ifdef CC3D
uint8_t use_buzzer_p6; uint8_t use_buzzer_p6;
#endif #endif
// global sensor-related stuff // global sensor-related stuff
sensorAlignmentConfig_t sensorAlignmentConfig; sensorAlignmentConfig_t sensorAlignmentConfig;
boardAlignment_t boardAlignment; boardAlignment_t boardAlignment;
@ -59,51 +66,35 @@ typedef struct master_t {
uint8_t mag_hardware; // Which mag hardware to use on boards with more than one device uint8_t mag_hardware; // Which mag hardware to use on boards with more than one device
uint8_t baro_hardware; // Barometer hardware to use uint8_t baro_hardware; // Barometer hardware to use
int16_t mag_declination; // Get your magnetic decliniation from here : http://magnetic-declination.com/ int16_t mag_declination; // Get your magnetic decliniation from here : http://magnetic-declination.com/
// For example, -6deg 37min, = -637 Japan, format is [sign]dddmm (degreesminutes) default is zero. // For example, -6deg 37min, = -637 Japan, format is [sign]dddmm (degreesminutes) default is zero.
rollAndPitchTrims_t accelerometerTrims; // accelerometer trim rollAndPitchTrims_t accelerometerTrims; // accelerometer trim
// sensor-related stuff
uint8_t acc_lpf_hz; // Set the Low Pass Filter factor for ACC. Reducing this value would reduce ACC noise (visible in GUI), but would increase ACC lag time. Zero = no filter uint8_t acc_lpf_hz; // Set the Low Pass Filter factor for ACC. Reducing this value would reduce ACC noise (visible in GUI), but would increase ACC lag time. Zero = no filter
float accz_lpf_cutoff; // cutoff frequency for the low pass filter used on the acc z-axis for althold in Hz float accz_lpf_cutoff; // cutoff frequency for the low pass filter used on the acc z-axis for althold in Hz
accDeadband_t accDeadband; accDeadband_t accDeadband;
barometerConfig_t barometerConfig; barometerConfig_t barometerConfig;
uint8_t acc_unarmedcal; // turn automatic acc compensation on/off uint8_t acc_unarmedcal; // turn automatic acc compensation on/off
uint16_t throttle_correction_angle; // the angle when the throttle correction is maximal. in 0.1 degres, ex 225 = 22.5 ,30.0, 450 = 45.0 deg uint16_t throttle_correction_angle; // the angle when the throttle correction is maximal. in 0.1 degres, ex 225 = 22.5 ,30.0, 450 = 45.0 deg
uint8_t throttle_correction_value; // the correction that will be applied at throttle_correction_angle. uint8_t throttle_correction_value; // the correction that will be applied at throttle_correction_angle.
batteryConfig_t batteryConfig;
// Radio/ESC-related configuration // Radio/ESC-related configuration
rcControlsConfig_t rcControlsConfig; rcControlsConfig_t rcControlsConfig;
#ifdef USE_SERVOS
// Servo-related stuff
servoParam_t servoConf[MAX_SUPPORTED_SERVOS]; // servo configuration
// gimbal-related configuration
gimbalConfig_t gimbalConfig;
#endif
#ifdef GPS #ifdef GPS
gpsProfile_t gpsProfile; gpsProfile_t gpsProfile;
#endif #endif
uint16_t max_angle_inclination; // max inclination allowed in angle (level) mode. default 500 (50 degrees). uint16_t max_angle_inclination; // max inclination allowed in angle (level) mode. default 500 (50 degrees).
flightDynamicsTrims_t accZero; flightDynamicsTrims_t accZero;
flightDynamicsTrims_t magZero; flightDynamicsTrims_t magZero;
batteryConfig_t batteryConfig;
rxConfig_t rxConfig; rxConfig_t rxConfig;
inputFilteringMode_e inputFilteringMode; // Use hardware input filtering, e.g. for OrangeRX PPM/PWM receivers. inputFilteringMode_e inputFilteringMode; // Use hardware input filtering, e.g. for OrangeRX PPM/PWM receivers.
failsafeConfig_t failsafeConfig;
uint8_t retarded_arm; // allow disarm/arm on throttle down + roll left/right uint8_t retarded_arm; // allow disarm/arm on throttle down + roll left/right
uint8_t disarm_kill_switch; // allow disarm via AUX switch regardless of throttle value uint8_t disarm_kill_switch; // allow disarm via AUX switch regardless of throttle value
@ -112,15 +103,14 @@ typedef struct master_t {
// mixer-related configuration // mixer-related configuration
mixerConfig_t mixerConfig; mixerConfig_t mixerConfig;
airplaneConfig_t airplaneConfig; airplaneConfig_t airplaneConfig;
#ifdef GPS #ifdef GPS
gpsConfig_t gpsConfig; gpsConfig_t gpsConfig;
#endif #endif
failsafeConfig_t failsafeConfig;
serialConfig_t serialConfig; serialConfig_t serialConfig;
telemetryConfig_t telemetryConfig; telemetryConfig_t telemetryConfig;
#ifdef LED_STRIP #ifdef LED_STRIP
@ -134,7 +124,7 @@ typedef struct master_t {
profile_t profile[MAX_PROFILE_COUNT]; profile_t profile[MAX_PROFILE_COUNT];
uint8_t current_profile_index; uint8_t current_profile_index;
controlRateConfig_t controlRateProfiles[MAX_CONTROL_RATE_PROFILE_COUNT];
modeActivationCondition_t modeActivationConditions[MAX_MODE_ACTIVATION_CONDITION_COUNT]; modeActivationCondition_t modeActivationConditions[MAX_MODE_ACTIVATION_CONDITION_COUNT];
adjustmentRange_t adjustmentRanges[MAX_ADJUSTMENT_RANGE_COUNT]; adjustmentRange_t adjustmentRanges[MAX_ADJUSTMENT_RANGE_COUNT];
@ -144,8 +134,6 @@ typedef struct master_t {
uint8_t blackbox_device; uint8_t blackbox_device;
#endif #endif
beeperOffConditions_t beeper_off;
uint8_t magic_ef; // magic number, should be 0xEF uint8_t magic_ef; // magic number, should be 0xEF
uint8_t chk; // XOR checksum uint8_t chk; // XOR checksum
} master_t; } master_t;

View file

@ -19,5 +19,5 @@
typedef struct profile_s { typedef struct profile_s {
pidProfile_t pidProfile; pidProfile_t pidProfile;
uint8_t defaultRateProfileIndex; controlRateConfig_t controlRateProfile;
} profile_t; } profile_t;

View file

@ -651,8 +651,7 @@ void applyStepAdjustment(controlRateConfig_t *controlRateConfig, uint8_t adjustm
}; };
} }
void changeControlRateProfile(uint8_t profileIndex); /* Is this needed ?
void applySelectAdjustment(uint8_t adjustmentFunction, uint8_t position) void applySelectAdjustment(uint8_t adjustmentFunction, uint8_t position)
{ {
bool applied = false; bool applied = false;
@ -660,7 +659,7 @@ void applySelectAdjustment(uint8_t adjustmentFunction, uint8_t position)
switch(adjustmentFunction) { switch(adjustmentFunction) {
case ADJUSTMENT_RATE_PROFILE: case ADJUSTMENT_RATE_PROFILE:
if (getCurrentControlRateProfile() != position) { if (getCurrentControlRateProfile() != position) {
changeControlRateProfile(position); changeProfile(position); // Is this safe to change profile "in flight" ?
blackboxLogInflightAdjustmentEvent(ADJUSTMENT_RATE_PROFILE, position); blackboxLogInflightAdjustmentEvent(ADJUSTMENT_RATE_PROFILE, position);
applied = true; applied = true;
} }
@ -671,7 +670,7 @@ void applySelectAdjustment(uint8_t adjustmentFunction, uint8_t position)
beeperConfirmationBeeps(position + 1); beeperConfirmationBeeps(position + 1);
} }
} }
*/
#define RESET_FREQUENCY_2HZ (1000 / 2) #define RESET_FREQUENCY_2HZ (1000 / 2)
void processRcAdjustments(controlRateConfig_t *controlRateConfig, rxConfig_t *rxConfig) void processRcAdjustments(controlRateConfig_t *controlRateConfig, rxConfig_t *rxConfig)
@ -728,7 +727,7 @@ void processRcAdjustments(controlRateConfig_t *controlRateConfig, rxConfig_t *rx
uint16_t rangeWidth = ((2100 - 900) / adjustmentState->config->data.selectConfig.switchPositions); uint16_t rangeWidth = ((2100 - 900) / adjustmentState->config->data.selectConfig.switchPositions);
uint8_t position = (constrain(rcData[channelIndex], 900, 2100 - 1) - 900) / rangeWidth; uint8_t position = (constrain(rcData[channelIndex], 900, 2100 - 1) - 900) / rangeWidth;
applySelectAdjustment(adjustmentFunction, position); // applySelectAdjustment(adjustmentFunction, position);
} }
MARK_ADJUSTMENT_FUNCTION_AS_BUSY(adjustmentIndex); MARK_ADJUSTMENT_FUNCTION_AS_BUSY(adjustmentIndex);
} }

View file

@ -113,7 +113,6 @@ static void cliFeature(char *cmdline);
static void cliMotor(char *cmdline); static void cliMotor(char *cmdline);
static void cliPlaySound(char *cmdline); static void cliPlaySound(char *cmdline);
static void cliProfile(char *cmdline); static void cliProfile(char *cmdline);
static void cliRateProfile(char *cmdline);
static void cliReboot(void); static void cliReboot(void);
static void cliSave(char *cmdline); static void cliSave(char *cmdline);
static void cliSerial(char *cmdline); static void cliSerial(char *cmdline);
@ -280,8 +279,6 @@ const clicmd_t cmdTable[] = {
"[<index>]\r\n", cliPlaySound), "[<index>]\r\n", cliPlaySound),
CLI_COMMAND_DEF("profile", "change profile", CLI_COMMAND_DEF("profile", "change profile",
"[<index>]", cliProfile), "[<index>]", cliProfile),
CLI_COMMAND_DEF("rateprofile", "change rate profile",
"[<index>]", cliRateProfile),
CLI_COMMAND_DEF("rxrange", "configure rx channel ranges", NULL, cliRxRange), CLI_COMMAND_DEF("rxrange", "configure rx channel ranges", NULL, cliRxRange),
CLI_COMMAND_DEF("rxfail", "show/set rx failsafe settings", NULL, cliRxFail), CLI_COMMAND_DEF("rxfail", "show/set rx failsafe settings", NULL, cliRxFail),
CLI_COMMAND_DEF("save", "save and reboot", NULL, cliSave), CLI_COMMAND_DEF("save", "save and reboot", NULL, cliSave),
@ -464,7 +461,6 @@ typedef enum {
// value section // value section
MASTER_VALUE = (0 << VALUE_SECTION_OFFSET), MASTER_VALUE = (0 << VALUE_SECTION_OFFSET),
PROFILE_VALUE = (1 << VALUE_SECTION_OFFSET), PROFILE_VALUE = (1 << VALUE_SECTION_OFFSET),
CONTROL_RATE_VALUE = (2 << VALUE_SECTION_OFFSET),
// value mode // value mode
MODE_DIRECT = (0 << VALUE_MODE_OFFSET), MODE_DIRECT = (0 << VALUE_MODE_OFFSET),
@ -624,17 +620,16 @@ const clivalue_t valueTable[] = {
{ "servo_lowpass_enable", VAR_INT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.mixerConfig.servo_lowpass_enable, .config.lookup = { TABLE_OFF_ON } }, { "servo_lowpass_enable", VAR_INT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.mixerConfig.servo_lowpass_enable, .config.lookup = { TABLE_OFF_ON } },
#endif #endif
{ "default_rate_profile", VAR_UINT8 | PROFILE_VALUE , &masterConfig.profile[0].defaultRateProfileIndex, .config.minmax = { 0, MAX_CONTROL_RATE_PROFILE_COUNT - 1 } }, { "rc_rate", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].controlRateProfile.rcRate8, .config.minmax = { 0, 250 } },
{ "rc_rate", VAR_UINT8 | CONTROL_RATE_VALUE, &masterConfig.controlRateProfiles[0].rcRate8, .config.minmax = { 0, 250 } }, { "rc_expo", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].controlRateProfile.rcExpo8, .config.minmax = { 0, 100 } },
{ "rc_expo", VAR_UINT8 | CONTROL_RATE_VALUE, &masterConfig.controlRateProfiles[0].rcExpo8, .config.minmax = { 0, 100 } }, { "rc_yaw_expo", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].controlRateProfile.rcYawExpo8, .config.minmax = { 0, 100 } },
{ "rc_yaw_expo", VAR_UINT8 | CONTROL_RATE_VALUE, &masterConfig.controlRateProfiles[0].rcYawExpo8, .config.minmax = { 0, 100 } }, { "thr_mid", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].controlRateProfile.thrMid8, .config.minmax = { 0, 100 } },
{ "thr_mid", VAR_UINT8 | CONTROL_RATE_VALUE, &masterConfig.controlRateProfiles[0].thrMid8, .config.minmax = { 0, 100 } }, { "thr_expo", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].controlRateProfile.thrExpo8, .config.minmax = { 0, 100 } },
{ "thr_expo", VAR_UINT8 | CONTROL_RATE_VALUE, &masterConfig.controlRateProfiles[0].thrExpo8, .config.minmax = { 0, 100 } }, { "roll_rate", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].controlRateProfile.rates[FD_ROLL], .config.minmax = { 0, CONTROL_RATE_CONFIG_ROLL_PITCH_RATE_MAX } },
{ "roll_rate", VAR_UINT8 | CONTROL_RATE_VALUE, &masterConfig.controlRateProfiles[0].rates[FD_ROLL], .config.minmax = { 0, CONTROL_RATE_CONFIG_ROLL_PITCH_RATE_MAX } }, { "pitch_rate", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].controlRateProfile.rates[FD_PITCH], .config.minmax = { 0, CONTROL_RATE_CONFIG_ROLL_PITCH_RATE_MAX } },
{ "pitch_rate", VAR_UINT8 | CONTROL_RATE_VALUE, &masterConfig.controlRateProfiles[0].rates[FD_PITCH], .config.minmax = { 0, CONTROL_RATE_CONFIG_ROLL_PITCH_RATE_MAX } }, { "yaw_rate", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].controlRateProfile.rates[FD_YAW], .config.minmax = { 0, CONTROL_RATE_CONFIG_YAW_RATE_MAX } },
{ "yaw_rate", VAR_UINT8 | CONTROL_RATE_VALUE, &masterConfig.controlRateProfiles[0].rates[FD_YAW], .config.minmax = { 0, CONTROL_RATE_CONFIG_YAW_RATE_MAX } }, { "tpa_rate", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].controlRateProfile.dynThrPID, .config.minmax = { 0, CONTROL_RATE_CONFIG_TPA_MAX} },
{ "tpa_rate", VAR_UINT8 | CONTROL_RATE_VALUE, &masterConfig.controlRateProfiles[0].dynThrPID, .config.minmax = { 0, CONTROL_RATE_CONFIG_TPA_MAX} }, { "tpa_breakpoint", VAR_UINT16 | PROFILE_VALUE, &masterConfig.profile[0].controlRateProfile.tpa_breakpoint, .config.minmax = { PWM_RANGE_MIN, PWM_RANGE_MAX} },
{ "tpa_breakpoint", VAR_UINT16 | CONTROL_RATE_VALUE, &masterConfig.controlRateProfiles[0].tpa_breakpoint, .config.minmax = { PWM_RANGE_MIN, PWM_RANGE_MAX} },
{ "failsafe_delay", VAR_UINT8 | MASTER_VALUE, &masterConfig.failsafeConfig.failsafe_delay, .config.minmax = { 0, 200 } }, { "failsafe_delay", VAR_UINT8 | MASTER_VALUE, &masterConfig.failsafeConfig.failsafe_delay, .config.minmax = { 0, 200 } },
{ "failsafe_off_delay", VAR_UINT8 | MASTER_VALUE, &masterConfig.failsafeConfig.failsafe_off_delay, .config.minmax = { 0, 200 } }, { "failsafe_off_delay", VAR_UINT8 | MASTER_VALUE, &masterConfig.failsafeConfig.failsafe_off_delay, .config.minmax = { 0, 200 } },
@ -1668,10 +1663,9 @@ static void dumpValues(uint16_t valueSection)
typedef enum { typedef enum {
DUMP_MASTER = (1 << 0), DUMP_MASTER = (1 << 0),
DUMP_PROFILE = (1 << 1), DUMP_PROFILE = (1 << 1),
DUMP_CONTROL_RATE_PROFILE = (1 << 2)
} dumpFlags_e; } dumpFlags_e;
#define DUMP_ALL (DUMP_MASTER | DUMP_PROFILE | DUMP_CONTROL_RATE_PROFILE) #define DUMP_ALL (DUMP_MASTER | DUMP_PROFILE)
static const char* const sectionBreak = "\r\n"; static const char* const sectionBreak = "\r\n";
@ -1695,9 +1689,6 @@ static void cliDump(char *cmdline)
if (strcasecmp(cmdline, "profile") == 0) { if (strcasecmp(cmdline, "profile") == 0) {
dumpMask = DUMP_PROFILE; // only dumpMask = DUMP_PROFILE; // only
} }
if (strcasecmp(cmdline, "rates") == 0) {
dumpMask = DUMP_CONTROL_RATE_PROFILE; // only
}
if (dumpMask & DUMP_MASTER) { if (dumpMask & DUMP_MASTER) {
@ -1834,17 +1825,6 @@ static void cliDump(char *cmdline)
dumpValues(PROFILE_VALUE); dumpValues(PROFILE_VALUE);
} }
if (dumpMask & DUMP_CONTROL_RATE_PROFILE) {
cliPrint("\r\n# dump rates\r\n");
cliPrint("\r\n# rateprofile\r\n");
cliRateProfile("");
printSectionBreak();
dumpValues(CONTROL_RATE_VALUE);
}
} }
void cliEnter(serialPort_t *serialPort) void cliEnter(serialPort_t *serialPort)
@ -2139,22 +2119,6 @@ static void cliProfile(char *cmdline)
} }
} }
static void cliRateProfile(char *cmdline)
{
int i;
if (isEmpty(cmdline)) {
cliPrintf("rateprofile %d\r\n", getCurrentControlRateProfile());
return;
} else {
i = atoi(cmdline);
if (i >= 0 && i < MAX_CONTROL_RATE_PROFILE_COUNT) {
changeControlRateProfile(i);
cliRateProfile("");
}
}
}
static void cliReboot(void) { static void cliReboot(void) {
cliPrint("\r\nRebooting"); cliPrint("\r\nRebooting");
waitForSerialPortToFinishTransmitting(cliPort); waitForSerialPortToFinishTransmitting(cliPort);
@ -2216,9 +2180,6 @@ static void cliPrintVar(const clivalue_t *var, uint32_t full)
if ((var->type & VALUE_SECTION_MASK) == PROFILE_VALUE) { if ((var->type & VALUE_SECTION_MASK) == PROFILE_VALUE) {
ptr = ((uint8_t *)ptr) + (sizeof(profile_t) * masterConfig.current_profile_index); ptr = ((uint8_t *)ptr) + (sizeof(profile_t) * masterConfig.current_profile_index);
} }
if ((var->type & VALUE_SECTION_MASK) == CONTROL_RATE_VALUE) {
ptr = ((uint8_t *)ptr) + (sizeof(controlRateConfig_t) * getCurrentControlRateProfile());
}
switch (var->type & VALUE_TYPE_MASK) { switch (var->type & VALUE_TYPE_MASK) {
case VAR_UINT8: case VAR_UINT8:
@ -2269,9 +2230,6 @@ static void cliSetVar(const clivalue_t *var, const int_float_value_t value)
if ((var->type & VALUE_SECTION_MASK) == PROFILE_VALUE) { if ((var->type & VALUE_SECTION_MASK) == PROFILE_VALUE) {
ptr = ((uint8_t *)ptr) + (sizeof(profile_t) * masterConfig.current_profile_index); ptr = ((uint8_t *)ptr) + (sizeof(profile_t) * masterConfig.current_profile_index);
} }
if ((var->type & VALUE_SECTION_MASK) == CONTROL_RATE_VALUE) {
ptr = ((uint8_t *)ptr) + (sizeof(controlRateConfig_t) * getCurrentControlRateProfile());
}
switch (var->type & VALUE_TYPE_MASK) { switch (var->type & VALUE_TYPE_MASK) {
case VAR_UINT8: case VAR_UINT8: