1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-16 04:45:24 +03:00

Added profile macros and index functions

This commit is contained in:
Martin Budden 2017-02-25 07:37:53 +00:00
parent 051c9cca48
commit a3ad97b0a4
10 changed files with 123 additions and 132 deletions

View file

@ -64,7 +64,7 @@ static controlRateConfig_t rateProfile;
static long cmsx_menuImu_onEnter(void) static long cmsx_menuImu_onEnter(void)
{ {
profileIndex = systemConfig()->current_profile_index; profileIndex = getCurrentProfileIndex();
tmpProfileIndex = profileIndex + 1; tmpProfileIndex = profileIndex + 1;
rateProfileIndex = systemConfig()->activeRateProfile; rateProfileIndex = systemConfig()->activeRateProfile;
@ -77,8 +77,8 @@ static long cmsx_menuImu_onExit(const OSD_Entry *self)
{ {
UNUSED(self); UNUSED(self);
systemConfigMutable()->current_profile_index = profileIndex; changeProfile(profileIndex);
systemConfigMutable()->activeRateProfile = rateProfileIndex; changeControlRateProfile(rateProfileIndex);
return 0; return 0;
} }
@ -106,7 +106,7 @@ static long cmsx_rateProfileIndexOnChange(displayPort_t *displayPort, const void
static long cmsx_PidRead(void) static long cmsx_PidRead(void)
{ {
const pidProfile_t *pidProfile = &masterConfig.profile[profileIndex].pidProfile; const pidProfile_t *pidProfile = pidProfiles(profileIndex);
for (uint8_t i = 0; i < 3; i++) { for (uint8_t i = 0; i < 3; i++) {
tempPid[i][0] = pidProfile->P8[i]; tempPid[i][0] = pidProfile->P8[i];
tempPid[i][1] = pidProfile->I8[i]; tempPid[i][1] = pidProfile->I8[i];
@ -128,7 +128,7 @@ static long cmsx_PidWriteback(const OSD_Entry *self)
{ {
UNUSED(self); UNUSED(self);
pidProfile_t *pidProfile = &masterConfig.profile[profileIndex].pidProfile; pidProfile_t *pidProfile = pidProfilesMutable(profileIndex);
for (uint8_t i = 0; i < 3; i++) { for (uint8_t i = 0; i < 3; i++) {
pidProfile->P8[i] = tempPid[i][0]; pidProfile->P8[i] = tempPid[i][0];
pidProfile->I8[i] = tempPid[i][1]; pidProfile->I8[i] = tempPid[i][1];
@ -237,7 +237,7 @@ static long cmsx_profileOtherOnEnter(void)
{ {
profileIndexString[1] = '0' + tmpProfileIndex; profileIndexString[1] = '0' + tmpProfileIndex;
const pidProfile_t *pidProfile = &masterConfig.profile[profileIndex].pidProfile; const pidProfile_t *pidProfile = pidProfiles(profileIndex);
cmsx_dtermSetpointWeight = pidProfile->dtermSetpointWeight; cmsx_dtermSetpointWeight = pidProfile->dtermSetpointWeight;
cmsx_setpointRelaxRatio = pidProfile->setpointRelaxRatio; cmsx_setpointRelaxRatio = pidProfile->setpointRelaxRatio;
@ -252,7 +252,7 @@ static long cmsx_profileOtherOnExit(const OSD_Entry *self)
{ {
UNUSED(self); UNUSED(self);
pidProfile_t *pidProfile = &masterConfig.profile[profileIndex].pidProfile; pidProfile_t *pidProfile = pidProfilesMutable(profileIndex);
pidProfile->dtermSetpointWeight = cmsx_dtermSetpointWeight; pidProfile->dtermSetpointWeight = cmsx_dtermSetpointWeight;
pidProfile->setpointRelaxRatio = cmsx_setpointRelaxRatio; pidProfile->setpointRelaxRatio = cmsx_setpointRelaxRatio;
pidInitConfig(&currentProfile->pidProfile); pidInitConfig(&currentProfile->pidProfile);
@ -347,7 +347,7 @@ static uint16_t cmsx_yaw_p_limit;
static long cmsx_FilterPerProfileRead(void) static long cmsx_FilterPerProfileRead(void)
{ {
const pidProfile_t *pidProfile = &masterConfig.profile[profileIndex].pidProfile; const pidProfile_t *pidProfile = pidProfiles(profileIndex);
cmsx_dterm_lpf_hz = pidProfile->dterm_lpf_hz; cmsx_dterm_lpf_hz = pidProfile->dterm_lpf_hz;
cmsx_dterm_notch_hz = pidProfile->dterm_notch_hz; cmsx_dterm_notch_hz = pidProfile->dterm_notch_hz;
cmsx_dterm_notch_cutoff = pidProfile->dterm_notch_cutoff; cmsx_dterm_notch_cutoff = pidProfile->dterm_notch_cutoff;
@ -361,7 +361,7 @@ static long cmsx_FilterPerProfileWriteback(const OSD_Entry *self)
{ {
UNUSED(self); UNUSED(self);
pidProfile_t *pidProfile = &masterConfig.profile[profileIndex].pidProfile; pidProfile_t *pidProfile = pidProfilesMutable(profileIndex);
pidProfile->dterm_lpf_hz = cmsx_dterm_lpf_hz; pidProfile->dterm_lpf_hz = cmsx_dterm_lpf_hz;
pidProfile->dterm_notch_hz = cmsx_dterm_notch_hz; pidProfile->dterm_notch_hz = cmsx_dterm_notch_hz;
pidProfile->dterm_notch_cutoff = cmsx_dterm_notch_cutoff; pidProfile->dterm_notch_cutoff = cmsx_dterm_notch_cutoff;

View file

@ -174,19 +174,21 @@
#define vtxConfigMutable(x) (&masterConfig.vtxConfig) #define vtxConfigMutable(x) (&masterConfig.vtxConfig)
#define beeperConfigMutable(x) (&masterConfig.beeperConfig) #define beeperConfigMutable(x) (&masterConfig.beeperConfig)
#define servoParams(x) (&servoProfile()->servoConf[x])
#define adjustmentRanges(x) (&adjustmentProfile()->adjustmentRanges[x])
#define rxFailsafeChannelConfigs(x) (&masterConfig.rxConfig.failsafe_channel_configurations[x])
#define osdConfig(x) (&masterConfig.osdProfile) #define osdConfig(x) (&masterConfig.osdProfile)
#define modeActivationConditions(x) (&masterConfig.modeActivationProfile.modeActivationConditions[x]) #define servoParams(i) (&servoProfile()->servoConf[i])
#define controlRateProfiles(x) (&masterConfig.controlRateProfile[x]) #define adjustmentRanges(i) (&adjustmentProfile()->adjustmentRanges[i])
#define rxFailsafeChannelConfigs(i) (&masterConfig.rxConfig.failsafe_channel_configurations[i])
#define modeActivationConditions(i) (&masterConfig.modeActivationProfile.modeActivationConditions[i])
#define controlRateProfiles(i) (&masterConfig.controlRateProfile[i])
#define pidProfiles(i) (&masterConfig.profile[i].pidProfile)
#define servoParamsMutable(x) (&servoProfile()->servoConf[x])
#define adjustmentRangesMutable(x) (&masterConfig.adjustmentProfile.adjustmentRanges[x])
#define rxFailsafeChannelConfigsMutable(x) (&masterConfig.rxConfig.>failsafe_channel_configurations[x])
#define osdConfigMutable(x) (&masterConfig.osdProfile) #define osdConfigMutable(x) (&masterConfig.osdProfile)
#define modeActivationConditionsMutable(x) (&masterConfig.modeActivationProfile.modeActivationConditions[x]) #define servoParamsMutable(i) (&servoProfile()->servoConf[i])
#define controlRateProfilesMutable(x) (&masterConfig.controlRateProfile[x]) #define adjustmentRangesMutable(i) (&masterConfig.adjustmentProfile.adjustmentRanges[i])
#define rxFailsafeChannelConfigsMutable(i) (&masterConfig.rxConfig.>failsafe_channel_configurations[i])
#define modeActivationConditionsMutable(i) (&masterConfig.modeActivationProfile.modeActivationConditions[i])
#define controlRateProfilesMutable(i) (&masterConfig.controlRateProfile[i])
#define pidProfilesMutable(i) (&masterConfig.profile[i].pidProfile)
#endif #endif
// System-wide // System-wide

View file

@ -612,15 +612,15 @@ static const clivalue_t valueTable[] = {
{ "gps_auto_config", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &gpsConfig()->autoConfig, .config.lookup = { TABLE_OFF_ON } }, { "gps_auto_config", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &gpsConfig()->autoConfig, .config.lookup = { TABLE_OFF_ON } },
{ "gps_auto_baud", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &gpsConfig()->autoBaud, .config.lookup = { TABLE_OFF_ON } }, { "gps_auto_baud", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &gpsConfig()->autoBaud, .config.lookup = { TABLE_OFF_ON } },
{ "gps_pos_p", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.P8[PIDPOS], .config.minmax = { 0, 200 } }, { "gps_pos_p", VAR_UINT8 | PROFILE_VALUE, &pidProfiles(0)->P8[PIDPOS], .config.minmax = { 0, 200 } },
{ "gps_pos_i", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.I8[PIDPOS], .config.minmax = { 0, 200 } }, { "gps_pos_i", VAR_UINT8 | PROFILE_VALUE, &pidProfiles(0)->I8[PIDPOS], .config.minmax = { 0, 200 } },
{ "gps_pos_d", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.D8[PIDPOS], .config.minmax = { 0, 200 } }, { "gps_pos_d", VAR_UINT8 | PROFILE_VALUE, &pidProfiles(0)->D8[PIDPOS], .config.minmax = { 0, 200 } },
{ "gps_posr_p", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.P8[PIDPOSR], .config.minmax = { 0, 200 } }, { "gps_posr_p", VAR_UINT8 | PROFILE_VALUE, &pidProfiles(0)->P8[PIDPOSR], .config.minmax = { 0, 200 } },
{ "gps_posr_i", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.I8[PIDPOSR], .config.minmax = { 0, 200 } }, { "gps_posr_i", VAR_UINT8 | PROFILE_VALUE, &pidProfiles(0)->I8[PIDPOSR], .config.minmax = { 0, 200 } },
{ "gps_posr_d", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.D8[PIDPOSR], .config.minmax = { 0, 200 } }, { "gps_posr_d", VAR_UINT8 | PROFILE_VALUE, &pidProfiles(0)->D8[PIDPOSR], .config.minmax = { 0, 200 } },
{ "gps_nav_p", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.P8[PIDNAVR], .config.minmax = { 0, 200 } }, { "gps_nav_p", VAR_UINT8 | PROFILE_VALUE, &pidProfiles(0)->P8[PIDNAVR], .config.minmax = { 0, 200 } },
{ "gps_nav_i", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.I8[PIDNAVR], .config.minmax = { 0, 200 } }, { "gps_nav_i", VAR_UINT8 | PROFILE_VALUE, &pidProfiles(0)->I8[PIDNAVR], .config.minmax = { 0, 200 } },
{ "gps_nav_d", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.D8[PIDNAVR], .config.minmax = { 0, 200 } }, { "gps_nav_d", VAR_UINT8 | PROFILE_VALUE, &pidProfiles(0)->D8[PIDNAVR], .config.minmax = { 0, 200 } },
{ "gps_wp_radius", VAR_UINT16 | MASTER_VALUE, &gpsProfile()->gps_wp_radius, .config.minmax = { 0, 2000 } }, { "gps_wp_radius", VAR_UINT16 | MASTER_VALUE, &gpsProfile()->gps_wp_radius, .config.minmax = { 0, 2000 } },
{ "nav_controls_heading", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &gpsProfile()->nav_controls_heading, .config.lookup = { TABLE_OFF_ON } }, { "nav_controls_heading", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &gpsProfile()->nav_controls_heading, .config.lookup = { TABLE_OFF_ON } },
{ "nav_speed_min", VAR_UINT16 | MASTER_VALUE, &gpsProfile()->nav_speed_min, .config.minmax = { 10, 2000 } }, { "nav_speed_min", VAR_UINT16 | MASTER_VALUE, &gpsProfile()->nav_speed_min, .config.minmax = { 10, 2000 } },
@ -714,8 +714,8 @@ static const clivalue_t valueTable[] = {
{ "yaw_control_direction", VAR_INT8 | MASTER_VALUE, &rcControlsConfig()->yaw_control_direction, .config.minmax = { -1, 1 } }, { "yaw_control_direction", VAR_INT8 | MASTER_VALUE, &rcControlsConfig()->yaw_control_direction, .config.minmax = { -1, 1 } },
{ "yaw_motor_direction", VAR_INT8 | MASTER_VALUE, &mixerConfig()->yaw_motor_direction, .config.minmax = { -1, 1 } }, { "yaw_motor_direction", VAR_INT8 | MASTER_VALUE, &mixerConfig()->yaw_motor_direction, .config.minmax = { -1, 1 } },
{ "yaw_p_limit", VAR_UINT16 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.yaw_p_limit, .config.minmax = { YAW_P_LIMIT_MIN, YAW_P_LIMIT_MAX } }, { "yaw_p_limit", VAR_UINT16 | PROFILE_VALUE, &pidProfiles(0)->yaw_p_limit, .config.minmax = { YAW_P_LIMIT_MIN, YAW_P_LIMIT_MAX } },
{ "pidsum_limit", VAR_FLOAT | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.pidSumLimit, .config.minmax = { 0.1, 1.0 } }, { "pidsum_limit", VAR_FLOAT | PROFILE_VALUE, &pidProfiles(0)->pidSumLimit, .config.minmax = { 0.1, 1.0 } },
#ifdef USE_SERVOS #ifdef USE_SERVOS
{ "servo_center_pulse", VAR_UINT16 | MASTER_VALUE, &servoConfig()->dev.servoCenterPulse, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX } }, { "servo_center_pulse", VAR_UINT16 | MASTER_VALUE, &servoConfig()->dev.servoCenterPulse, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX } },
{ "tri_unarmed_servo", VAR_INT8 | MASTER_VALUE | MODE_LOOKUP, &servoConfig()->tri_unarmed_servo, .config.lookup = { TABLE_OFF_ON } }, { "tri_unarmed_servo", VAR_INT8 | MASTER_VALUE | MODE_LOOKUP, &servoConfig()->tri_unarmed_servo, .config.lookup = { TABLE_OFF_ON } },
@ -768,47 +768,47 @@ static const clivalue_t valueTable[] = {
{ "mag_hardware", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &compassConfig()->mag_hardware, .config.lookup = { TABLE_MAG_HARDWARE } }, { "mag_hardware", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &compassConfig()->mag_hardware, .config.lookup = { TABLE_MAG_HARDWARE } },
{ "mag_declination", VAR_INT16 | MASTER_VALUE, &compassConfig()->mag_declination, .config.minmax = { -18000, 18000 } }, { "mag_declination", VAR_INT16 | MASTER_VALUE, &compassConfig()->mag_declination, .config.minmax = { -18000, 18000 } },
#endif #endif
{ "d_lowpass_type", VAR_UINT8 | PROFILE_VALUE | MODE_LOOKUP, &masterConfig.profile[0].pidProfile.dterm_filter_type, .config.lookup = { TABLE_LOWPASS_TYPE } }, { "d_lowpass_type", VAR_UINT8 | PROFILE_VALUE | MODE_LOOKUP, &pidProfiles(0)->dterm_filter_type, .config.lookup = { TABLE_LOWPASS_TYPE } },
{ "d_lowpass", VAR_INT16 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.dterm_lpf_hz, .config.minmax = {0, 16000 } }, { "d_lowpass", VAR_INT16 | PROFILE_VALUE, &pidProfiles(0)->dterm_lpf_hz, .config.minmax = {0, 16000 } },
{ "d_notch_hz", VAR_UINT16 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.dterm_notch_hz, .config.minmax = { 0, 16000 } }, { "d_notch_hz", VAR_UINT16 | PROFILE_VALUE, &pidProfiles(0)->dterm_notch_hz, .config.minmax = { 0, 16000 } },
{ "d_notch_cut", VAR_UINT16 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.dterm_notch_cutoff, .config.minmax = { 1, 16000 } }, { "d_notch_cut", VAR_UINT16 | PROFILE_VALUE, &pidProfiles(0)->dterm_notch_cutoff, .config.minmax = { 1, 16000 } },
{ "vbat_pid_gain", VAR_UINT8 | PROFILE_VALUE | MODE_LOOKUP, &masterConfig.profile[0].pidProfile.vbatPidCompensation, .config.lookup = { TABLE_OFF_ON } }, { "vbat_pid_gain", VAR_UINT8 | PROFILE_VALUE | MODE_LOOKUP, &pidProfiles(0)->vbatPidCompensation, .config.lookup = { TABLE_OFF_ON } },
{ "pid_at_min_throttle", VAR_UINT8 | PROFILE_VALUE | MODE_LOOKUP, &masterConfig.profile[0].pidProfile.pidAtMinThrottle, .config.lookup = { TABLE_OFF_ON } }, { "pid_at_min_throttle", VAR_UINT8 | PROFILE_VALUE | MODE_LOOKUP, &pidProfiles(0)->pidAtMinThrottle, .config.lookup = { TABLE_OFF_ON } },
{ "anti_gravity_thresh", VAR_UINT16 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.itermThrottleThreshold, .config.minmax = {20, 1000 } }, { "anti_gravity_thresh", VAR_UINT16 | PROFILE_VALUE, &pidProfiles(0)->itermThrottleThreshold, .config.minmax = {20, 1000 } },
{ "anti_gravity_gain", VAR_FLOAT | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.itermAcceleratorGain, .config.minmax = {1, 30 } }, { "anti_gravity_gain", VAR_FLOAT | PROFILE_VALUE, &pidProfiles(0)->itermAcceleratorGain, .config.minmax = {1, 30 } },
{ "setpoint_relax_ratio", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.setpointRelaxRatio, .config.minmax = {0, 100 } }, { "setpoint_relax_ratio", VAR_UINT8 | PROFILE_VALUE, &pidProfiles(0)->setpointRelaxRatio, .config.minmax = {0, 100 } },
{ "d_setpoint_weight", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.dtermSetpointWeight, .config.minmax = {0, 254 } }, { "d_setpoint_weight", VAR_UINT8 | PROFILE_VALUE, &pidProfiles(0)->dtermSetpointWeight, .config.minmax = {0, 254 } },
{ "yaw_accel_limit", VAR_FLOAT | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.yawRateAccelLimit, .config.minmax = {0.1f, 50.0f } }, { "yaw_accel_limit", VAR_FLOAT | PROFILE_VALUE, &pidProfiles(0)->yawRateAccelLimit, .config.minmax = {0.1f, 50.0f } },
{ "accel_limit", VAR_FLOAT | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.rateAccelLimit, .config.minmax = {0.1f, 50.0f } }, { "accel_limit", VAR_FLOAT | PROFILE_VALUE, &pidProfiles(0)->rateAccelLimit, .config.minmax = {0.1f, 50.0f } },
{ "iterm_windup", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.itermWindupPointPercent, .config.minmax = {30, 100 } }, { "iterm_windup", VAR_UINT8 | PROFILE_VALUE, &pidProfiles(0)->itermWindupPointPercent, .config.minmax = {30, 100 } },
{ "yaw_lowpass", VAR_UINT16 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.yaw_lpf_hz, .config.minmax = {0, 500 } }, { "yaw_lowpass", VAR_UINT16 | PROFILE_VALUE, &pidProfiles(0)->yaw_lpf_hz, .config.minmax = {0, 500 } },
{ "pid_process_denom", VAR_UINT8 | MASTER_VALUE, &pidConfig()->pid_process_denom, .config.minmax = { 1, MAX_PID_PROCESS_DENOM } }, { "pid_process_denom", VAR_UINT8 | MASTER_VALUE, &pidConfig()->pid_process_denom, .config.minmax = { 1, MAX_PID_PROCESS_DENOM } },
{ "p_pitch", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.P8[PITCH], .config.minmax = { 0, 200 } }, { "p_pitch", VAR_UINT8 | PROFILE_VALUE, &pidProfiles(0)->P8[PITCH], .config.minmax = { 0, 200 } },
{ "i_pitch", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.I8[PITCH], .config.minmax = { 0, 200 } }, { "i_pitch", VAR_UINT8 | PROFILE_VALUE, &pidProfiles(0)->I8[PITCH], .config.minmax = { 0, 200 } },
{ "d_pitch", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.D8[PITCH], .config.minmax = { 0, 200 } }, { "d_pitch", VAR_UINT8 | PROFILE_VALUE, &pidProfiles(0)->D8[PITCH], .config.minmax = { 0, 200 } },
{ "p_roll", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.P8[ROLL], .config.minmax = { 0, 200 } }, { "p_roll", VAR_UINT8 | PROFILE_VALUE, &pidProfiles(0)->P8[ROLL], .config.minmax = { 0, 200 } },
{ "i_roll", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.I8[ROLL], .config.minmax = { 0, 200 } }, { "i_roll", VAR_UINT8 | PROFILE_VALUE, &pidProfiles(0)->I8[ROLL], .config.minmax = { 0, 200 } },
{ "d_roll", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.D8[ROLL], .config.minmax = { 0, 200 } }, { "d_roll", VAR_UINT8 | PROFILE_VALUE, &pidProfiles(0)->D8[ROLL], .config.minmax = { 0, 200 } },
{ "p_yaw", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.P8[YAW], .config.minmax = { 0, 200 } }, { "p_yaw", VAR_UINT8 | PROFILE_VALUE, &pidProfiles(0)->P8[YAW], .config.minmax = { 0, 200 } },
{ "i_yaw", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.I8[YAW], .config.minmax = { 0, 200 } }, { "i_yaw", VAR_UINT8 | PROFILE_VALUE, &pidProfiles(0)->I8[YAW], .config.minmax = { 0, 200 } },
{ "d_yaw", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.D8[YAW], .config.minmax = { 0, 200 } }, { "d_yaw", VAR_UINT8 | PROFILE_VALUE, &pidProfiles(0)->D8[YAW], .config.minmax = { 0, 200 } },
{ "p_alt", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.P8[PIDALT], .config.minmax = { 0, 200 } }, { "p_alt", VAR_UINT8 | PROFILE_VALUE, &pidProfiles(0)->P8[PIDALT], .config.minmax = { 0, 200 } },
{ "i_alt", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.I8[PIDALT], .config.minmax = { 0, 200 } }, { "i_alt", VAR_UINT8 | PROFILE_VALUE, &pidProfiles(0)->I8[PIDALT], .config.minmax = { 0, 200 } },
{ "d_alt", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.D8[PIDALT], .config.minmax = { 0, 200 } }, { "d_alt", VAR_UINT8 | PROFILE_VALUE, &pidProfiles(0)->D8[PIDALT], .config.minmax = { 0, 200 } },
{ "p_level", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.P8[PIDLEVEL], .config.minmax = { 0, 200 } }, { "p_level", VAR_UINT8 | PROFILE_VALUE, &pidProfiles(0)->P8[PIDLEVEL], .config.minmax = { 0, 200 } },
{ "i_level", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.I8[PIDLEVEL], .config.minmax = { 0, 200 } }, { "i_level", VAR_UINT8 | PROFILE_VALUE, &pidProfiles(0)->I8[PIDLEVEL], .config.minmax = { 0, 200 } },
{ "d_level", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.D8[PIDLEVEL], .config.minmax = { 0, 200 } }, { "d_level", VAR_UINT8 | PROFILE_VALUE, &pidProfiles(0)->D8[PIDLEVEL], .config.minmax = { 0, 200 } },
{ "p_vel", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.P8[PIDVEL], .config.minmax = { 0, 200 } }, { "p_vel", VAR_UINT8 | PROFILE_VALUE, &pidProfiles(0)->P8[PIDVEL], .config.minmax = { 0, 200 } },
{ "i_vel", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.I8[PIDVEL], .config.minmax = { 0, 200 } }, { "i_vel", VAR_UINT8 | PROFILE_VALUE, &pidProfiles(0)->I8[PIDVEL], .config.minmax = { 0, 200 } },
{ "d_vel", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.D8[PIDVEL], .config.minmax = { 0, 200 } }, { "d_vel", VAR_UINT8 | PROFILE_VALUE, &pidProfiles(0)->D8[PIDVEL], .config.minmax = { 0, 200 } },
{ "level_sensitivity", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.levelSensitivity, .config.minmax = { 10, 200 } }, { "level_sensitivity", VAR_UINT8 | PROFILE_VALUE, &pidProfiles(0)->levelSensitivity, .config.minmax = { 10, 200 } },
{ "level_limit", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.levelAngleLimit, .config.minmax = { 10, 120 } }, { "level_limit", VAR_UINT8 | PROFILE_VALUE, &pidProfiles(0)->levelAngleLimit, .config.minmax = { 10, 120 } },
#ifdef BLACKBOX #ifdef BLACKBOX
{ "blackbox_rate_num", VAR_UINT8 | MASTER_VALUE, &blackboxConfig()->rate_num, .config.minmax = { 1, 32 } }, { "blackbox_rate_num", VAR_UINT8 | MASTER_VALUE, &blackboxConfig()->rate_num, .config.minmax = { 1, 32 } },
@ -1304,7 +1304,7 @@ static uint16_t getValueOffset(const clivalue_t *value)
case PROFILE_VALUE: case PROFILE_VALUE:
return value->offset; return value->offset;
case PROFILE_RATE_VALUE: case PROFILE_RATE_VALUE:
return value->offset + sizeof(controlRateConfig_t) * getCurrentControlRateProfile(); return value->offset + sizeof(controlRateConfig_t) * getCurrentControlRateProfileIndex();
} }
return 0; return 0;
} }
@ -1318,7 +1318,7 @@ static void *getValuePointer(const clivalue_t *value)
case PROFILE_VALUE: case PROFILE_VALUE:
return rec->address + value->offset; return rec->address + value->offset;
case PROFILE_RATE_VALUE: case PROFILE_RATE_VALUE:
return rec->address + value->offset + sizeof(controlRateConfig_t) * getCurrentControlRateProfile(); return rec->address + value->offset + sizeof(controlRateConfig_t) * getCurrentControlRateProfileIndex();
} }
return NULL; return NULL;
} }
@ -1370,7 +1370,7 @@ void *getValuePointer(const clivalue_t *value)
} }
if ((value->type & VALUE_SECTION_MASK) == PROFILE_RATE_VALUE) { if ((value->type & VALUE_SECTION_MASK) == PROFILE_RATE_VALUE) {
ptr = ((uint8_t *)ptr) + (sizeof(profile_t) * systemConfig()->current_profile_index) + (sizeof(controlRateConfig_t) * getCurrentControlRateProfile()); ptr = ((uint8_t *)ptr) + (sizeof(profile_t) * systemConfig()->current_profile_index) + (sizeof(controlRateConfig_t) * getCurrentControlRateProfileIndex());
} }
return ptr; return ptr;
@ -3402,7 +3402,7 @@ static void cliPlaySound(char *cmdline)
static void cliProfile(char *cmdline) static void cliProfile(char *cmdline)
{ {
if (isEmpty(cmdline)) { if (isEmpty(cmdline)) {
cliPrintf("profile %d\r\n", getCurrentProfile()); cliPrintf("profile %d\r\n", getCurrentProfileIndex());
return; return;
} else { } else {
const int i = atoi(cmdline); const int i = atoi(cmdline);
@ -3418,7 +3418,7 @@ static void cliProfile(char *cmdline)
static void cliRateProfile(char *cmdline) static void cliRateProfile(char *cmdline)
{ {
if (isEmpty(cmdline)) { if (isEmpty(cmdline)) {
cliPrintf("rateprofile %d\r\n", getCurrentControlRateProfile()); cliPrintf("rateprofile %d\r\n", getCurrentControlRateProfileIndex());
return; return;
} else { } else {
const int i = atoi(cmdline); const int i = atoi(cmdline);
@ -4127,38 +4127,36 @@ static void printConfig(char *cmdline, bool doDiff)
dumpValues(MASTER_VALUE, dumpMask, &defaultConfig); dumpValues(MASTER_VALUE, dumpMask, &defaultConfig);
if (dumpMask & DUMP_ALL) { if (dumpMask & DUMP_ALL) {
const uint8_t activeProfile = systemConfig()->current_profile_index; const uint8_t profileIndexSave = getCurrentProfileIndex();
for (uint32_t profileCount=0; profileCount<MAX_PROFILE_COUNT;profileCount++) { for (uint32_t profileIndex = 0; profileIndex < MAX_PROFILE_COUNT; profileIndex++) {
cliDumpProfile(profileCount, dumpMask, &defaultConfig); cliDumpProfile(profileIndex, dumpMask, &defaultConfig);
const uint8_t currentRateIndex = systemConfig()->activeRateProfile;
for (uint32_t rateCount = 0; rateCount < MAX_RATEPROFILES; rateCount++) {
cliDumpRateProfile(rateCount, dumpMask, &defaultConfig);
} }
changeProfile(profileIndexSave);
changeControlRateProfile(currentRateIndex);
cliPrintHashLine("restore original rateprofile selection");
cliRateProfile("");
}
changeProfile(activeProfile);
cliPrintHashLine("restore original profile selection"); cliPrintHashLine("restore original profile selection");
cliProfile(""); cliProfile("");
const uint8_t controlRateProfileIndexSave = getCurrentControlRateProfileIndex();
for (uint32_t rateIndex = 0; rateIndex < MAX_RATEPROFILES; rateIndex++) {
cliDumpRateProfile(rateIndex, dumpMask, &defaultConfig);
}
changeControlRateProfile(controlRateProfileIndexSave);
cliPrintHashLine("restore original rateprofile selection");
cliRateProfile("");
cliPrintHashLine("save configuration"); cliPrintHashLine("save configuration");
cliPrint("save"); cliPrint("save");
} else { } else {
cliDumpProfile(systemConfig()->current_profile_index, dumpMask, &defaultConfig); cliDumpProfile(getCurrentProfileIndex(), dumpMask, &defaultConfig);
cliDumpRateProfile(systemConfig()->activeRateProfile, dumpMask, &defaultConfig); cliDumpRateProfile(getCurrentControlRateProfileIndex(), dumpMask, &defaultConfig);
} }
} }
if (dumpMask & DUMP_PROFILE) { if (dumpMask & DUMP_PROFILE) {
cliDumpProfile(systemConfig()->current_profile_index, dumpMask, &defaultConfig); cliDumpProfile(getCurrentProfileIndex(), dumpMask, &defaultConfig);
} }
if (dumpMask & DUMP_RATES) { if (dumpMask & DUMP_RATES) {
cliDumpRateProfile(systemConfig()->activeRateProfile, dumpMask, &defaultConfig); cliDumpRateProfile(getCurrentControlRateProfileIndex(), dumpMask, &defaultConfig);
} }
#ifdef USE_PARAMETER_GROUPS #ifdef USE_PARAMETER_GROUPS
// restore configs from copies // restore configs from copies

View file

@ -107,7 +107,6 @@
master_t masterConfig; // master config struct with data independent from profiles master_t masterConfig; // master config struct with data independent from profiles
profile_t *currentProfile; profile_t *currentProfile;
static uint8_t currentControlRateProfileIndex = 0;
controlRateConfig_t *currentControlRateProfile; controlRateConfig_t *currentControlRateProfile;
#ifndef USE_PARAMETER_GROUPS #ifndef USE_PARAMETER_GROUPS
@ -715,32 +714,30 @@ void resetFlashConfig(flashConfig_t *flashConfig)
} }
#endif #endif
uint8_t getCurrentProfile(void) uint8_t getCurrentProfileIndex(void)
{ {
return systemConfig()->current_profile_index; return systemConfig()->current_profile_index;
;
} }
static void setProfile(uint8_t profileIndex) static void setProfile(uint8_t profileIndex)
{ {
if (profileIndex < MAX_PROFILE_COUNT) {
systemConfigMutable()->current_profile_index = profileIndex;
currentProfile = &masterConfig.profile[profileIndex]; currentProfile = &masterConfig.profile[profileIndex];
} }
}
uint8_t getCurrentControlRateProfile(void) uint8_t getCurrentControlRateProfileIndex(void)
{ {
return currentControlRateProfileIndex; return systemConfigMutable()->activeRateProfile;
} }
static void setControlRateProfile(uint8_t controlRateProfileIndex) static void setControlRateProfile(uint8_t controlRateProfileIndex)
{ {
if (controlRateProfileIndex < MAX_CONTROL_RATE_PROFILE_COUNT) {
systemConfigMutable()->activeRateProfile = controlRateProfileIndex; systemConfigMutable()->activeRateProfile = controlRateProfileIndex;
currentControlRateProfileIndex = controlRateProfileIndex;
currentControlRateProfile = controlRateProfilesMutable(controlRateProfileIndex); currentControlRateProfile = controlRateProfilesMutable(controlRateProfileIndex);
} }
const controlRateConfig_t *getControlRateConfig(uint8_t controlRateProfileIndex)
{
return controlRateProfiles(controlRateProfileIndex);
} }
uint16_t getCurrentMinthrottle(void) uint16_t getCurrentMinthrottle(void)
@ -1256,7 +1253,7 @@ void readEEPROM(void)
failureMode(FAILURE_INVALID_EEPROM_CONTENTS); failureMode(FAILURE_INVALID_EEPROM_CONTENTS);
} }
// pgActivateProfile(getCurrentProfile()); // pgActivateProfile(getCurrentProfileIndex());
// setControlRateProfile(rateProfileSelection()->defaultRateProfileIndex); // setControlRateProfile(rateProfileSelection()->defaultRateProfileIndex);
if (systemConfig()->current_profile_index > MAX_PROFILE_COUNT - 1) {// sanity check if (systemConfig()->current_profile_index > MAX_PROFILE_COUNT - 1) {// sanity check

View file

@ -101,8 +101,6 @@ void setBeeperOffMask(uint32_t mask);
uint32_t getPreferredBeeperOffMask(void); uint32_t getPreferredBeeperOffMask(void);
void setPreferredBeeperOffMask(uint32_t mask); void setPreferredBeeperOffMask(uint32_t mask);
void copyCurrentProfileToProfileSlot(uint8_t profileSlotIndex);
void initEEPROM(void); void initEEPROM(void);
void resetEEPROM(void); void resetEEPROM(void);
void readEEPROM(void); void readEEPROM(void);
@ -114,13 +112,14 @@ void validateAndFixConfig(void);
void validateAndFixGyroConfig(void); void validateAndFixGyroConfig(void);
void activateConfig(void); void activateConfig(void);
uint8_t getCurrentProfile(void); uint8_t getCurrentProfileIndex(void);
void changeProfile(uint8_t profileIndex); void changeProfile(uint8_t profileIndex);
struct profile_s; struct profile_s;
void resetProfile(struct profile_s *profile); void resetProfile(struct profile_s *profile);
uint8_t getCurrentControlRateProfile(void); uint8_t getCurrentControlRateProfileIndex(void);
void changeControlRateProfile(uint8_t profileIndex); void changeControlRateProfile(uint8_t profileIndex);
bool canSoftwareSerialBeUsed(void); bool canSoftwareSerialBeUsed(void);
uint16_t getCurrentMinthrottle(void); uint16_t getCurrentMinthrottle(void);

View file

@ -612,10 +612,10 @@ static bool mspFcProcessOutCommand(uint8_t cmdMSP, sbuf_t *dst, mspPostProcessFn
#endif #endif
sbufWriteU16(dst, sensors(SENSOR_ACC) | sensors(SENSOR_BARO) << 1 | sensors(SENSOR_MAG) << 2 | sensors(SENSOR_GPS) << 3 | sensors(SENSOR_SONAR) << 4); sbufWriteU16(dst, sensors(SENSOR_ACC) | sensors(SENSOR_BARO) << 1 | sensors(SENSOR_MAG) << 2 | sensors(SENSOR_GPS) << 3 | sensors(SENSOR_SONAR) << 4);
sbufWriteU32(dst, packFlightModeFlags()); sbufWriteU32(dst, packFlightModeFlags());
sbufWriteU8(dst, getCurrentProfile()); sbufWriteU8(dst, getCurrentProfileIndex());
sbufWriteU16(dst, constrain(averageSystemLoadPercent, 0, 100)); sbufWriteU16(dst, constrain(averageSystemLoadPercent, 0, 100));
sbufWriteU8(dst, MAX_PROFILE_COUNT); sbufWriteU8(dst, MAX_PROFILE_COUNT);
sbufWriteU8(dst, getCurrentControlRateProfile()); sbufWriteU8(dst, getCurrentControlRateProfileIndex());
break; break;
case MSP_NAME: case MSP_NAME:
@ -636,7 +636,7 @@ static bool mspFcProcessOutCommand(uint8_t cmdMSP, sbuf_t *dst, mspPostProcessFn
#endif #endif
sbufWriteU16(dst, sensors(SENSOR_ACC) | sensors(SENSOR_BARO) << 1 | sensors(SENSOR_MAG) << 2 | sensors(SENSOR_GPS) << 3 | sensors(SENSOR_SONAR) << 4); sbufWriteU16(dst, sensors(SENSOR_ACC) | sensors(SENSOR_BARO) << 1 | sensors(SENSOR_MAG) << 2 | sensors(SENSOR_GPS) << 3 | sensors(SENSOR_SONAR) << 4);
sbufWriteU32(dst, packFlightModeFlags()); sbufWriteU32(dst, packFlightModeFlags());
sbufWriteU8(dst, systemConfig()->current_profile_index); sbufWriteU8(dst, getCurrentProfileIndex());
sbufWriteU16(dst, constrain(averageSystemLoadPercent, 0, 100)); sbufWriteU16(dst, constrain(averageSystemLoadPercent, 0, 100));
sbufWriteU16(dst, 0); // gyro cycle time sbufWriteU16(dst, 0); // gyro cycle time
break; break;

View file

@ -362,7 +362,7 @@ static void applySelectAdjustment(uint8_t adjustmentFunction, uint8_t position)
switch(adjustmentFunction) { switch(adjustmentFunction) {
case ADJUSTMENT_RATE_PROFILE: case ADJUSTMENT_RATE_PROFILE:
if (getCurrentControlRateProfile() != position) { if (getCurrentControlRateProfileIndex() != position) {
changeControlRateProfile(position); changeControlRateProfile(position);
blackboxLogInflightAdjustmentEvent(ADJUSTMENT_RATE_PROFILE, position); blackboxLogInflightAdjustmentEvent(ADJUSTMENT_RATE_PROFILE, position);
applied = true; applied = true;

View file

@ -42,11 +42,10 @@
#include "common/axis.h" #include "common/axis.h"
#include "common/typeconversion.h" #include "common/typeconversion.h"
#include "sensors/battery.h" #include "config/feature.h"
#include "sensors/sensors.h" #include "config/config_profile.h"
#include "sensors/compass.h" #include "config/parameter_group.h"
#include "sensors/acceleration.h" #include "config/parameter_group_ids.h"
#include "sensors/gyro.h"
#include "fc/config.h" #include "fc/config.h"
#include "fc/rc_controls.h" #include "fc/rc_controls.h"
@ -55,26 +54,22 @@
#include "flight/pid.h" #include "flight/pid.h"
#include "flight/imu.h" #include "flight/imu.h"
#include "flight/failsafe.h" #include "flight/failsafe.h"
#include "io/displayport_oled.h"
#ifdef GPS
#include "io/gps.h"
#include "flight/navigation.h" #include "flight/navigation.h"
#endif
#include "config/feature.h"
#include "config/config_profile.h"
#include "io/gps.h"
#include "io/dashboard.h" #include "io/dashboard.h"
#include "io/displayport_oled.h"
#include "rx/rx.h" #include "rx/rx.h"
#include "scheduler/scheduler.h" #include "scheduler/scheduler.h"
extern profile_t *currentProfile; #include "sensors/acceleration.h"
#include "sensors/battery.h"
#include "sensors/compass.h"
#include "sensors/gyro.h"
#include "sensors/sensors.h"
controlRateConfig_t *getControlRateConfig(uint8_t profileIndex);
#define MICROSECONDS_IN_A_SECOND (1000 * 1000) #define MICROSECONDS_IN_A_SECOND (1000 * 1000)
@ -321,7 +316,7 @@ void showProfilePage(void)
{ {
uint8_t rowIndex = PAGE_TITLE_LINE_COUNT; uint8_t rowIndex = PAGE_TITLE_LINE_COUNT;
tfp_sprintf(lineBuffer, "Profile: %d", getCurrentProfile()); tfp_sprintf(lineBuffer, "Profile: %d", getCurrentProfileIndex());
i2c_OLED_set_line(rowIndex++); i2c_OLED_set_line(rowIndex++);
i2c_OLED_send_string(lineBuffer); i2c_OLED_send_string(lineBuffer);
@ -339,12 +334,12 @@ void showProfilePage(void)
i2c_OLED_send_string(lineBuffer); i2c_OLED_send_string(lineBuffer);
} }
const uint8_t currentRateProfileIndex = getCurrentControlRateProfile(); const uint8_t currentRateProfileIndex = getCurrentControlRateProfileIndex();
tfp_sprintf(lineBuffer, "Rate profile: %d", currentRateProfileIndex); tfp_sprintf(lineBuffer, "Rate profile: %d", currentRateProfileIndex);
i2c_OLED_set_line(rowIndex++); i2c_OLED_set_line(rowIndex++);
i2c_OLED_send_string(lineBuffer); i2c_OLED_send_string(lineBuffer);
const controlRateConfig_t *controlRateConfig = getControlRateConfig(currentRateProfileIndex); const controlRateConfig_t *controlRateConfig = controlRateProfiles(currentRateProfileIndex);
tfp_sprintf(lineBuffer, "RCE: %d, RCR: %d", tfp_sprintf(lineBuffer, "RCE: %d, RCR: %d",
controlRateConfig->rcExpo8, controlRateConfig->rcExpo8,
controlRateConfig->rcRate8 controlRateConfig->rcRate8

View file

@ -393,8 +393,8 @@ static void osdDrawSingleElement(uint8_t item)
case OSD_PIDRATE_PROFILE: case OSD_PIDRATE_PROFILE:
{ {
const uint8_t profileIndex = systemConfig()->current_profile_index; const uint8_t profileIndex = getCurrentProfileIndex();
const uint8_t rateProfileIndex = systemConfig()->activeRateProfile; const uint8_t rateProfileIndex = getCurrentControlRateProfileIndex();
sprintf(buff, "%d-%d", profileIndex + 1, rateProfileIndex + 1); sprintf(buff, "%d-%d", profileIndex + 1, rateProfileIndex + 1);
break; break;
} }

View file

@ -598,7 +598,7 @@ static bool bstSlaveProcessFeedbackCommand(uint8_t bstRequest)
junk |= 1 << i; junk |= 1 << i;
} }
bstWrite32(junk); bstWrite32(junk);
bstWrite8(systemConfig()->current_profile_index); bstWrite8(getCurrentProfileIndex());
break; break;
case BST_RAW_IMU: case BST_RAW_IMU:
{ {