1
0
Fork 0
mirror of https://github.com/iNavFlight/inav.git synced 2025-07-26 09:45:33 +03:00

From profile to master

This commit is contained in:
Sami Korhonen 2017-01-01 11:57:54 +02:00
parent 308e1acc99
commit 37c3b2213f
8 changed files with 137 additions and 138 deletions

View file

@ -1003,7 +1003,7 @@ void startBlackbox(void)
*/
blackboxBuildConditionCache();
blackboxModeActivationConditionPresent = isModeActivationConditionPresent(currentProfile->modeActivationConditions, BOXBLACKBOX);
blackboxModeActivationConditionPresent = isModeActivationConditionPresent(masterConfig.modeActivationConditions, BOXBLACKBOX);
blackboxIteration = 0;
blackboxPFrameIndex = 0;
@ -1377,8 +1377,8 @@ static bool blackboxWriteSysinfo()
BLACKBOX_PRINT_HEADER_LINE("yaw_p_limit:%d", masterConfig.profile[masterConfig.current_profile_index].pidProfile.yaw_p_limit);
BLACKBOX_PRINT_HEADER_LINE("yaw_lpf_hz:%d", (int)(masterConfig.profile[masterConfig.current_profile_index].pidProfile.yaw_lpf_hz * 100.0f));
BLACKBOX_PRINT_HEADER_LINE("dterm_lpf_hz:%d", (int)(masterConfig.profile[masterConfig.current_profile_index].pidProfile.dterm_lpf_hz * 100.0f));
BLACKBOX_PRINT_HEADER_LINE("deadband:%d", masterConfig.profile[masterConfig.current_profile_index].rcControlsConfig.deadband);
BLACKBOX_PRINT_HEADER_LINE("yaw_deadband:%d", masterConfig.profile[masterConfig.current_profile_index].rcControlsConfig.yaw_deadband);
BLACKBOX_PRINT_HEADER_LINE("deadband:%d", masterConfig.rcControlsConfig.deadband);
BLACKBOX_PRINT_HEADER_LINE("yaw_deadband:%d", masterConfig.rcControlsConfig.yaw_deadband);
BLACKBOX_PRINT_HEADER_LINE("gyro_lpf:%d", gyroConfig()->gyro_lpf);
BLACKBOX_PRINT_HEADER_LINE("gyro_lowpass_hz:%d", (int)(masterConfig.profile[masterConfig.current_profile_index].pidProfile.gyro_soft_lpf_hz * 100.0f));
BLACKBOX_PRINT_HEADER_LINE("acc_lpf_hz:%d", (int)(masterConfig.profile[masterConfig.current_profile_index].pidProfile.acc_soft_lpf_hz * 100.0f));

View file

@ -611,7 +611,7 @@ void createDefaultConfig(master_t *config)
config->compassConfig.mag_declination = 0;
config->profile[0].modeActivationOperator = MODE_OPERATOR_OR; // default is to OR multiple-channel mode activation conditions
config->modeActivationOperator = MODE_OPERATOR_OR; // default is to OR multiple-channel mode activation conditions
resetBarometerConfig(&config->barometerConfig);
resetPitotmeterConfig(&config->pitotmeterConfig);
@ -623,9 +623,9 @@ void createDefaultConfig(master_t *config)
parseRcChannels("AETR1234", &config->rxConfig);
#endif
resetRcControlsConfig(&config->profile[0].rcControlsConfig);
resetRcControlsConfig(&config->rcControlsConfig);
config->profile[0].throttle_tilt_compensation_strength = 0; // 0-100, 0 - disabled
config->throttle_tilt_compensation_strength = 0; // 0-100, 0 - disabled
// Failsafe Variables
config->failsafeConfig.failsafe_delay = 5; // 0.5 sec
@ -639,20 +639,20 @@ void createDefaultConfig(master_t *config)
#ifdef USE_SERVOS
// servos
for (int i = 0; i < MAX_SUPPORTED_SERVOS; i++) {
config->profile[0].servoConf[i].min = DEFAULT_SERVO_MIN;
config->profile[0].servoConf[i].max = DEFAULT_SERVO_MAX;
config->profile[0].servoConf[i].middle = DEFAULT_SERVO_MIDDLE;
config->profile[0].servoConf[i].rate = 100;
config->profile[0].servoConf[i].angleAtMin = DEFAULT_SERVO_MIN_ANGLE;
config->profile[0].servoConf[i].angleAtMax = DEFAULT_SERVO_MAX_ANGLE;
config->profile[0].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
config->profile[0].gimbalConfig.mode = GIMBAL_MODE_NORMAL;
config->gimbalConfig.mode = GIMBAL_MODE_NORMAL;
config->profile[0].flaperon_throw_offset = FLAPERON_THROW_DEFAULT;
config->profile[0].flaperon_throw_inverted = 0;
config->flaperon_throw_offset = FLAPERON_THROW_DEFAULT;
config->flaperon_throw_inverted = 0;
#endif
@ -794,7 +794,7 @@ void activateConfig(void)
resetAdjustmentStates();
useRcControlsConfig(
currentProfile->modeActivationConditions,
masterConfig.modeActivationConditions,
&masterConfig.motorConfig,
&currentProfile->pidProfile
);
@ -812,7 +812,7 @@ void activateConfig(void)
mixerUseConfigs(&masterConfig.flight3DConfig, &masterConfig.motorConfig, &masterConfig.mixerConfig, &masterConfig.rxConfig);
#ifdef USE_SERVOS
servosUseConfigs(&masterConfig.servoMixerConfig, currentProfile->servoConf, &currentProfile->gimbalConfig, &masterConfig.rxConfig);
servosUseConfigs(&masterConfig.servoMixerConfig, masterConfig.servoConf, &masterConfig.gimbalConfig, &masterConfig.rxConfig);
#endif
imuConfigure(&masterConfig.imuConfig, &currentProfile->pidProfile);
@ -822,7 +822,7 @@ void activateConfig(void)
#ifdef NAV
navigationUseConfig(&masterConfig.navConfig);
navigationUsePIDs(&currentProfile->pidProfile);
navigationUseRcControlsConfig(&currentProfile->rcControlsConfig);
navigationUseRcControlsConfig(&masterConfig.rcControlsConfig);
navigationUseRxConfig(&masterConfig.rxConfig);
navigationUseFlight3DConfig(&masterConfig.flight3DConfig);
navigationUsemotorConfig(&masterConfig.motorConfig);

View file

@ -116,6 +116,28 @@ typedef struct master_s {
servoConfig_t servoConfig;
servoMixerConfig_t servoMixerConfig;
servoMixer_t customServoMixer[MAX_SERVO_RULES];
#endif
modeActivationCondition_t modeActivationConditions[MAX_MODE_ACTIVATION_CONDITION_COUNT];
modeActivationOperator_e modeActivationOperator;
adjustmentRange_t adjustmentRanges[MAX_ADJUSTMENT_RANGE_COUNT];
// Radio/ESC-related configuration
rcControlsConfig_t rcControlsConfig;
uint8_t throttle_tilt_compensation_strength; // the correction that will be applied at throttle_correction_angle.
#ifdef USE_SERVOS
// Servo-related stuff
servoParam_t servoConf[MAX_SUPPORTED_SERVOS]; // servo configuration
// gimbal-related configuration
gimbalConfig_t gimbalConfig;
uint16_t flaperon_throw_offset;
uint8_t flaperon_throw_inverted;
#endif
boardAlignment_t boardAlignment;

View file

@ -31,25 +31,5 @@ typedef struct profile_s {
uint8_t defaultRateProfileIndex;
modeActivationCondition_t modeActivationConditions[MAX_MODE_ACTIVATION_CONDITION_COUNT];
modeActivationOperator_e modeActivationOperator;
adjustmentRange_t adjustmentRanges[MAX_ADJUSTMENT_RANGE_COUNT];
// Radio/ESC-related configuration
rcControlsConfig_t rcControlsConfig;
uint8_t throttle_tilt_compensation_strength; // the correction that will be applied at throttle_correction_angle.
#ifdef USE_SERVOS
// Servo-related stuff
servoParam_t servoConf[MAX_SUPPORTED_SERVOS]; // servo configuration
// gimbal-related configuration
gimbalConfig_t gimbalConfig;
uint16_t flaperon_throw_offset;
uint8_t flaperon_throw_inverted;
#endif
} profile_t;

View file

@ -512,7 +512,7 @@ void init(void)
failsafeInit(&masterConfig.rxConfig, flight3DConfig()->deadband3d_throttle);
rxInit(&masterConfig.rxConfig, currentProfile->modeActivationConditions);
rxInit(&masterConfig.rxConfig, masterConfig.modeActivationConditions);
#ifdef GPS
if (feature(FEATURE_GPS)) {
@ -529,7 +529,7 @@ void init(void)
navigationInit(
&masterConfig.navConfig,
&currentProfile->pidProfile,
&currentProfile->rcControlsConfig,
&masterConfig.rcControlsConfig,
&masterConfig.rxConfig,
&masterConfig.flight3DConfig,
&masterConfig.motorConfig

View file

@ -608,14 +608,14 @@ static bool mspFcProcessOutCommand(uint8_t cmdMSP, sbuf_t *dst, mspPostProcessFn
break;
case MSP_SERVO_CONFIGURATIONS:
for (int i = 0; i < MAX_SUPPORTED_SERVOS; i++) {
sbufWriteU16(dst, currentProfile->servoConf[i].min);
sbufWriteU16(dst, currentProfile->servoConf[i].max);
sbufWriteU16(dst, currentProfile->servoConf[i].middle);
sbufWriteU8(dst, currentProfile->servoConf[i].rate);
sbufWriteU8(dst, currentProfile->servoConf[i].angleAtMin);
sbufWriteU8(dst, currentProfile->servoConf[i].angleAtMax);
sbufWriteU8(dst, currentProfile->servoConf[i].forwardFromChannel);
sbufWriteU32(dst, currentProfile->servoConf[i].reversedSources);
sbufWriteU16(dst, masterConfig.servoConf[i].min);
sbufWriteU16(dst, masterConfig.servoConf[i].max);
sbufWriteU16(dst, masterConfig.servoConf[i].middle);
sbufWriteU8(dst, masterConfig.servoConf[i].rate);
sbufWriteU8(dst, masterConfig.servoConf[i].angleAtMin);
sbufWriteU8(dst, masterConfig.servoConf[i].angleAtMax);
sbufWriteU8(dst, masterConfig.servoConf[i].forwardFromChannel);
sbufWriteU32(dst, masterConfig.servoConf[i].reversedSources);
}
break;
case MSP_SERVO_MIX_RULES:
@ -719,7 +719,7 @@ static bool mspFcProcessOutCommand(uint8_t cmdMSP, sbuf_t *dst, mspPostProcessFn
case MSP_MODE_RANGES:
for (int i = 0; i < MAX_MODE_ACTIVATION_CONDITION_COUNT; i++) {
modeActivationCondition_t *mac = &currentProfile->modeActivationConditions[i];
modeActivationCondition_t *mac = &masterConfig.modeActivationConditions[i];
const box_t *box = findBoxByActiveBoxId(mac->modeId);
sbufWriteU8(dst, box ? box->permanentId : 0);
sbufWriteU8(dst, mac->auxChannelIndex);
@ -730,7 +730,7 @@ static bool mspFcProcessOutCommand(uint8_t cmdMSP, sbuf_t *dst, mspPostProcessFn
case MSP_ADJUSTMENT_RANGES:
for (int i = 0; i < MAX_ADJUSTMENT_RANGE_COUNT; i++) {
adjustmentRange_t *adjRange = &currentProfile->adjustmentRanges[i];
adjustmentRange_t *adjRange = &masterConfig.adjustmentRanges[i];
sbufWriteU8(dst, adjRange->adjustmentIndex);
sbufWriteU8(dst, adjRange->auxChannelIndex);
sbufWriteU8(dst, adjRange->range.startStep);
@ -1041,9 +1041,9 @@ static bool mspFcProcessOutCommand(uint8_t cmdMSP, sbuf_t *dst, mspPostProcessFn
break;
case MSP_RC_DEADBAND:
sbufWriteU8(dst, currentProfile->rcControlsConfig.deadband);
sbufWriteU8(dst, currentProfile->rcControlsConfig.yaw_deadband);
sbufWriteU8(dst, currentProfile->rcControlsConfig.alt_hold_deadband);
sbufWriteU8(dst, masterConfig.rcControlsConfig.deadband);
sbufWriteU8(dst, masterConfig.rcControlsConfig.yaw_deadband);
sbufWriteU8(dst, masterConfig.rcControlsConfig.alt_hold_deadband);
sbufWriteU16(dst, flight3DConfig()->deadband3d_throttle);
break;
@ -1277,7 +1277,7 @@ static mspResult_e mspFcProcessInCommand(uint8_t cmdMSP, sbuf_t *src)
case MSP_SET_MODE_RANGE:
i = sbufReadU8(src);
if (i < MAX_MODE_ACTIVATION_CONDITION_COUNT) {
modeActivationCondition_t *mac = &currentProfile->modeActivationConditions[i];
modeActivationCondition_t *mac = &masterConfig.modeActivationConditions[i];
i = sbufReadU8(src);
const box_t *box = findBoxByPermenantId(i);
if (box) {
@ -1286,7 +1286,7 @@ static mspResult_e mspFcProcessInCommand(uint8_t cmdMSP, sbuf_t *src)
mac->range.startStep = sbufReadU8(src);
mac->range.endStep = sbufReadU8(src);
useRcControlsConfig(currentProfile->modeActivationConditions, &masterConfig.motorConfig, &currentProfile->pidProfile);
useRcControlsConfig(masterConfig.modeActivationConditions, &masterConfig.motorConfig, &currentProfile->pidProfile);
} else {
return MSP_RESULT_ERROR;
}
@ -1298,7 +1298,7 @@ static mspResult_e mspFcProcessInCommand(uint8_t cmdMSP, sbuf_t *src)
case MSP_SET_ADJUSTMENT_RANGE:
i = sbufReadU8(src);
if (i < MAX_ADJUSTMENT_RANGE_COUNT) {
adjustmentRange_t *adjRange = &currentProfile->adjustmentRanges[i];
adjustmentRange_t *adjRange = &masterConfig.adjustmentRanges[i];
i = sbufReadU8(src);
if (i < MAX_SIMULTANEOUS_ADJUSTMENT_COUNT) {
adjRange->adjustmentIndex = i;
@ -1394,14 +1394,14 @@ static mspResult_e mspFcProcessInCommand(uint8_t cmdMSP, sbuf_t *src)
if (i >= MAX_SUPPORTED_SERVOS) {
return MSP_RESULT_ERROR;
} else {
currentProfile->servoConf[i].min = sbufReadU16(src);
currentProfile->servoConf[i].max = sbufReadU16(src);
currentProfile->servoConf[i].middle = sbufReadU16(src);
currentProfile->servoConf[i].rate = sbufReadU8(src);
currentProfile->servoConf[i].angleAtMin = sbufReadU8(src);
currentProfile->servoConf[i].angleAtMax = sbufReadU8(src);
currentProfile->servoConf[i].forwardFromChannel = sbufReadU8(src);
currentProfile->servoConf[i].reversedSources = sbufReadU32(src);
masterConfig.servoConf[i].min = sbufReadU16(src);
masterConfig.servoConf[i].max = sbufReadU16(src);
masterConfig.servoConf[i].middle = sbufReadU16(src);
masterConfig.servoConf[i].rate = sbufReadU8(src);
masterConfig.servoConf[i].angleAtMin = sbufReadU8(src);
masterConfig.servoConf[i].angleAtMax = sbufReadU8(src);
masterConfig.servoConf[i].forwardFromChannel = sbufReadU8(src);
masterConfig.servoConf[i].reversedSources = sbufReadU32(src);
}
#endif
break;
@ -1432,9 +1432,9 @@ static mspResult_e mspFcProcessInCommand(uint8_t cmdMSP, sbuf_t *src)
break;
case MSP_SET_RC_DEADBAND:
currentProfile->rcControlsConfig.deadband = sbufReadU8(src);
currentProfile->rcControlsConfig.yaw_deadband = sbufReadU8(src);
currentProfile->rcControlsConfig.alt_hold_deadband = sbufReadU8(src);
masterConfig.rcControlsConfig.deadband = sbufReadU8(src);
masterConfig.rcControlsConfig.yaw_deadband = sbufReadU8(src);
masterConfig.rcControlsConfig.alt_hold_deadband = sbufReadU8(src);
break;
case MSP_SET_RESET_CURR_PID:

View file

@ -177,9 +177,9 @@ void annexCode(void)
int32_t throttleValue;
// Compute ROLL PITCH and YAW command
rcCommand[ROLL] = getAxisRcCommand(rcData[ROLL], currentControlRateProfile->rcExpo8, currentProfile->rcControlsConfig.deadband);
rcCommand[PITCH] = getAxisRcCommand(rcData[PITCH], currentControlRateProfile->rcExpo8, currentProfile->rcControlsConfig.deadband);
rcCommand[YAW] = -getAxisRcCommand(rcData[YAW], currentControlRateProfile->rcYawExpo8, currentProfile->rcControlsConfig.yaw_deadband);
rcCommand[ROLL] = getAxisRcCommand(rcData[ROLL], currentControlRateProfile->rcExpo8, masterConfig.rcControlsConfig.deadband);
rcCommand[PITCH] = getAxisRcCommand(rcData[PITCH], currentControlRateProfile->rcExpo8, masterConfig.rcControlsConfig.deadband);
rcCommand[YAW] = -getAxisRcCommand(rcData[YAW], currentControlRateProfile->rcYawExpo8, masterConfig.rcControlsConfig.yaw_deadband);
//Compute THROTTLE command
throttleValue = constrain(rcData[THROTTLE], rxConfig()->mincheck, PWM_RANGE_MAX);
@ -361,10 +361,10 @@ void processRx(timeUs_t currentTimeUs)
processRcStickPositions(&masterConfig.rxConfig, throttleStatus, armingConfig()->disarm_kill_switch, armingConfig()->fixed_wing_auto_arm);
updateActivatedModes(currentProfile->modeActivationConditions, currentProfile->modeActivationOperator);
updateActivatedModes(masterConfig.modeActivationConditions, masterConfig.modeActivationOperator);
if (!cliMode) {
updateAdjustmentStates(currentProfile->adjustmentRanges);
updateAdjustmentStates(masterConfig.adjustmentRanges);
processRcAdjustments(currentControlRateProfile, &masterConfig.rxConfig);
}
@ -645,8 +645,8 @@ void taskMainPidLoop(timeUs_t currentTimeUs)
if (navigationRequiresThrottleTiltCompensation()) {
thrTiltCompStrength = 100;
}
else if (currentProfile->throttle_tilt_compensation_strength && (FLIGHT_MODE(ANGLE_MODE) || FLIGHT_MODE(HORIZON_MODE))) {
thrTiltCompStrength = currentProfile->throttle_tilt_compensation_strength;
else if (masterConfig.throttle_tilt_compensation_strength && (FLIGHT_MODE(ANGLE_MODE) || FLIGHT_MODE(HORIZON_MODE))) {
thrTiltCompStrength = masterConfig.throttle_tilt_compensation_strength;
}
if (thrTiltCompStrength) {
@ -678,7 +678,7 @@ void taskMainPidLoop(timeUs_t currentTimeUs)
#ifdef USE_SERVOS
if (isMixerUsingServos()) {
servoMixer(currentProfile->flaperon_throw_offset, currentProfile->flaperon_throw_inverted);
servoMixer(masterConfig.flaperon_throw_offset, masterConfig.flaperon_throw_inverted);
}
if (feature(FEATURE_SERVO_TILT)) {

View file

@ -837,29 +837,29 @@ const clivalue_t valueTable[] = {
{ "imu_dcm_kp_mag", VAR_UINT16 | MASTER_VALUE, &imuConfig()->dcm_kp_mag, .config.minmax = { 0, 65535 } },
{ "imu_dcm_ki_mag", VAR_UINT16 | MASTER_VALUE, &imuConfig()->dcm_ki_mag, .config.minmax = { 0, 65535 } },
{ "deadband", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].rcControlsConfig.deadband, .config.minmax = { 0, 32 }, },
{ "yaw_deadband", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].rcControlsConfig.yaw_deadband, .config.minmax = { 0, 100 }, },
{ "pos_hold_deadband", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].rcControlsConfig.pos_hold_deadband, .config.minmax = { 10, 250 }, },
{ "alt_hold_deadband", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].rcControlsConfig.alt_hold_deadband, .config.minmax = { 10, 250 }, },
{ "deadband", VAR_UINT8 | MASTER_VALUE, &masterConfig.rcControlsConfig.deadband, .config.minmax = { 0, 32 }, },
{ "yaw_deadband", VAR_UINT8 | MASTER_VALUE, &masterConfig.rcControlsConfig.yaw_deadband, .config.minmax = { 0, 100 }, },
{ "pos_hold_deadband", VAR_UINT8 | MASTER_VALUE, &masterConfig.rcControlsConfig.pos_hold_deadband, .config.minmax = { 10, 250 }, },
{ "alt_hold_deadband", VAR_UINT8 | MASTER_VALUE, &masterConfig.rcControlsConfig.alt_hold_deadband, .config.minmax = { 10, 250 }, },
{ "throttle_tilt_comp_str", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].throttle_tilt_compensation_strength, .config.minmax = { 0, 100 }, },
{ "throttle_tilt_comp_str", VAR_UINT8 | MASTER_VALUE, &masterConfig.throttle_tilt_compensation_strength, .config.minmax = { 0, 100 }, },
{ "yaw_motor_direction", VAR_INT8 | MASTER_VALUE, &mixerConfig()->yaw_motor_direction, .config.minmax = { -1, 1 } },
{ "yaw_jump_prevention_limit", VAR_UINT16 | MASTER_VALUE, &mixerConfig()->yaw_jump_prevention_limit, .config.minmax = { YAW_JUMP_PREVENTION_LIMIT_LOW, YAW_JUMP_PREVENTION_LIMIT_HIGH } },
#ifdef USE_SERVOS
{ "flaperon_throw_offset", VAR_INT16 | PROFILE_VALUE, &masterConfig.profile[0].flaperon_throw_offset, .config.minmax = { FLAPERON_THROW_MIN, FLAPERON_THROW_MAX} },
{ "flaperon_throw_inverted", VAR_UINT8 | PROFILE_VALUE | MODE_LOOKUP, &masterConfig.profile[0].flaperon_throw_inverted, .config.lookup = { TABLE_OFF_ON } },
{ "flaperon_throw_offset", VAR_INT16 | MASTER_VALUE, &masterConfig.flaperon_throw_offset, .config.minmax = { FLAPERON_THROW_MIN, FLAPERON_THROW_MAX} },
{ "flaperon_throw_inverted", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.flaperon_throw_inverted, .config.lookup = { TABLE_OFF_ON } },
{ "tri_unarmed_servo", VAR_INT8 | MASTER_VALUE | MODE_LOOKUP, &servoMixerConfig()->tri_unarmed_servo, .config.lookup = { TABLE_OFF_ON } },
{ "servo_lowpass_freq", VAR_INT16 | MASTER_VALUE, &servoMixerConfig()->servo_lowpass_freq, .config.minmax = { 10, 400} },
{ "servo_lowpass_enable", VAR_INT8 | MASTER_VALUE | MODE_LOOKUP, &servoMixerConfig()->servo_lowpass_enable, .config.lookup = { TABLE_OFF_ON } },
{ "gimbal_mode", VAR_UINT8 | PROFILE_VALUE | MODE_LOOKUP, &masterConfig.profile[0].gimbalConfig.mode, .config.lookup = { TABLE_GIMBAL_MODE } },
{ "gimbal_mode", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.gimbalConfig.mode, .config.lookup = { TABLE_GIMBAL_MODE } },
{ "servo_center_pulse", VAR_UINT16 | MASTER_VALUE, &servoConfig()->servoCenterPulse, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX } },
{ "servo_pwm_rate", VAR_UINT16 | MASTER_VALUE, &servoConfig()->servoPwmRate, .config.minmax = { 50, 498 } },
{ "fw_iterm_throw_limit", VAR_INT16 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.fixedWingItermThrowLimit, .config.minmax = { FW_ITERM_THROW_LIMIT_MIN, FW_ITERM_THROW_LIMIT_MAX} },
#endif
{ "mode_range_logic_operator", VAR_UINT8 | PROFILE_VALUE | MODE_LOOKUP, &masterConfig.profile[0].modeActivationOperator, .config.lookup = { TABLE_AUX_OPERATOR } },
{ "mode_range_logic_operator", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.modeActivationOperator, .config.lookup = { TABLE_AUX_OPERATOR } },
{ "default_rate_profile", VAR_UINT8 | PROFILE_VALUE , &masterConfig.profile[0].defaultRateProfileIndex, .config.minmax = { 0, MAX_CONTROL_RATE_PROFILE_COUNT - 1 } },
{ "rc_expo", VAR_UINT8 | CONTROL_RATE_VALUE, &masterConfig.controlRateProfiles[0].rcExpo8, .config.minmax = { 0, 100 } },
{ "rc_yaw_expo", VAR_UINT8 | CONTROL_RATE_VALUE, &masterConfig.controlRateProfiles[0].rcYawExpo8, .config.minmax = { 0, 100 } },
@ -953,6 +953,9 @@ const clivalue_t valueTable[] = {
{ "acczero_x", VAR_INT16 | MASTER_VALUE, &accelerometerConfig()->accZero.raw[X], .config.minmax = { -32768, 32767 } },
{ "acczero_y", VAR_INT16 | MASTER_VALUE, &accelerometerConfig()->accZero.raw[Y], .config.minmax = { -32768, 32767 } },
{ "acczero_z", VAR_INT16 | MASTER_VALUE, &accelerometerConfig()->accZero.raw[Z], .config.minmax = { -32768, 32767 } },
{ "accgain_x", VAR_INT16 | MASTER_VALUE, &accelerometerConfig()->accGain.raw[X], .config.minmax = { 1, 8192 } },
{ "accgain_y", VAR_INT16 | MASTER_VALUE, &accelerometerConfig()->accGain.raw[Y], .config.minmax = { 1, 8192 } },
{ "accgain_z", VAR_INT16 | MASTER_VALUE, &accelerometerConfig()->accGain.raw[Z], .config.minmax = { 1, 8192 } },
#ifdef LED_STRIP
{ "ledstrip_visual_beeper", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &ledStripConfig()->ledstrip_visual_beeper, .config.lookup = { TABLE_OFF_ON } },
#endif
@ -982,9 +985,6 @@ const clivalue_t valueTable[] = {
{ "osd_gps_sats_pos", VAR_UINT16 | MASTER_VALUE, &osdProfile()->item_pos[OSD_GPS_SATS], .config.minmax = { 0, UINT16_MAX } },
{ "osd_altitude_pos", VAR_UINT16 | MASTER_VALUE, &osdProfile()->item_pos[OSD_ALTITUDE], .config.minmax = { 0, UINT16_MAX } },
#endif
{ "accgain_x", VAR_INT16 | MASTER_VALUE, &accelerometerConfig()->accGain.raw[X], .config.minmax = { 1, 8192 } },
{ "accgain_y", VAR_INT16 | MASTER_VALUE, &accelerometerConfig()->accGain.raw[Y], .config.minmax = { 1, 8192 } },
{ "accgain_z", VAR_INT16 | MASTER_VALUE, &accelerometerConfig()->accGain.raw[Z], .config.minmax = { 1, 8192 } },
};
#define VALUE_COUNT (sizeof(valueTable) / sizeof(clivalue_t))
@ -1251,8 +1251,8 @@ static void printAux(uint8_t dumpMask, master_t *defaultConfig)
modeActivationCondition_t *macDefault;
bool equalsDefault;
for (uint32_t i = 0; i < MAX_MODE_ACTIVATION_CONDITION_COUNT; i++) {
mac = &currentProfile->modeActivationConditions[i];
macDefault = &defaultConfig->profile[0].modeActivationConditions[i];
mac = &masterConfig.modeActivationConditions[i];
macDefault = &defaultConfig->modeActivationConditions[i];
equalsDefault = mac->modeId == macDefault->modeId
&& mac->auxChannelIndex == macDefault->auxChannelIndex
&& mac->range.startStep == macDefault->range.startStep
@ -1286,7 +1286,7 @@ static void cliAux(char *cmdline)
ptr = cmdline;
i = atoi(ptr++);
if (i < MAX_MODE_ACTIVATION_CONDITION_COUNT) {
modeActivationCondition_t *mac = &currentProfile->modeActivationConditions[i];
modeActivationCondition_t *mac = &masterConfig.modeActivationConditions[i];
uint8_t validArgumentCount = 0;
ptr = nextArg(ptr);
if (ptr) {
@ -1444,8 +1444,8 @@ static void printAdjustmentRange(uint8_t dumpMask, master_t *defaultConfig)
adjustmentRange_t *arDefault;
bool equalsDefault;
for (uint32_t i = 0; i < MAX_ADJUSTMENT_RANGE_COUNT; i++) {
ar = &currentProfile->adjustmentRanges[i];
arDefault = &defaultConfig->profile[0].adjustmentRanges[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
@ -1485,7 +1485,7 @@ static void cliAdjustmentRange(char *cmdline)
ptr = cmdline;
i = atoi(ptr++);
if (i < MAX_ADJUSTMENT_RANGE_COUNT) {
adjustmentRange_t *ar = &currentProfile->adjustmentRanges[i];
adjustmentRange_t *ar = &masterConfig.adjustmentRanges[i];
uint8_t validArgumentCount = 0;
ptr = nextArg(ptr);
@ -1853,8 +1853,8 @@ static void printServo(uint8_t dumpMask, master_t *defaultConfig)
{
// print out servo settings
for (uint32_t i = 0; i < MAX_SUPPORTED_SERVOS; i++) {
servoParam_t *servoConf = &currentProfile->servoConf[i];
servoParam_t *servoConfDefault = &defaultConfig->profile[0].servoConf[i];
servoParam_t *servoConf = &masterConfig.servoConf[i];
servoParam_t *servoConfDefault = &defaultConfig->servoConf[i];
bool equalsDefault = servoConf->min == servoConfDefault->min
&& servoConf->max == servoConfDefault->max
&& servoConf->middle == servoConfDefault->middle
@ -1886,8 +1886,8 @@ static void printServo(uint8_t dumpMask, master_t *defaultConfig)
// print servo directions
for (uint32_t i = 0; i < MAX_SUPPORTED_SERVOS; i++) {
servoParam_t *servoConf = &currentProfile->servoConf[i];
servoParam_t *servoConfDefault = &defaultConfig->profile[0].servoConf[i];
servoParam_t *servoConf = &masterConfig.servoConf[i];
servoParam_t *servoConfDefault = &defaultConfig->servoConf[i];
bool equalsDefault = servoConf->reversedSources == servoConfDefault->reversedSources;
for (uint32_t channel = 0; channel < INPUT_SOURCE_COUNT; channel++) {
equalsDefault = ~(servoConf->reversedSources ^ servoConfDefault->reversedSources) & (1 << channel);
@ -1952,7 +1952,7 @@ static void cliServo(char *cmdline)
return;
}
servo = &currentProfile->servoConf[i];
servo = &masterConfig.servoConf[i];
if (
arguments[MIN] < PWM_PULSE_MIN || arguments[MIN] > PWM_PULSE_MAX ||
@ -2034,7 +2034,7 @@ static void cliServoMix(char *cmdline)
// erase custom mixer
memset(masterConfig.customServoMixer, 0, sizeof(masterConfig.customServoMixer));
for (uint32_t i = 0; i < MAX_SUPPORTED_SERVOS; i++) {
currentProfile->servoConf[i].reversedSources = 0;
masterConfig.servoConf[i].reversedSources = 0;
}
} else if (strncasecmp(cmdline, "load", 4) == 0) {
ptr = nextArg(cmdline);
@ -2067,7 +2067,7 @@ static void cliServoMix(char *cmdline)
for (uint32_t servoIndex = 0; servoIndex < MAX_SUPPORTED_SERVOS; servoIndex++) {
cliPrintf("%d", servoIndex);
for (uint32_t inputSource = 0; inputSource < INPUT_SOURCE_COUNT; inputSource++)
cliPrintf("\t%s ", (currentProfile->servoConf[servoIndex].reversedSources & (1 << inputSource)) ? "r" : "n");
cliPrintf("\t%s ", (masterConfig.servoConf[servoIndex].reversedSources & (1 << inputSource)) ? "r" : "n");
cliPrintf("\r\n");
}
return;
@ -2088,9 +2088,9 @@ static void cliServoMix(char *cmdline)
&& args[INPUT] >= 0 && args[INPUT] < INPUT_SOURCE_COUNT
&& (*ptr == 'r' || *ptr == 'n')) {
if (*ptr == 'r')
currentProfile->servoConf[args[SERVO]].reversedSources |= 1 << args[INPUT];
masterConfig.servoConf[args[SERVO]].reversedSources |= 1 << args[INPUT];
else
currentProfile->servoConf[args[SERVO]].reversedSources &= ~(1 << args[INPUT]);
masterConfig.servoConf[args[SERVO]].reversedSources &= ~(1 << args[INPUT]);
} else
cliShowParseError();
@ -2663,6 +2663,10 @@ static void printConfig(char *cmdline, bool doDiff)
printMotorMix(dumpMask, &defaultConfig);
#ifdef USE_SERVOS
#ifndef CLI_MINIMAL_VERBOSITY
cliPrint("\r\n# servo\r\n");
#endif
printServo(dumpMask, &defaultConfig);
#ifndef CLI_MINIMAL_VERBOSITY
cliPrint("\r\n# servo mix\r\n");
#endif
@ -2711,6 +2715,16 @@ static void printConfig(char *cmdline, bool doDiff)
printModeColor(dumpMask, &defaultConfig);
#endif
#ifndef CLI_MINIMAL_VERBOSITY
cliPrint("\r\n# aux\r\n");
#endif
printAux(dumpMask, &defaultConfig);
#ifndef CLI_MINIMAL_VERBOSITY
cliPrint("\r\n# adjrange\r\n");
#endif
printAdjustmentRange(dumpMask, &defaultConfig);
#ifndef CLI_MINIMAL_VERBOSITY
cliPrint("\r\n# rxrange\r\n");
#endif
@ -2778,23 +2792,6 @@ static void cliDumpProfile(uint8_t profileIndex, uint8_t dumpMask, master_t *def
cliProfile("");
cliPrint("\r\n");
dumpValues(PROFILE_VALUE, dumpMask, defaultConfig);
#ifndef CLI_MINIMAL_VERBOSITY
cliPrint("\r\n# aux\r\n");
#endif
printAux(dumpMask, defaultConfig);
#ifndef CLI_MINIMAL_VERBOSITY
cliPrint("\r\n# adjrange\r\n");
#endif
printAdjustmentRange(dumpMask, defaultConfig);
#ifdef USE_SERVOS
#ifndef CLI_MINIMAL_VERBOSITY
cliPrint("\r\n# servo\r\n");
#endif
printServo(dumpMask, defaultConfig);
#endif
}
static void cliDumpRateProfile(uint8_t rateProfileIndex, uint8_t dumpMask, master_t *defaultConfig)