Skip to content

Commit f812d5c

Browse files
committed
Drop gyro method of ITerm relax
1 parent 2025c15 commit f812d5c

File tree

6 files changed

+10
-48
lines changed

6 files changed

+10
-48
lines changed

src/main/build/debug.h

Lines changed: 0 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -63,7 +63,6 @@ typedef enum {
6363
DEBUG_REM_FLIGHT_TIME,
6464
DEBUG_SMARTAUDIO,
6565
DEBUG_ACC,
66-
DEBUG_ITERM_RELAX,
6766
DEBUG_ERPM,
6867
DEBUG_RPM_FILTER,
6968
DEBUG_RPM_FREQ,

src/main/common/maths.c

Lines changed: 0 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -142,15 +142,6 @@ int32_t applyDeadband(int32_t value, int32_t deadband)
142142
return value;
143143
}
144144

145-
float fapplyDeadbandf(float value, float deadband)
146-
{
147-
if (fabsf(value) < deadband) {
148-
return 0;
149-
}
150-
151-
return value >= 0 ? value - deadband : value + deadband;
152-
}
153-
154145
int constrain(int amt, int low, int high)
155146
{
156147
if (amt < low)

src/main/common/maths.h

Lines changed: 0 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -130,7 +130,6 @@ bool sensorCalibrationSolveForScale(sensorCalibrationState_t * state, float resu
130130

131131
int gcd(int num, int denom);
132132
int32_t applyDeadband(int32_t value, int32_t deadband);
133-
float fapplyDeadbandf(float value, float deadband);
134133

135134
int constrain(int amt, int low, int high);
136135
float constrainf(float amt, float low, float high);

src/main/fc/settings.yaml

Lines changed: 1 addition & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -82,7 +82,7 @@ tables:
8282
- name: debug_modes
8383
values: ["NONE", "GYRO", "AGL", "FLOW_RAW",
8484
"FLOW", "SBUS", "FPORT", "ALWAYS", "SAG_COMP_VOLTAGE",
85-
"VIBE", "CRUISE", "REM_FLIGHT_TIME", "SMARTAUDIO", "ACC", "ITERM_RELAX",
85+
"VIBE", "CRUISE", "REM_FLIGHT_TIME", "SMARTAUDIO", "ACC",
8686
"ERPM", "RPM_FILTER", "RPM_FREQ", "NAV_YAW", "DYNAMIC_FILTER", "DYNAMIC_FILTER_FREQUENCY",
8787
"IRLOCK", "CD", "KALMAN_GAIN", "PID_MEASUREMENT", "SPM_CELLS", "SPM_VS600", "SPM_VARIO", "PCF8574"]
8888
- name: async_mode
@@ -124,9 +124,6 @@ tables:
124124
- name: iterm_relax
125125
values: ["OFF", "RP", "RPY"]
126126
enum: itermRelax_e
127-
- name: iterm_relax_type
128-
values: ["GYRO", "SETPOINT"]
129-
enum: itermRelaxType_e
130127
- name: airmodeHandlingType
131128
values: ["STICK_CENTER", "THROTTLE_THRESHOLD"]
132129
- name: nav_extra_arming_safety
@@ -1727,9 +1724,6 @@ groups:
17271724
field: navFwPosHdgPidsumLimit
17281725
min: PID_SUM_LIMIT_MIN
17291726
max: PID_SUM_LIMIT_MAX
1730-
- name: mc_iterm_relax_type
1731-
field: iterm_relax_type
1732-
table: iterm_relax_type
17331727
- name: mc_iterm_relax
17341728
field: iterm_relax
17351729
table: iterm_relax

src/main/flight/pid.c

Lines changed: 9 additions & 24 deletions
Original file line numberDiff line numberDiff line change
@@ -124,7 +124,6 @@ int32_t axisPID_P[FLIGHT_DYNAMICS_INDEX_COUNT], axisPID_I[FLIGHT_DYNAMICS_INDEX_
124124
static EXTENDED_FASTRAM pidState_t pidState[FLIGHT_DYNAMICS_INDEX_COUNT];
125125
static EXTENDED_FASTRAM pt1Filter_t windupLpf[XYZ_AXIS_COUNT];
126126
static EXTENDED_FASTRAM uint8_t itermRelax;
127-
static EXTENDED_FASTRAM uint8_t itermRelaxType;
128127

129128
#ifdef USE_ANTIGRAVITY
130129
static EXTENDED_FASTRAM pt1Filter_t antigravityThrottleLpf;
@@ -155,7 +154,7 @@ static EXTENDED_FASTRAM filterApplyFnPtr dTermLpfFilterApplyFn;
155154
static EXTENDED_FASTRAM filterApplyFnPtr dTermLpf2FilterApplyFn;
156155
static EXTENDED_FASTRAM bool levelingEnabled = false;
157156

158-
PG_REGISTER_PROFILE_WITH_RESET_TEMPLATE(pidProfile_t, pidProfile, PG_PID_PROFILE, 14);
157+
PG_REGISTER_PROFILE_WITH_RESET_TEMPLATE(pidProfile_t, pidProfile, PG_PID_PROFILE, 15);
159158

160159
PG_RESET_TEMPLATE(pidProfile_t, pidProfile,
161160
.bank_mc = {
@@ -264,7 +263,6 @@ PG_RESET_TEMPLATE(pidProfile_t, pidProfile,
264263
.navVelXyDtermAttenuation = 90,
265264
.navVelXyDtermAttenuationStart = 10,
266265
.navVelXyDtermAttenuationEnd = 60,
267-
.iterm_relax_type = ITERM_RELAX_SETPOINT,
268266
.iterm_relax_cutoff = MC_ITERM_RELAX_CUTOFF_DEFAULT,
269267
.iterm_relax = ITERM_RELAX_RP,
270268
.dBoostFactor = 1.25f,
@@ -636,31 +634,20 @@ static void NOINLINE pidApplyFixedWingRateController(pidState_t *pidState, fligh
636634
#endif
637635
}
638636

639-
static void FAST_CODE applyItermRelax(const int axis, const float gyroRate, float currentPidSetpoint, float *itermErrorRate)
637+
static float FAST_CODE applyItermRelax(const int axis, float currentPidSetpoint, float itermErrorRate)
640638
{
641-
const float setpointLpf = pt1FilterApply(&windupLpf[axis], currentPidSetpoint);
642-
const float setpointHpf = fabsf(currentPidSetpoint - setpointLpf);
643-
644639
if (itermRelax) {
645640
if (axis < FD_YAW || itermRelax == ITERM_RELAX_RPY) {
646641

642+
const float setpointLpf = pt1FilterApply(&windupLpf[axis], currentPidSetpoint);
643+
const float setpointHpf = fabsf(currentPidSetpoint - setpointLpf);
644+
647645
const float itermRelaxFactor = MAX(0, 1 - setpointHpf / MC_ITERM_RELAX_SETPOINT_THRESHOLD);
648-
649-
if (itermRelaxType == ITERM_RELAX_SETPOINT) {
650-
*itermErrorRate *= itermRelaxFactor;
651-
} else if (itermRelaxType == ITERM_RELAX_GYRO ) {
652-
*itermErrorRate = fapplyDeadbandf(setpointLpf - gyroRate, setpointHpf);
653-
} else {
654-
*itermErrorRate = 0.0f;
655-
}
656-
657-
if (axis == FD_ROLL) {
658-
DEBUG_SET(DEBUG_ITERM_RELAX, 0, lrintf(setpointHpf));
659-
DEBUG_SET(DEBUG_ITERM_RELAX, 1, lrintf(itermRelaxFactor * 100.0f));
660-
DEBUG_SET(DEBUG_ITERM_RELAX, 2, lrintf(*itermErrorRate));
661-
}
646+
return itermErrorRate * itermRelaxFactor;
662647
}
663648
}
649+
650+
return itermErrorRate;
664651
}
665652
#ifdef USE_D_BOOST
666653
static float FAST_CODE applyDBoost(pidState_t *pidState, float dT) {
@@ -727,8 +714,7 @@ static void FAST_CODE NOINLINE pidApplyMulticopterRateController(pidState_t *pid
727714
const float newOutput = newPTerm + newDTerm + pidState->errorGyroIf + newCDTerm;
728715
const float newOutputLimited = constrainf(newOutput, -pidState->pidSumLimit, +pidState->pidSumLimit);
729716

730-
float itermErrorRate = rateError;
731-
applyItermRelax(axis, pidState->gyroRate, pidState->rateTarget, &itermErrorRate);
717+
float itermErrorRate = applyItermRelax(axis, pidState->rateTarget, rateError);
732718

733719
#ifdef USE_ANTIGRAVITY
734720
itermErrorRate *= iTermAntigravityGain;
@@ -1046,7 +1032,6 @@ void pidInit(void)
10461032
pidGainsUpdateRequired = false;
10471033

10481034
itermRelax = pidProfile()->iterm_relax;
1049-
itermRelaxType = pidProfile()->iterm_relax_type;
10501035

10511036
yawLpfHz = pidProfile()->yaw_lpf_hz;
10521037
motorItermWindupPoint = 1.0f - (pidProfile()->itermWindupPointPercent / 100.0f);

src/main/flight/pid.h

Lines changed: 0 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -97,11 +97,6 @@ typedef enum {
9797
ITERM_RELAX_RPY
9898
} itermRelax_e;
9999

100-
typedef enum {
101-
ITERM_RELAX_GYRO = 0,
102-
ITERM_RELAX_SETPOINT
103-
} itermRelaxType_e;
104-
105100
typedef struct pidProfile_s {
106101
uint8_t pidControllerType;
107102
pidBank_t bank_fw;
@@ -138,7 +133,6 @@ typedef struct pidProfile_s {
138133
uint8_t navVelXyDtermAttenuation; // VEL_XY dynamic Dterm scale: Dterm will be attenuatedby this value (in percent) when UAV is traveling with more than navVelXyDtermAttenuationStart percents of max velocity
139134
uint8_t navVelXyDtermAttenuationStart; // VEL_XY dynamic Dterm scale: Dterm attenuation will begin at this percent of max velocity
140135
uint8_t navVelXyDtermAttenuationEnd; // VEL_XY dynamic Dterm scale: Dterm will be fully attenuated at this percent of max velocity
141-
uint8_t iterm_relax_type; // Specifies type of relax algorithm
142136
uint8_t iterm_relax_cutoff; // This cutoff frequency specifies a low pass filter which predicts average response of the quad to setpoint
143137
uint8_t iterm_relax; // Enable iterm suppression during stick input
144138

0 commit comments

Comments
 (0)