Moved masterConfig throttle correction items into a struct
This commit is contained in:
parent
18b052e246
commit
84467ea0e1
|
@ -109,8 +109,8 @@ typedef struct master_s {
|
||||||
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
|
throttleCorrectionConfig_t throttleCorrectionConfig;
|
||||||
uint8_t throttle_correction_value; // the correction that will be applied at throttle_correction_angle.
|
|
||||||
batteryConfig_t batteryConfig;
|
batteryConfig_t batteryConfig;
|
||||||
|
|
||||||
// Radio/ESC-related configuration
|
// Radio/ESC-related configuration
|
||||||
|
|
|
@ -719,8 +719,8 @@ void createDefaultConfig(master_t *config)
|
||||||
|
|
||||||
resetRcControlsConfig(&config->rcControlsConfig);
|
resetRcControlsConfig(&config->rcControlsConfig);
|
||||||
|
|
||||||
config->throttle_correction_value = 0; // could 10 with althold or 40 for fpv
|
config->throttleCorrectionConfig.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
|
config->throttleCorrectionConfig.throttle_correction_angle = 800; // could be 80.0 deg with atlhold or 45.0 for fpv
|
||||||
|
|
||||||
// Failsafe Variables
|
// Failsafe Variables
|
||||||
config->failsafeConfig.failsafe_delay = 10; // 1sec
|
config->failsafeConfig.failsafe_delay = 10; // 1sec
|
||||||
|
@ -867,7 +867,7 @@ void activateConfig(void)
|
||||||
&imuRuntimeConfig,
|
&imuRuntimeConfig,
|
||||||
¤tProfile->pidProfile,
|
¤tProfile->pidProfile,
|
||||||
&masterConfig.accDeadband,
|
&masterConfig.accDeadband,
|
||||||
masterConfig.throttle_correction_angle
|
masterConfig.throttleCorrectionConfig.throttle_correction_angle
|
||||||
);
|
);
|
||||||
|
|
||||||
configureAltitudeHold(
|
configureAltitudeHold(
|
||||||
|
|
|
@ -745,8 +745,8 @@ void subTaskMainSubprocesses(void)
|
||||||
setpointRate[YAW] = 0;
|
setpointRate[YAW] = 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
if (masterConfig.throttle_correction_value && (FLIGHT_MODE(ANGLE_MODE) || FLIGHT_MODE(HORIZON_MODE))) {
|
if (masterConfig.throttleCorrectionConfig.throttle_correction_value && (FLIGHT_MODE(ANGLE_MODE) || FLIGHT_MODE(HORIZON_MODE))) {
|
||||||
rcCommand[THROTTLE] += calculateThrottleAngleCorrection(masterConfig.throttle_correction_value);
|
rcCommand[THROTTLE] += calculateThrottleAngleCorrection(masterConfig.throttleCorrectionConfig.throttle_correction_value);
|
||||||
}
|
}
|
||||||
|
|
||||||
processRcCommand();
|
processRcCommand();
|
||||||
|
|
|
@ -51,6 +51,11 @@ typedef struct accDeadband_s {
|
||||||
uint8_t z; // set the acc deadband for z-Axis, this ignores small accelerations
|
uint8_t z; // set the acc deadband for z-Axis, this ignores small accelerations
|
||||||
} accDeadband_t;
|
} accDeadband_t;
|
||||||
|
|
||||||
|
typedef struct throttleCorrectionConfig_s {
|
||||||
|
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.
|
||||||
|
} throttleCorrectionConfig_t;
|
||||||
|
|
||||||
typedef struct imuRuntimeConfig_s {
|
typedef struct imuRuntimeConfig_s {
|
||||||
uint8_t acc_cut_hz;
|
uint8_t acc_cut_hz;
|
||||||
uint8_t acc_unarmedcal;
|
uint8_t acc_unarmedcal;
|
||||||
|
|
|
@ -827,8 +827,8 @@ const clivalue_t valueTable[] = {
|
||||||
{ "deadband", VAR_UINT8 | MASTER_VALUE, &masterConfig.rcControlsConfig.deadband, .config.minmax = { 0, 32 } },
|
{ "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 } },
|
{ "yaw_deadband", VAR_UINT8 | MASTER_VALUE, &masterConfig.rcControlsConfig.yaw_deadband, .config.minmax = { 0, 100 } },
|
||||||
|
|
||||||
{ "throttle_correction_value", VAR_UINT8 | MASTER_VALUE, &masterConfig.throttle_correction_value, .config.minmax = { 0, 150 } },
|
{ "throttle_correction_value", VAR_UINT8 | MASTER_VALUE, &masterConfig.throttleCorrectionConfig.throttle_correction_value, .config.minmax = { 0, 150 } },
|
||||||
{ "throttle_correction_angle", VAR_UINT16 | MASTER_VALUE, &masterConfig.throttle_correction_angle, .config.minmax = { 1, 900 } },
|
{ "throttle_correction_angle", VAR_UINT16 | MASTER_VALUE, &masterConfig.throttleCorrectionConfig.throttle_correction_angle, .config.minmax = { 1, 900 } },
|
||||||
|
|
||||||
{ "yaw_control_direction", VAR_INT8 | MASTER_VALUE, &masterConfig.yaw_control_direction, .config.minmax = { -1, 1 } },
|
{ "yaw_control_direction", VAR_INT8 | MASTER_VALUE, &masterConfig.yaw_control_direction, .config.minmax = { -1, 1 } },
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue