2 * This file is part of Cleanflight.
4 * Cleanflight is free software: you can redistribute it and/or modify
5 * it under the terms of the GNU General Public License as published by
6 * the Free Software Foundation, either version 3 of the License, or
7 * (at your option) any later version.
9 * Cleanflight is distributed in the hope that it will be useful,
10 * but WITHOUT ANY WARRANTY; without even the implied warranty of
11 * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
12 * GNU General Public License for more details.
14 * You should have received a copy of the GNU General Public License
15 * along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
24 #include "build/build_config.h"
25 #include "build/debug.h"
27 #include "common/axis.h"
28 #include "common/filter.h"
29 #include "common/maths.h"
30 #include "common/utils.h"
31 #include "common/fp_pid.h"
33 #include "config/parameter_group.h"
34 #include "config/parameter_group_ids.h"
36 #include "fc/config.h"
37 #include "fc/controlrate_profile.h"
38 #include "fc/rc_controls.h"
39 #include "fc/rc_modes.h"
40 #include "fc/runtime_config.h"
41 #include "fc/settings.h"
43 #include "flight/pid.h"
44 #include "flight/imu.h"
45 #include "flight/mixer.h"
46 #include "flight/mixer_profile.h"
47 #include "flight/rpm_filter.h"
48 #include "flight/kalman.h"
49 #include "flight/smith_predictor.h"
53 #include "navigation/navigation.h"
57 #include "sensors/battery.h"
58 #include "sensors/sensors.h"
59 #include "sensors/gyro.h"
60 #include "sensors/acceleration.h"
61 #include "sensors/compass.h"
62 #include "sensors/pitotmeter.h"
64 #include "scheduler/scheduler.h"
66 #include "programming/logic_condition.h"
70 float kP
; // Proportional gain
71 float kI
; // Integral gain
72 float kD
; // Derivative gain
73 float kFF
; // Feed-forward gain
74 float kCD
; // Control Derivative
75 float kT
; // Back-calculation tracking gain
82 float errorGyroIfLimit
;
84 // Used for ANGLE filtering (PT1, we don't need super-sharpness here)
85 pt1Filter_t angleFilterState
;
88 rateLimitFilter_t axisAccelFilter
;
89 pt1Filter_t ptermLpfState
;
90 filter_t dtermLpfState
;
94 float previousRateTarget
;
95 float previousRateGyro
;
98 pt1Filter_t dBoostLpf
;
99 biquadFilter_t dBoostGyroLpf
;
100 float dBoostTargetAcceleration
;
102 uint16_t pidSumLimit
;
103 filterApply4FnPtr ptermFilterApplyFn
;
104 bool itermLimitActive
;
105 bool itermFreezeActive
;
107 pt3Filter_t rateTargetFilter
;
109 smithPredictor_t smithPredictor
;
112 STATIC_FASTRAM
bool pidFiltersConfigured
= false;
113 static EXTENDED_FASTRAM
float headingHoldCosZLimit
;
114 static EXTENDED_FASTRAM
int16_t headingHoldTarget
;
115 static EXTENDED_FASTRAM pt1Filter_t headingHoldRateFilter
;
116 static EXTENDED_FASTRAM pt1Filter_t fixedWingTpaFilter
;
118 // Thrust PID Attenuation factor. 0.0f means fully attenuated, 1.0f no attenuation is applied
119 STATIC_FASTRAM
bool pidGainsUpdateRequired
;
120 FASTRAM
int16_t axisPID
[FLIGHT_DYNAMICS_INDEX_COUNT
];
123 int32_t axisPID_P
[FLIGHT_DYNAMICS_INDEX_COUNT
];
124 int32_t axisPID_I
[FLIGHT_DYNAMICS_INDEX_COUNT
];
125 int32_t axisPID_D
[FLIGHT_DYNAMICS_INDEX_COUNT
];
126 int32_t axisPID_F
[FLIGHT_DYNAMICS_INDEX_COUNT
];
127 int32_t axisPID_Setpoint
[FLIGHT_DYNAMICS_INDEX_COUNT
];
130 static EXTENDED_FASTRAM pidState_t pidState
[FLIGHT_DYNAMICS_INDEX_COUNT
];
131 static EXTENDED_FASTRAM pt1Filter_t windupLpf
[XYZ_AXIS_COUNT
];
132 static EXTENDED_FASTRAM
uint8_t itermRelax
;
134 #ifdef USE_ANTIGRAVITY
135 static EXTENDED_FASTRAM pt1Filter_t antigravityThrottleLpf
;
136 static EXTENDED_FASTRAM
float antigravityThrottleHpf
;
137 static EXTENDED_FASTRAM
float antigravityGain
;
138 static EXTENDED_FASTRAM
float antigravityAccelerator
;
141 #define D_BOOST_GYRO_LPF_HZ 80 // Biquad lowpass input cutoff to peak D around propwash frequencies
142 #define D_BOOST_LPF_HZ 7 // PT1 lowpass cutoff to smooth the boost effect
145 static EXTENDED_FASTRAM
float dBoostMin
;
146 static EXTENDED_FASTRAM
float dBoostMax
;
147 static EXTENDED_FASTRAM
float dBoostMaxAtAlleceleration
;
150 static EXTENDED_FASTRAM
uint8_t yawLpfHz
;
151 static EXTENDED_FASTRAM
float motorItermWindupPoint
;
152 static EXTENDED_FASTRAM
float antiWindupScaler
;
153 #ifdef USE_ANTIGRAVITY
154 static EXTENDED_FASTRAM
float iTermAntigravityGain
;
156 static EXTENDED_FASTRAM
uint8_t usedPidControllerType
;
158 typedef void (*pidControllerFnPtr
)(pidState_t
*pidState
, flight_dynamics_index_t axis
, float dT
, float dT_inv
);
159 static EXTENDED_FASTRAM pidControllerFnPtr pidControllerApplyFn
;
160 static EXTENDED_FASTRAM filterApplyFnPtr dTermLpfFilterApplyFn
;
161 static EXTENDED_FASTRAM
bool levelingEnabled
= false;
163 #define FIXED_WING_LEVEL_TRIM_MAX_ANGLE 10.0f // Max angle auto trimming can demand
164 #define FIXED_WING_LEVEL_TRIM_DIVIDER 50.0f
165 #define FIXED_WING_LEVEL_TRIM_MULTIPLIER 1.0f / FIXED_WING_LEVEL_TRIM_DIVIDER
166 #define FIXED_WING_LEVEL_TRIM_CONTROLLER_LIMIT FIXED_WING_LEVEL_TRIM_DIVIDER * FIXED_WING_LEVEL_TRIM_MAX_ANGLE
168 static EXTENDED_FASTRAM
float fixedWingLevelTrim
;
169 static EXTENDED_FASTRAM pidController_t fixedWingLevelTrimController
;
171 PG_REGISTER_PROFILE_WITH_RESET_TEMPLATE(pidProfile_t
, pidProfile
, PG_PID_PROFILE
, 6);
173 PG_RESET_TEMPLATE(pidProfile_t
, pidProfile
,
176 [PID_ROLL
] = { SETTING_MC_P_ROLL_DEFAULT
, SETTING_MC_I_ROLL_DEFAULT
, SETTING_MC_D_ROLL_DEFAULT
, SETTING_MC_CD_ROLL_DEFAULT
},
177 [PID_PITCH
] = { SETTING_MC_P_PITCH_DEFAULT
, SETTING_MC_I_PITCH_DEFAULT
, SETTING_MC_D_PITCH_DEFAULT
, SETTING_MC_CD_PITCH_DEFAULT
},
178 [PID_YAW
] = { SETTING_MC_P_YAW_DEFAULT
, SETTING_MC_I_YAW_DEFAULT
, SETTING_MC_D_YAW_DEFAULT
, SETTING_MC_CD_YAW_DEFAULT
},
180 .P
= SETTING_MC_P_LEVEL_DEFAULT
, // Self-level strength
181 .I
= SETTING_MC_I_LEVEL_DEFAULT
, // Self-leveing low-pass frequency (0 - disabled)
182 .D
= SETTING_MC_D_LEVEL_DEFAULT
, // 75% horizon strength
185 [PID_HEADING
] = { SETTING_NAV_MC_HEADING_P_DEFAULT
, 0, 0, 0 },
187 .P
= SETTING_NAV_MC_POS_XY_P_DEFAULT
, // NAV_POS_XY_P * 100
193 .P
= SETTING_NAV_MC_VEL_XY_P_DEFAULT
, // NAV_VEL_XY_P * 20
194 .I
= SETTING_NAV_MC_VEL_XY_I_DEFAULT
, // NAV_VEL_XY_I * 100
195 .D
= SETTING_NAV_MC_VEL_XY_D_DEFAULT
, // NAV_VEL_XY_D * 100
196 .FF
= SETTING_NAV_MC_VEL_XY_FF_DEFAULT
, // NAV_VEL_XY_D * 100
199 .P
= SETTING_NAV_MC_POS_Z_P_DEFAULT
, // NAV_POS_Z_P * 100
205 .P
= SETTING_NAV_MC_VEL_Z_P_DEFAULT
, // NAV_VEL_Z_P * 66.7
206 .I
= SETTING_NAV_MC_VEL_Z_I_DEFAULT
, // NAV_VEL_Z_I * 20
207 .D
= SETTING_NAV_MC_VEL_Z_D_DEFAULT
, // NAV_VEL_Z_D * 100
210 [PID_POS_HEADING
] = {
221 [PID_ROLL
] = { SETTING_FW_P_ROLL_DEFAULT
, SETTING_FW_I_ROLL_DEFAULT
, 0, SETTING_FW_FF_ROLL_DEFAULT
},
222 [PID_PITCH
] = { SETTING_FW_P_PITCH_DEFAULT
, SETTING_FW_I_PITCH_DEFAULT
, 0, SETTING_FW_FF_PITCH_DEFAULT
},
223 [PID_YAW
] = { SETTING_FW_P_YAW_DEFAULT
, SETTING_FW_I_YAW_DEFAULT
, 0, SETTING_FW_FF_YAW_DEFAULT
},
225 .P
= SETTING_FW_P_LEVEL_DEFAULT
, // Self-level strength
226 .I
= SETTING_FW_I_LEVEL_DEFAULT
, // Self-leveing low-pass frequency (0 - disabled)
227 .D
= SETTING_FW_D_LEVEL_DEFAULT
, // 75% horizon strength
230 [PID_HEADING
] = { SETTING_NAV_FW_HEADING_P_DEFAULT
, 0, 0, 0 },
232 .P
= SETTING_NAV_FW_POS_Z_P_DEFAULT
, // FW_POS_Z_P * 10
233 .I
= SETTING_NAV_FW_POS_Z_I_DEFAULT
, // FW_POS_Z_I * 10
234 .D
= SETTING_NAV_FW_POS_Z_D_DEFAULT
, // FW_POS_Z_D * 10
238 .P
= SETTING_NAV_FW_POS_XY_P_DEFAULT
, // FW_POS_XY_P * 100
239 .I
= SETTING_NAV_FW_POS_XY_I_DEFAULT
, // FW_POS_XY_I * 100
240 .D
= SETTING_NAV_FW_POS_XY_D_DEFAULT
, // FW_POS_XY_D * 100
243 [PID_POS_HEADING
] = {
244 .P
= SETTING_NAV_FW_POS_HDG_P_DEFAULT
,
245 .I
= SETTING_NAV_FW_POS_HDG_I_DEFAULT
,
246 .D
= SETTING_NAV_FW_POS_HDG_D_DEFAULT
,
252 .dterm_lpf_type
= SETTING_DTERM_LPF_TYPE_DEFAULT
,
253 .dterm_lpf_hz
= SETTING_DTERM_LPF_HZ_DEFAULT
,
254 .yaw_lpf_hz
= SETTING_YAW_LPF_HZ_DEFAULT
,
256 .itermWindupPointPercent
= SETTING_ITERM_WINDUP_DEFAULT
,
258 .axisAccelerationLimitYaw
= SETTING_RATE_ACCEL_LIMIT_YAW_DEFAULT
,
259 .axisAccelerationLimitRollPitch
= SETTING_RATE_ACCEL_LIMIT_ROLL_PITCH_DEFAULT
,
261 .heading_hold_rate_limit
= SETTING_HEADING_HOLD_RATE_LIMIT_DEFAULT
,
263 .max_angle_inclination
[FD_ROLL
] = SETTING_MAX_ANGLE_INCLINATION_RLL_DEFAULT
,
264 .max_angle_inclination
[FD_PITCH
] = SETTING_MAX_ANGLE_INCLINATION_PIT_DEFAULT
,
265 .pidSumLimit
= SETTING_PIDSUM_LIMIT_DEFAULT
,
266 .pidSumLimitYaw
= SETTING_PIDSUM_LIMIT_YAW_DEFAULT
,
268 .fixedWingItermThrowLimit
= SETTING_FW_ITERM_THROW_LIMIT_DEFAULT
,
269 .fixedWingReferenceAirspeed
= SETTING_FW_REFERENCE_AIRSPEED_DEFAULT
,
270 .fixedWingCoordinatedYawGain
= SETTING_FW_TURN_ASSIST_YAW_GAIN_DEFAULT
,
271 .fixedWingCoordinatedPitchGain
= SETTING_FW_TURN_ASSIST_PITCH_GAIN_DEFAULT
,
272 .fixedWingItermLimitOnStickPosition
= SETTING_FW_ITERM_LIMIT_STICK_POSITION_DEFAULT
,
273 .fixedWingYawItermBankFreeze
= SETTING_FW_YAW_ITERM_FREEZE_BANK_ANGLE_DEFAULT
,
275 .navVelXyDTermLpfHz
= SETTING_NAV_MC_VEL_XY_DTERM_LPF_HZ_DEFAULT
,
276 .navVelXyDtermAttenuation
= SETTING_NAV_MC_VEL_XY_DTERM_ATTENUATION_DEFAULT
,
277 .navVelXyDtermAttenuationStart
= SETTING_NAV_MC_VEL_XY_DTERM_ATTENUATION_START_DEFAULT
,
278 .navVelXyDtermAttenuationEnd
= SETTING_NAV_MC_VEL_XY_DTERM_ATTENUATION_END_DEFAULT
,
279 .iterm_relax_cutoff
= SETTING_MC_ITERM_RELAX_CUTOFF_DEFAULT
,
280 .iterm_relax
= SETTING_MC_ITERM_RELAX_DEFAULT
,
283 .dBoostMin
= SETTING_D_BOOST_MIN_DEFAULT
,
284 .dBoostMax
= SETTING_D_BOOST_MAX_DEFAULT
,
285 .dBoostMaxAtAlleceleration
= SETTING_D_BOOST_MAX_AT_ACCELERATION_DEFAULT
,
286 .dBoostGyroDeltaLpfHz
= SETTING_D_BOOST_GYRO_DELTA_LPF_HZ_DEFAULT
,
289 #ifdef USE_ANTIGRAVITY
290 .antigravityGain
= SETTING_ANTIGRAVITY_GAIN_DEFAULT
,
291 .antigravityAccelerator
= SETTING_ANTIGRAVITY_ACCELERATOR_DEFAULT
,
292 .antigravityCutoff
= SETTING_ANTIGRAVITY_CUTOFF_LPF_HZ_DEFAULT
,
295 .pidControllerType
= SETTING_PID_TYPE_DEFAULT
,
296 .navFwPosHdgPidsumLimit
= SETTING_NAV_FW_POS_HDG_PIDSUM_LIMIT_DEFAULT
,
297 .controlDerivativeLpfHz
= SETTING_MC_CD_LPF_HZ_DEFAULT
,
299 .fixedWingLevelTrim
= SETTING_FW_LEVEL_PITCH_TRIM_DEFAULT
,
300 .fixedWingLevelTrimGain
= SETTING_FW_LEVEL_PITCH_GAIN_DEFAULT
,
302 #ifdef USE_SMITH_PREDICTOR
303 .smithPredictorStrength
= SETTING_SMITH_PREDICTOR_STRENGTH_DEFAULT
,
304 .smithPredictorDelay
= SETTING_SMITH_PREDICTOR_DELAY_DEFAULT
,
305 .smithPredictorFilterHz
= SETTING_SMITH_PREDICTOR_LPF_HZ_DEFAULT
,
309 bool pidInitFilters(void)
311 const uint32_t refreshRate
= getLooptime();
313 if (refreshRate
== 0) {
317 for (int axis
= 0; axis
< 3; ++ axis
) {
318 initFilter(pidProfile()->dterm_lpf_type
, &pidState
[axis
].dtermLpfState
, pidProfile()->dterm_lpf_hz
, refreshRate
);
321 for (int i
= 0; i
< XYZ_AXIS_COUNT
; i
++) {
322 pt1FilterInit(&windupLpf
[i
], pidProfile()->iterm_relax_cutoff
, US2S(refreshRate
));
325 #ifdef USE_ANTIGRAVITY
326 pt1FilterInit(&antigravityThrottleLpf
, pidProfile()->antigravityCutoff
, US2S(TASK_PERIOD_HZ(TASK_AUX_RATE_HZ
)));
330 for (int axis
= 0; axis
< XYZ_AXIS_COUNT
; axis
++) {
331 biquadFilterInitLPF(&pidState
[axis
].dBoostGyroLpf
, pidProfile()->dBoostGyroDeltaLpfHz
, getLooptime());
335 if (pidProfile()->controlDerivativeLpfHz
) {
336 for (int axis
= 0; axis
< XYZ_AXIS_COUNT
; axis
++) {
337 pt3FilterInit(&pidState
[axis
].rateTargetFilter
, pt3FilterGain(pidProfile()->controlDerivativeLpfHz
, US2S(refreshRate
)));
341 #ifdef USE_SMITH_PREDICTOR
343 &pidState
[FD_ROLL
].smithPredictor
,
344 pidProfile()->smithPredictorDelay
,
345 pidProfile()->smithPredictorStrength
,
346 pidProfile()->smithPredictorFilterHz
,
350 &pidState
[FD_PITCH
].smithPredictor
,
351 pidProfile()->smithPredictorDelay
,
352 pidProfile()->smithPredictorStrength
,
353 pidProfile()->smithPredictorFilterHz
,
357 &pidState
[FD_YAW
].smithPredictor
,
358 pidProfile()->smithPredictorDelay
,
359 pidProfile()->smithPredictorStrength
,
360 pidProfile()->smithPredictorFilterHz
,
365 pidFiltersConfigured
= true;
370 void pidResetTPAFilter(void)
372 if (usedPidControllerType
== PID_TYPE_PIFF
&& currentControlRateProfile
->throttle
.fixedWingTauMs
> 0) {
373 pt1FilterInitRC(&fixedWingTpaFilter
, MS2S(currentControlRateProfile
->throttle
.fixedWingTauMs
), US2S(TASK_PERIOD_HZ(TASK_AUX_RATE_HZ
)));
374 pt1FilterReset(&fixedWingTpaFilter
, getThrottleIdleValue());
378 void pidResetErrorAccumulators(void)
380 // Reset R/P/Y integrator
381 for (int axis
= 0; axis
< 3; axis
++) {
382 pidState
[axis
].errorGyroIf
= 0.0f
;
383 pidState
[axis
].errorGyroIfLimit
= 0.0f
;
387 void pidReduceErrorAccumulators(int8_t delta
, uint8_t axis
)
389 pidState
[axis
].errorGyroIf
-= delta
;
390 pidState
[axis
].errorGyroIfLimit
-= delta
;
393 float getTotalRateTarget(void)
395 return calc_length_pythagorean_3D(pidState
[FD_ROLL
].rateTarget
, pidState
[FD_PITCH
].rateTarget
, pidState
[FD_YAW
].rateTarget
);
398 float getAxisIterm(uint8_t axis
)
400 return pidState
[axis
].errorGyroIf
;
403 static float pidRcCommandToAngle(int16_t stick
, int16_t maxInclination
)
405 stick
= constrain(stick
, -500, 500);
406 return scaleRangef((float) stick
, -500.0f
, 500.0f
, (float) -maxInclination
, (float) maxInclination
);
409 int16_t pidAngleToRcCommand(float angleDeciDegrees
, int16_t maxInclination
)
411 angleDeciDegrees
= constrainf(angleDeciDegrees
, (float) -maxInclination
, (float) maxInclination
);
412 return scaleRangef((float) angleDeciDegrees
, (float) -maxInclination
, (float) maxInclination
, -500.0f
, 500.0f
);
416 Map stick positions to desired rotatrion rate in given axis.
417 Rotation rate in dps at full stick deflection is defined by axis rate measured in dps/10
418 Rate 20 means 200dps at full stick deflection
420 float pidRateToRcCommand(float rateDPS
, uint8_t rate
)
422 const float maxRateDPS
= rate
* 10.0f
;
423 return scaleRangef(rateDPS
, -maxRateDPS
, maxRateDPS
, -500.0f
, 500.0f
);
426 float pidRcCommandToRate(int16_t stick
, uint8_t rate
)
428 const float maxRateDPS
= rate
* 10.0f
;
429 return scaleRangef((float) stick
, -500.0f
, 500.0f
, -maxRateDPS
, maxRateDPS
);
432 static float calculateFixedWingTPAFactor(uint16_t throttle
)
436 // tpa_rate is amount of curve TPA applied to PIDs
437 // tpa_breakpoint for fixed wing is cruise throttle value (value at which PIDs were tuned)
438 if (currentControlRateProfile
->throttle
.dynPID
!= 0 && currentControlRateProfile
->throttle
.pa_breakpoint
> getThrottleIdleValue() && !FLIGHT_MODE(AUTO_TUNE
) && ARMING_FLAG(ARMED
)) {
439 if (throttle
> getThrottleIdleValue()) {
440 // Calculate TPA according to throttle
441 tpaFactor
= 0.5f
+ ((float)(currentControlRateProfile
->throttle
.pa_breakpoint
- getThrottleIdleValue()) / (throttle
- getThrottleIdleValue()) / 2.0f
);
443 // Limit to [0.5; 2] range
444 tpaFactor
= constrainf(tpaFactor
, 0.5f
, 2.0f
);
450 // Attenuate TPA curve according to configured amount
451 tpaFactor
= 1.0f
+ (tpaFactor
- 1.0f
) * (currentControlRateProfile
->throttle
.dynPID
/ 100.0f
);
460 static float calculateMultirotorTPAFactor(void)
464 // TPA should be updated only when TPA is actually set
465 if (currentControlRateProfile
->throttle
.dynPID
== 0 || rcCommand
[THROTTLE
] < currentControlRateProfile
->throttle
.pa_breakpoint
) {
467 } else if (rcCommand
[THROTTLE
] < motorConfig()->maxthrottle
) {
468 tpaFactor
= (100 - (uint16_t)currentControlRateProfile
->throttle
.dynPID
* (rcCommand
[THROTTLE
] - currentControlRateProfile
->throttle
.pa_breakpoint
) / (float)(motorConfig()->maxthrottle
- currentControlRateProfile
->throttle
.pa_breakpoint
)) / 100.0f
;
470 tpaFactor
= (100 - currentControlRateProfile
->throttle
.dynPID
) / 100.0f
;
476 void schedulePidGainsUpdate(void)
478 pidGainsUpdateRequired
= true;
481 void updatePIDCoefficients(void)
483 STATIC_FASTRAM
uint16_t prevThrottle
= 0;
485 // Check if throttle changed. Different logic for fixed wing vs multirotor
486 if (usedPidControllerType
== PID_TYPE_PIFF
&& (currentControlRateProfile
->throttle
.fixedWingTauMs
> 0)) {
487 uint16_t filteredThrottle
= pt1FilterApply(&fixedWingTpaFilter
, rcCommand
[THROTTLE
]);
488 if (filteredThrottle
!= prevThrottle
) {
489 prevThrottle
= filteredThrottle
;
490 pidGainsUpdateRequired
= true;
494 if (rcCommand
[THROTTLE
] != prevThrottle
) {
495 prevThrottle
= rcCommand
[THROTTLE
];
496 pidGainsUpdateRequired
= true;
500 #ifdef USE_ANTIGRAVITY
501 if (usedPidControllerType
== PID_TYPE_PID
) {
502 antigravityThrottleHpf
= rcCommand
[THROTTLE
] - pt1FilterApply(&antigravityThrottleLpf
, rcCommand
[THROTTLE
]);
503 iTermAntigravityGain
= scaleRangef(fabsf(antigravityThrottleHpf
) * antigravityAccelerator
, 0.0f
, 1000.0f
, 1.0f
, antigravityGain
);
508 * Compute stick position in range of [-1.0f : 1.0f] without deadband and expo
510 for (int axis
= 0; axis
< 3; axis
++) {
511 pidState
[axis
].stickPosition
= constrain(rxGetChannelValue(axis
) - PWM_RANGE_MIDDLE
, -500, 500) / 500.0f
;
514 // If nothing changed - don't waste time recalculating coefficients
515 if (!pidGainsUpdateRequired
) {
519 const float tpaFactor
= usedPidControllerType
== PID_TYPE_PIFF
? calculateFixedWingTPAFactor(prevThrottle
) : calculateMultirotorTPAFactor();
521 // PID coefficients can be update only with THROTTLE and TPA or inflight PID adjustments
522 //TODO: Next step would be to update those only at THROTTLE or inflight adjustments change
523 for (int axis
= 0; axis
< 3; axis
++) {
524 if (usedPidControllerType
== PID_TYPE_PIFF
) {
525 // Airplanes - scale all PIDs according to TPA
526 pidState
[axis
].kP
= pidBank()->pid
[axis
].P
/ FP_PID_RATE_P_MULTIPLIER
* tpaFactor
;
527 pidState
[axis
].kI
= pidBank()->pid
[axis
].I
/ FP_PID_RATE_I_MULTIPLIER
* tpaFactor
;
528 pidState
[axis
].kD
= pidBank()->pid
[axis
].D
/ FP_PID_RATE_D_MULTIPLIER
* tpaFactor
;
529 pidState
[axis
].kFF
= pidBank()->pid
[axis
].FF
/ FP_PID_RATE_FF_MULTIPLIER
* tpaFactor
;
530 pidState
[axis
].kCD
= 0.0f
;
531 pidState
[axis
].kT
= 0.0f
;
534 const float axisTPA
= (axis
== FD_YAW
) ? 1.0f
: tpaFactor
;
535 pidState
[axis
].kP
= pidBank()->pid
[axis
].P
/ FP_PID_RATE_P_MULTIPLIER
* axisTPA
;
536 pidState
[axis
].kI
= pidBank()->pid
[axis
].I
/ FP_PID_RATE_I_MULTIPLIER
;
537 pidState
[axis
].kD
= pidBank()->pid
[axis
].D
/ FP_PID_RATE_D_MULTIPLIER
* axisTPA
;
538 pidState
[axis
].kCD
= (pidBank()->pid
[axis
].FF
/ FP_PID_RATE_D_FF_MULTIPLIER
* axisTPA
) / (getLooptime() * 0.000001f
);
539 pidState
[axis
].kFF
= 0.0f
;
541 // Tracking anti-windup requires P/I/D to be all defined which is only true for MC
542 if ((pidBank()->pid
[axis
].P
!= 0) && (pidBank()->pid
[axis
].I
!= 0) && (usedPidControllerType
== PID_TYPE_PID
)) {
543 pidState
[axis
].kT
= 2.0f
/ ((pidState
[axis
].kP
/ pidState
[axis
].kI
) + (pidState
[axis
].kD
/ pidState
[axis
].kP
));
545 pidState
[axis
].kT
= 0;
550 pidGainsUpdateRequired
= false;
553 static float calcHorizonRateMagnitude(void)
555 // Figure out the raw stick positions
556 const int32_t stickPosAil
= ABS(getRcStickDeflection(FD_ROLL
));
557 const int32_t stickPosEle
= ABS(getRcStickDeflection(FD_PITCH
));
558 const float mostDeflectedStickPos
= constrain(MAX(stickPosAil
, stickPosEle
), 0, 500) / 500.0f
;
559 const float modeTransitionStickPos
= constrain(pidBank()->pid
[PID_LEVEL
].D
, 0, 100) / 100.0f
;
561 float horizonRateMagnitude
;
563 // Calculate transition point according to stick deflection
564 if (mostDeflectedStickPos
<= modeTransitionStickPos
) {
565 horizonRateMagnitude
= mostDeflectedStickPos
/ modeTransitionStickPos
;
568 horizonRateMagnitude
= 1.0f
;
571 return horizonRateMagnitude
;
574 /* ANGLE freefloat deadband (degs).Angle error only starts to increase if atttiude outside deadband. */
575 int16_t angleFreefloatDeadband(int16_t deadband
, flight_dynamics_index_t axis
)
577 int16_t levelDatum
= axis
== FD_PITCH
? attitude
.raw
[axis
] + DEGREES_TO_DECIDEGREES(fixedWingLevelTrim
) : attitude
.raw
[axis
];
578 if (ABS(levelDatum
) > deadband
) {
579 return levelDatum
> 0 ? deadband
- levelDatum
: -(levelDatum
+ deadband
);
585 static float computePidLevelTarget(flight_dynamics_index_t axis
) {
586 // This is ROLL/PITCH, run ANGLE/HORIZON controllers
587 float angleTarget
= pidRcCommandToAngle(rcCommand
[axis
], pidProfile()->max_angle_inclination
[axis
]);
589 // Automatically pitch down if the throttle is manually controlled and reduced bellow cruise throttle
590 if ((axis
== FD_PITCH
) && STATE(AIRPLANE
) && FLIGHT_MODE(ANGLE_MODE
) && !navigationIsControllingThrottle()) {
591 angleTarget
+= scaleRange(MAX(0, currentBatteryProfile
->nav
.fw
.cruise_throttle
- rcCommand
[THROTTLE
]), 0, currentBatteryProfile
->nav
.fw
.cruise_throttle
- PWM_RANGE_MIN
, 0, navConfig()->fw
.minThrottleDownPitchAngle
);
594 //PITCH trim applied by a AutoLevel flight mode and manual pitch trimming
595 if (axis
== FD_PITCH
&& STATE(AIRPLANE
)) {
596 DEBUG_SET(DEBUG_AUTOLEVEL
, 0, angleTarget
* 10);
597 DEBUG_SET(DEBUG_AUTOLEVEL
, 1, fixedWingLevelTrim
* 10);
598 DEBUG_SET(DEBUG_AUTOLEVEL
, 2, getEstimatedActualVelocity(Z
));
601 * fixedWingLevelTrim has opposite sign to rcCommand.
602 * Positive rcCommand means nose should point downwards
603 * Negative rcCommand mean nose should point upwards
604 * This is counter intuitive and a natural way suggests that + should mean UP
605 * This is why fixedWingLevelTrim has opposite sign to rcCommand
606 * Positive fixedWingLevelTrim means nose should point upwards
607 * Negative fixedWingLevelTrim means nose should point downwards
609 angleTarget
-= DEGREES_TO_DECIDEGREES(fixedWingLevelTrim
);
610 DEBUG_SET(DEBUG_AUTOLEVEL
, 3, angleTarget
* 10);
616 static void pidLevel(const float angleTarget
, pidState_t
*pidState
, flight_dynamics_index_t axis
, float horizonRateMagnitude
, float dT
)
618 float angleErrorDeg
= DECIDEGREES_TO_DEGREES(angleTarget
- attitude
.raw
[axis
]);
620 // Soaring mode deadband inactive if pitch/roll stick not centered to allow RC stick adjustment
621 if (FLIGHT_MODE(SOARING_MODE
) && axis
== FD_PITCH
&& calculateRollPitchCenterStatus() == CENTERED
) {
622 angleErrorDeg
= DECIDEGREES_TO_DEGREES((float)angleFreefloatDeadband(DEGREES_TO_DECIDEGREES(navConfig()->fw
.soaring_pitch_deadband
), FD_PITCH
));
623 if (!angleErrorDeg
) {
624 pidState
->errorGyroIf
= 0.0f
;
625 pidState
->errorGyroIfLimit
= 0.0f
;
629 float angleRateTarget
= constrainf(angleErrorDeg
* (pidBank()->pid
[PID_LEVEL
].P
* FP_PID_LEVEL_P_MULTIPLIER
), -currentControlRateProfile
->stabilized
.rates
[axis
] * 10.0f
, currentControlRateProfile
->stabilized
.rates
[axis
] * 10.0f
);
631 // Apply simple LPF to angleRateTarget to make response less jerky
632 // Ideas behind this:
633 // 1) Attitude is updated at gyro rate, rateTarget for ANGLE mode is calculated from attitude
634 // 2) If this rateTarget is passed directly into gyro-base PID controller this effectively doubles the rateError.
635 // D-term that is calculated from error tend to amplify this even more. Moreover, this tend to respond to every
636 // slightest change in attitude making self-leveling jittery
637 // 3) Lowering LEVEL P can make the effects of (2) less visible, but this also slows down self-leveling.
638 // 4) Human pilot response to attitude change in RATE mode is fairly slow and smooth, human pilot doesn't
639 // compensate for each slightest change
640 // 5) (2) and (4) lead to a simple idea of adding a low-pass filter on rateTarget for ANGLE mode damping
641 // response to rapid attitude changes and smoothing out self-leveling reaction
642 if (pidBank()->pid
[PID_LEVEL
].I
) {
643 // I8[PIDLEVEL] is filter cutoff frequency (Hz). Practical values of filtering frequency is 5-10 Hz
644 angleRateTarget
= pt1FilterApply4(&pidState
->angleFilterState
, angleRateTarget
, pidBank()->pid
[PID_LEVEL
].I
, dT
);
647 // P[LEVEL] defines self-leveling strength (both for ANGLE and HORIZON modes)
648 if (FLIGHT_MODE(HORIZON_MODE
)) {
649 pidState
->rateTarget
= (1.0f
- horizonRateMagnitude
) * angleRateTarget
+ horizonRateMagnitude
* pidState
->rateTarget
;
651 pidState
->rateTarget
= angleRateTarget
;
655 /* Apply angular acceleration limit to rate target to limit extreme stick inputs to respect physical capabilities of the machine */
656 static void pidApplySetpointRateLimiting(pidState_t
*pidState
, flight_dynamics_index_t axis
, float dT
)
658 const uint32_t axisAccelLimit
= (axis
== FD_YAW
) ? pidProfile()->axisAccelerationLimitYaw
: pidProfile()->axisAccelerationLimitRollPitch
;
660 if (axisAccelLimit
> AXIS_ACCEL_MIN_LIMIT
) {
661 pidState
->rateTarget
= rateLimitFilterApply4(&pidState
->axisAccelFilter
, pidState
->rateTarget
, (float)axisAccelLimit
, dT
);
665 bool isFixedWingItermLimitActive(float stickPosition
)
668 * Iterm anti windup whould be active only when pilot controls the rotation
669 * velocity directly, not when ANGLE or HORIZON are used
671 if (levelingEnabled
) {
675 return fabsf(stickPosition
) > pidProfile()->fixedWingItermLimitOnStickPosition
;
678 static float pTermProcess(pidState_t
*pidState
, float rateError
, float dT
) {
679 float newPTerm
= rateError
* pidState
->kP
;
681 return pidState
->ptermFilterApplyFn(&pidState
->ptermLpfState
, newPTerm
, yawLpfHz
, dT
);
685 static float FAST_CODE
applyDBoost(pidState_t
*pidState
, float currentRateTarget
, float dT
, float dT_inv
) {
689 const float dBoostGyroDelta
= (pidState
->gyroRate
- pidState
->previousRateGyro
) * dT_inv
;
690 const float dBoostGyroAcceleration
= fabsf(biquadFilterApply(&pidState
->dBoostGyroLpf
, dBoostGyroDelta
));
691 const float dBoostRateAcceleration
= fabsf((currentRateTarget
- pidState
->previousRateTarget
) * dT_inv
);
693 if (dBoostGyroAcceleration
>= dBoostRateAcceleration
) {
694 //Gyro is accelerating faster than setpoint, we want to smooth out
695 dBoost
= scaleRangef(dBoostGyroAcceleration
, 0.0f
, dBoostMaxAtAlleceleration
, 1.0f
, dBoostMax
);
697 //Setpoint is accelerating, we want to boost response
698 dBoost
= scaleRangef(dBoostRateAcceleration
, 0.0f
, pidState
->dBoostTargetAcceleration
, 1.0f
, dBoostMin
);
701 dBoost
= pt1FilterApply4(&pidState
->dBoostLpf
, dBoost
, D_BOOST_LPF_HZ
, dT
);
702 dBoost
= constrainf(dBoost
, dBoostMin
, dBoostMax
);
707 static float applyDBoost(pidState_t
*pidState
, float dT
) {
714 static float dTermProcess(pidState_t
*pidState
, float currentRateTarget
, float dT
, float dT_inv
) {
715 // Calculate new D-term
717 if (pidState
->kD
== 0) {
718 // optimisation for when D is zero, often used by YAW axis
721 float delta
= pidState
->previousRateGyro
- pidState
->gyroRate
;
723 delta
= dTermLpfFilterApplyFn((filter_t
*) &pidState
->dtermLpfState
, delta
);
725 // Calculate derivative
726 newDTerm
= delta
* (pidState
->kD
* dT_inv
) * applyDBoost(pidState
, currentRateTarget
, dT
, dT_inv
);
731 static void applyItermLimiting(pidState_t
*pidState
) {
732 if (pidState
->itermLimitActive
) {
733 pidState
->errorGyroIf
= constrainf(pidState
->errorGyroIf
, -pidState
->errorGyroIfLimit
, pidState
->errorGyroIfLimit
);
736 pidState
->errorGyroIfLimit
= fabsf(pidState
->errorGyroIf
);
740 static void nullRateController(pidState_t
*pidState
, flight_dynamics_index_t axis
, float dT
, float dT_inv
) {
747 static void NOINLINE
pidApplyFixedWingRateController(pidState_t
*pidState
, flight_dynamics_index_t axis
, float dT
, float dT_inv
)
749 const float rateTarget
= getFlightAxisRateOverride(axis
, pidState
->rateTarget
);
751 const float rateError
= rateTarget
- pidState
->gyroRate
;
752 const float newPTerm
= pTermProcess(pidState
, rateError
, dT
);
753 const float newDTerm
= dTermProcess(pidState
, rateTarget
, dT
, dT_inv
);
754 const float newFFTerm
= rateTarget
* pidState
->kFF
;
757 * Integral should be updated only if axis Iterm is not frozen
759 if (!pidState
->itermFreezeActive
) {
760 pidState
->errorGyroIf
+= rateError
* pidState
->kI
* dT
;
763 applyItermLimiting(pidState
);
765 if (pidProfile()->fixedWingItermThrowLimit
!= 0) {
766 pidState
->errorGyroIf
= constrainf(pidState
->errorGyroIf
, -pidProfile()->fixedWingItermThrowLimit
, pidProfile()->fixedWingItermThrowLimit
);
769 axisPID
[axis
] = constrainf(newPTerm
+ newFFTerm
+ pidState
->errorGyroIf
+ newDTerm
, -pidState
->pidSumLimit
, +pidState
->pidSumLimit
);
771 if (FLIGHT_MODE(SOARING_MODE
) && axis
== FD_PITCH
&& calculateRollPitchCenterStatus() == CENTERED
) {
772 if (!angleFreefloatDeadband(DEGREES_TO_DECIDEGREES(navConfig()->fw
.soaring_pitch_deadband
), FD_PITCH
)) {
773 axisPID
[FD_PITCH
] = 0; // center pitch servo if pitch attitude within soaring mode deadband
777 #ifdef USE_AUTOTUNE_FIXED_WING
778 if (FLIGHT_MODE(AUTO_TUNE
) && !FLIGHT_MODE(MANUAL_MODE
)) {
779 autotuneFixedWingUpdate(axis
, rateTarget
, pidState
->gyroRate
, constrainf(newPTerm
+ newFFTerm
, -pidState
->pidSumLimit
, +pidState
->pidSumLimit
));
784 axisPID_P
[axis
] = newPTerm
;
785 axisPID_I
[axis
] = pidState
->errorGyroIf
;
786 axisPID_D
[axis
] = newDTerm
;
787 axisPID_F
[axis
] = newFFTerm
;
788 axisPID_Setpoint
[axis
] = rateTarget
;
791 pidState
->previousRateGyro
= pidState
->gyroRate
;
795 static float FAST_CODE
applyItermRelax(const int axis
, float currentPidSetpoint
, float itermErrorRate
)
798 if (axis
< FD_YAW
|| itermRelax
== ITERM_RELAX_RPY
) {
800 const float setpointLpf
= pt1FilterApply(&windupLpf
[axis
], currentPidSetpoint
);
801 const float setpointHpf
= fabsf(currentPidSetpoint
- setpointLpf
);
803 const float itermRelaxFactor
= MAX(0, 1 - setpointHpf
/ MC_ITERM_RELAX_SETPOINT_THRESHOLD
);
804 return itermErrorRate
* itermRelaxFactor
;
808 return itermErrorRate
;
811 static void FAST_CODE NOINLINE
pidApplyMulticopterRateController(pidState_t
*pidState
, flight_dynamics_index_t axis
, float dT
, float dT_inv
)
814 const float rateTarget
= getFlightAxisRateOverride(axis
, pidState
->rateTarget
);
816 const float rateError
= rateTarget
- pidState
->gyroRate
;
817 const float newPTerm
= pTermProcess(pidState
, rateError
, dT
);
818 const float newDTerm
= dTermProcess(pidState
, rateTarget
, dT
, dT_inv
);
820 const float rateTargetDelta
= rateTarget
- pidState
->previousRateTarget
;
821 const float rateTargetDeltaFiltered
= pt3FilterApply(&pidState
->rateTargetFilter
, rateTargetDelta
);
824 * Compute Control Derivative
826 const float newCDTerm
= rateTargetDeltaFiltered
* pidState
->kCD
;
828 // TODO: Get feedback from mixer on available correction range for each axis
829 const float newOutput
= newPTerm
+ newDTerm
+ pidState
->errorGyroIf
+ newCDTerm
;
830 const float newOutputLimited
= constrainf(newOutput
, -pidState
->pidSumLimit
, +pidState
->pidSumLimit
);
832 float itermErrorRate
= applyItermRelax(axis
, rateTarget
, rateError
);
834 #ifdef USE_ANTIGRAVITY
835 itermErrorRate
*= iTermAntigravityGain
;
838 pidState
->errorGyroIf
+= (itermErrorRate
* pidState
->kI
* antiWindupScaler
* dT
)
839 + ((newOutputLimited
- newOutput
) * pidState
->kT
* antiWindupScaler
* dT
);
841 // Don't grow I-term if motors are at their limit
842 applyItermLimiting(pidState
);
844 axisPID
[axis
] = newOutputLimited
;
847 axisPID_P
[axis
] = newPTerm
;
848 axisPID_I
[axis
] = pidState
->errorGyroIf
;
849 axisPID_D
[axis
] = newDTerm
;
850 axisPID_F
[axis
] = newCDTerm
;
851 axisPID_Setpoint
[axis
] = rateTarget
;
854 pidState
->previousRateTarget
= rateTarget
;
855 pidState
->previousRateGyro
= pidState
->gyroRate
;
858 void updateHeadingHoldTarget(int16_t heading
)
860 headingHoldTarget
= heading
;
863 void resetHeadingHoldTarget(int16_t heading
)
865 updateHeadingHoldTarget(heading
);
866 pt1FilterReset(&headingHoldRateFilter
, 0.0f
);
869 int16_t getHeadingHoldTarget(void) {
870 return headingHoldTarget
;
873 static uint8_t getHeadingHoldState(void)
875 // Don't apply heading hold if overall tilt is greater than maximum angle inclination
876 if (calculateCosTiltAngle() < headingHoldCosZLimit
) {
877 return HEADING_HOLD_DISABLED
;
880 int navHeadingState
= navigationGetHeadingControlState();
881 // NAV will prevent MAG_MODE from activating, but require heading control
882 if (navHeadingState
!= NAV_HEADING_CONTROL_NONE
) {
883 // Apply maghold only if heading control is in auto mode
884 if (navHeadingState
== NAV_HEADING_CONTROL_AUTO
) {
885 return HEADING_HOLD_ENABLED
;
888 else if (ABS(rcCommand
[YAW
]) == 0 && FLIGHT_MODE(HEADING_MODE
)) {
889 return HEADING_HOLD_ENABLED
;
892 return HEADING_HOLD_UPDATE_HEADING
;
896 * HEADING_HOLD P Controller returns desired rotation rate in dps to be fed to Rate controller
898 float pidHeadingHold(float dT
)
900 float headingHoldRate
;
902 /* Convert absolute error into relative to current heading */
903 int16_t error
= DECIDEGREES_TO_DEGREES(attitude
.values
.yaw
) - headingHoldTarget
;
905 /* Convert absolute error into relative to current heading */
908 } else if (error
< -180) {
913 New MAG_HOLD controller work slightly different that previous one.
914 Old one mapped error to rotation speed in following way:
915 - on rate 0 it gave about 0.5dps for each degree of error
916 - error 0 = rotation speed of 0dps
917 - error 180 = rotation speed of 96 degrees per second
919 - that gives about 2 seconds to correct any error, no matter how big. Of course, usually more because of inertia.
920 That was making him quite "soft" for small changes and rapid for big ones that started to appear
921 when INAV introduced real RTH and WAYPOINT that might require rapid heading changes.
923 New approach uses modified principle:
924 - manual yaw rate is not used. MAG_HOLD is decoupled from manual input settings
925 - instead, mag_hold_rate_limit is used. It defines max rotation speed in dps that MAG_HOLD controller can require from RateController
926 - computed rotation speed is capped at -mag_hold_rate_limit and mag_hold_rate_limit
927 - Default mag_hold_rate_limit = 40dps and default MAG_HOLD P-gain is 40
928 - With those values, maximum rotation speed will be required from Rate Controller when error is greater that 30 degrees
929 - For smaller error, required rate will be proportional.
930 - It uses LPF filter set at 2Hz to additionally smoothen out any rapid changes
931 - That makes correction of smaller errors stronger, and those of big errors softer
933 This make looks as very slow rotation rate, but please remember this is automatic mode.
934 Manual override with YAW input when MAG_HOLD is enabled will still use "manual" rates, not MAG_HOLD rates.
935 Highest possible correction is 180 degrees and it will take more less 4.5 seconds. It is even more than sufficient
936 to run RTH or WAYPOINT missions. My favourite rate range here is 20dps - 30dps that gives nice and smooth turns.
938 Correction for small errors is much faster now. For example, old contrioller for 2deg errors required 1dps (correction in 2 seconds).
939 New controller for 2deg error requires 2,6dps. 4dps for 3deg and so on up until mag_hold_rate_limit is reached.
942 headingHoldRate
= error
* pidBank()->pid
[PID_HEADING
].P
/ 30.0f
;
943 headingHoldRate
= constrainf(headingHoldRate
, -pidProfile()->heading_hold_rate_limit
, pidProfile()->heading_hold_rate_limit
);
944 headingHoldRate
= pt1FilterApply4(&headingHoldRateFilter
, headingHoldRate
, HEADING_HOLD_ERROR_LPF_FREQ
, dT
);
946 return headingHoldRate
;
950 * TURN ASSISTANT mode is an assisted mode to do a Yaw rotation on a ground plane, allowing one-stick turn in RATE more
951 * and keeping ROLL and PITCH attitude though the turn.
953 static void NOINLINE
pidTurnAssistant(pidState_t
*pidState
, float bankAngleTarget
, float pitchAngleTarget
)
955 fpVector3_t targetRates
;
956 targetRates
.x
= 0.0f
;
957 targetRates
.y
= 0.0f
;
959 if (STATE(AIRPLANE
)) {
960 if (calculateCosTiltAngle() >= 0.173648f
) {
961 // Ideal banked turn follow the equations:
962 // forward_vel^2 / radius = Gravity * tan(roll_angle)
963 // yaw_rate = forward_vel / radius
964 // If we solve for roll angle we get:
965 // tan(roll_angle) = forward_vel * yaw_rate / Gravity
966 // If we solve for yaw rate we get:
967 // yaw_rate = tan(roll_angle) * Gravity / forward_vel
969 #if defined(USE_PITOT)
970 float airspeedForCoordinatedTurn
= sensors(SENSOR_PITOT
) && pitotIsHealthy()? getAirspeedEstimate() : pidProfile()->fixedWingReferenceAirspeed
;
972 float airspeedForCoordinatedTurn
= pidProfile()->fixedWingReferenceAirspeed
;
975 // Constrain to somewhat sane limits - 10km/h - 216km/h
976 airspeedForCoordinatedTurn
= constrainf(airspeedForCoordinatedTurn
, 300.0f
, 6000.0f
);
978 // Calculate rate of turn in Earth frame according to FAA's Pilot's Handbook of Aeronautical Knowledge
979 bankAngleTarget
= constrainf(bankAngleTarget
, -DEGREES_TO_RADIANS(60), DEGREES_TO_RADIANS(60));
980 float turnRatePitchAdjustmentFactor
= cos_approx(fabsf(pitchAngleTarget
));
981 float coordinatedTurnRateEarthFrame
= GRAVITY_CMSS
* tan_approx(-bankAngleTarget
) / airspeedForCoordinatedTurn
* turnRatePitchAdjustmentFactor
;
983 targetRates
.z
= RADIANS_TO_DEGREES(coordinatedTurnRateEarthFrame
);
986 // Don't allow coordinated turn calculation if airplane is in hard bank or steep climb/dive
991 targetRates
.z
= pidState
[YAW
].rateTarget
;
994 // Transform calculated rate offsets into body frame and apply
995 imuTransformVectorEarthToBody(&targetRates
);
997 // Add in roll and pitch
998 pidState
[ROLL
].rateTarget
= constrainf(pidState
[ROLL
].rateTarget
+ targetRates
.x
, -currentControlRateProfile
->stabilized
.rates
[ROLL
] * 10.0f
, currentControlRateProfile
->stabilized
.rates
[ROLL
] * 10.0f
);
999 pidState
[PITCH
].rateTarget
= constrainf(pidState
[PITCH
].rateTarget
+ targetRates
.y
* pidProfile()->fixedWingCoordinatedPitchGain
, -currentControlRateProfile
->stabilized
.rates
[PITCH
] * 10.0f
, currentControlRateProfile
->stabilized
.rates
[PITCH
] * 10.0f
);
1001 // Replace YAW on quads - add it in on airplanes
1002 if (STATE(AIRPLANE
)) {
1003 pidState
[YAW
].rateTarget
= constrainf(pidState
[YAW
].rateTarget
+ targetRates
.z
* pidProfile()->fixedWingCoordinatedYawGain
, -currentControlRateProfile
->stabilized
.rates
[YAW
] * 10.0f
, currentControlRateProfile
->stabilized
.rates
[YAW
] * 10.0f
);
1006 pidState
[YAW
].rateTarget
= constrainf(targetRates
.z
, -currentControlRateProfile
->stabilized
.rates
[YAW
] * 10.0f
, currentControlRateProfile
->stabilized
.rates
[YAW
] * 10.0f
);
1010 static void pidApplyFpvCameraAngleMix(pidState_t
*pidState
, uint8_t fpvCameraAngle
)
1012 static uint8_t lastFpvCamAngleDegrees
= 0;
1013 static float cosCameraAngle
= 1.0f
;
1014 static float sinCameraAngle
= 0.0f
;
1016 if (lastFpvCamAngleDegrees
!= fpvCameraAngle
) {
1017 lastFpvCamAngleDegrees
= fpvCameraAngle
;
1018 cosCameraAngle
= cos_approx(DEGREES_TO_RADIANS(fpvCameraAngle
));
1019 sinCameraAngle
= sin_approx(DEGREES_TO_RADIANS(fpvCameraAngle
));
1022 // Rotate roll/yaw command from camera-frame coordinate system to body-frame coordinate system
1023 const float rollRate
= pidState
[ROLL
].rateTarget
;
1024 const float yawRate
= pidState
[YAW
].rateTarget
;
1025 pidState
[ROLL
].rateTarget
= constrainf(rollRate
* cosCameraAngle
- yawRate
* sinCameraAngle
, -GYRO_SATURATION_LIMIT
, GYRO_SATURATION_LIMIT
);
1026 pidState
[YAW
].rateTarget
= constrainf(yawRate
* cosCameraAngle
+ rollRate
* sinCameraAngle
, -GYRO_SATURATION_LIMIT
, GYRO_SATURATION_LIMIT
);
1029 void checkItermLimitingActive(pidState_t
*pidState
)
1031 bool shouldActivate
;
1032 if (usedPidControllerType
== PID_TYPE_PIFF
) {
1033 shouldActivate
= isFixedWingItermLimitActive(pidState
->stickPosition
);
1036 shouldActivate
= mixerIsOutputSaturated();
1039 pidState
->itermLimitActive
= STATE(ANTI_WINDUP
) || shouldActivate
;
1042 void checkItermFreezingActive(pidState_t
*pidState
, flight_dynamics_index_t axis
)
1044 if (usedPidControllerType
== PID_TYPE_PIFF
&& pidProfile()->fixedWingYawItermBankFreeze
!= 0 && axis
== FD_YAW
) {
1045 // Do not allow yaw I-term to grow when bank angle is too large
1046 float bankAngle
= DECIDEGREES_TO_DEGREES(attitude
.values
.roll
);
1047 if (fabsf(bankAngle
) > pidProfile()->fixedWingYawItermBankFreeze
&& !(FLIGHT_MODE(AUTO_TUNE
) || FLIGHT_MODE(TURN_ASSISTANT
) || navigationRequiresTurnAssistance())){
1048 pidState
->itermFreezeActive
= true;
1051 pidState
->itermFreezeActive
= false;
1055 pidState
->itermFreezeActive
= false;
1060 void FAST_CODE
pidController(float dT
)
1063 const float dT_inv
= 1.0f
/ dT
;
1065 if (!pidFiltersConfigured
) {
1069 bool canUseFpvCameraMix
= STATE(MULTIROTOR
);
1070 uint8_t headingHoldState
= getHeadingHoldState();
1072 // In case Yaw override is active, we engage the Heading Hold state
1073 if (isFlightAxisAngleOverrideActive(FD_YAW
)) {
1074 headingHoldState
= HEADING_HOLD_ENABLED
;
1075 headingHoldTarget
= getFlightAxisAngleOverride(FD_YAW
, 0);
1078 if (headingHoldState
== HEADING_HOLD_UPDATE_HEADING
) {
1079 updateHeadingHoldTarget(DECIDEGREES_TO_DEGREES(attitude
.values
.yaw
));
1082 for (int axis
= 0; axis
< 3; axis
++) {
1083 // Step 1: Calculate gyro rates
1084 pidState
[axis
].gyroRate
= gyro
.gyroADCf
[axis
];
1086 // Step 2: Read target
1089 if (axis
== FD_YAW
&& headingHoldState
== HEADING_HOLD_ENABLED
) {
1090 rateTarget
= pidHeadingHold(dT
);
1092 #ifdef USE_PROGRAMMING_FRAMEWORK
1093 rateTarget
= pidRcCommandToRate(getRcCommandOverride(rcCommand
, axis
), currentControlRateProfile
->stabilized
.rates
[axis
]);
1095 rateTarget
= pidRcCommandToRate(rcCommand
[axis
], currentControlRateProfile
->stabilized
.rates
[axis
]);
1099 // Limit desired rate to something gyro can measure reliably
1100 pidState
[axis
].rateTarget
= constrainf(rateTarget
, -GYRO_SATURATION_LIMIT
, +GYRO_SATURATION_LIMIT
);
1102 #ifdef USE_GYRO_KALMAN
1103 gyroKalmanUpdateSetpoint(axis
, pidState
[axis
].rateTarget
);
1106 #ifdef USE_SMITH_PREDICTOR
1107 pidState
[axis
].gyroRate
= applySmithPredictor(axis
, &pidState
[axis
].smithPredictor
, pidState
[axis
].gyroRate
);
1111 // Step 3: Run control for ANGLE_MODE, HORIZON_MODE, and HEADING_LOCK
1112 const float horizonRateMagnitude
= calcHorizonRateMagnitude();
1113 levelingEnabled
= false;
1114 for (uint8_t axis
= FD_ROLL
; axis
<= FD_PITCH
; axis
++) {
1115 if (FLIGHT_MODE(ANGLE_MODE
) || FLIGHT_MODE(HORIZON_MODE
) || isFlightAxisAngleOverrideActive(axis
)) {
1116 //If axis angle override, get the correct angle from Logic Conditions
1117 float angleTarget
= getFlightAxisAngleOverride(axis
, computePidLevelTarget(axis
));
1119 //Apply the Level PID controller
1120 pidLevel(angleTarget
, &pidState
[axis
], axis
, horizonRateMagnitude
, dT
);
1121 canUseFpvCameraMix
= false; // FPVANGLEMIX is incompatible with ANGLE/HORIZON
1122 levelingEnabled
= true;
1126 if ((FLIGHT_MODE(TURN_ASSISTANT
) || navigationRequiresTurnAssistance()) && (FLIGHT_MODE(ANGLE_MODE
) || FLIGHT_MODE(HORIZON_MODE
))) {
1127 float bankAngleTarget
= DECIDEGREES_TO_RADIANS(pidRcCommandToAngle(rcCommand
[FD_ROLL
], pidProfile()->max_angle_inclination
[FD_ROLL
]));
1128 float pitchAngleTarget
= DECIDEGREES_TO_RADIANS(pidRcCommandToAngle(rcCommand
[FD_PITCH
], pidProfile()->max_angle_inclination
[FD_PITCH
]));
1129 pidTurnAssistant(pidState
, bankAngleTarget
, pitchAngleTarget
);
1130 canUseFpvCameraMix
= false; // FPVANGLEMIX is incompatible with TURN_ASSISTANT
1133 if (canUseFpvCameraMix
&& IS_RC_MODE_ACTIVE(BOXFPVANGLEMIX
) && currentControlRateProfile
->misc
.fpvCamAngleDegrees
&& STATE(MULTIROTOR
)) {
1134 pidApplyFpvCameraAngleMix(pidState
, currentControlRateProfile
->misc
.fpvCamAngleDegrees
);
1137 // Prevent strong Iterm accumulation during stick inputs
1138 antiWindupScaler
= constrainf((1.0f
- getMotorMixRange()) * motorItermWindupPoint
, 0.0f
, 1.0f
);
1140 for (int axis
= 0; axis
< 3; axis
++) {
1141 // Apply setpoint rate of change limits
1142 pidApplySetpointRateLimiting(&pidState
[axis
], axis
, dT
);
1144 // Step 4: Run gyro-driven control
1145 checkItermLimitingActive(&pidState
[axis
]);
1146 checkItermFreezingActive(&pidState
[axis
], axis
);
1148 pidControllerApplyFn(&pidState
[axis
], axis
, dT
, dT_inv
);
1152 pidType_e
pidIndexGetType(pidIndex_e pidIndex
)
1154 if (pidIndex
== PID_ROLL
|| pidIndex
== PID_PITCH
|| pidIndex
== PID_YAW
) {
1155 return usedPidControllerType
;
1157 if (STATE(AIRPLANE
) || STATE(ROVER
) || STATE(BOAT
)) {
1158 if (pidIndex
== PID_VEL_XY
|| pidIndex
== PID_VEL_Z
) {
1159 return PID_TYPE_NONE
;
1163 if (pidIndex
== PID_SURFACE
) {
1164 return PID_TYPE_NONE
;
1166 return PID_TYPE_PID
;
1171 // Calculate max overall tilt (max pitch + max roll combined) as a limit to heading hold
1172 headingHoldCosZLimit
= cos_approx(DECIDEGREES_TO_RADIANS(pidProfile()->max_angle_inclination
[FD_ROLL
])) *
1173 cos_approx(DECIDEGREES_TO_RADIANS(pidProfile()->max_angle_inclination
[FD_PITCH
]));
1175 pidGainsUpdateRequired
= false;
1177 itermRelax
= pidProfile()->iterm_relax
;
1179 yawLpfHz
= pidProfile()->yaw_lpf_hz
;
1180 motorItermWindupPoint
= 1.0f
/ (1.0f
- (pidProfile()->itermWindupPointPercent
/ 100.0f
));
1183 dBoostMin
= pidProfile()->dBoostMin
;
1184 dBoostMax
= pidProfile()->dBoostMax
;
1185 dBoostMaxAtAlleceleration
= pidProfile()->dBoostMaxAtAlleceleration
;
1188 #ifdef USE_ANTIGRAVITY
1189 antigravityGain
= pidProfile()->antigravityGain
;
1190 antigravityAccelerator
= pidProfile()->antigravityAccelerator
;
1193 for (uint8_t axis
= FD_ROLL
; axis
<= FD_YAW
; axis
++) {
1196 // Rate * 10 * 10. First 10 is to convert stick to DPS. Second 10 is to convert target to acceleration.
1197 // We assume, max acceleration is when pilot deflects the stick fully in 100ms
1198 pidState
[axis
].dBoostTargetAcceleration
= currentControlRateProfile
->stabilized
.rates
[axis
] * 10 * 10;
1201 pidState
[axis
].axis
= axis
;
1202 if (axis
== FD_YAW
) {
1203 pidState
[axis
].pidSumLimit
= pidProfile()->pidSumLimitYaw
;
1205 pidState
[axis
].ptermFilterApplyFn
= (filterApply4FnPtr
) pt1FilterApply4
;
1207 pidState
[axis
].ptermFilterApplyFn
= (filterApply4FnPtr
) nullFilterApply4
;
1210 pidState
[axis
].pidSumLimit
= pidProfile()->pidSumLimit
;
1211 pidState
[axis
].ptermFilterApplyFn
= (filterApply4FnPtr
) nullFilterApply4
;
1215 if (pidProfile()->pidControllerType
== PID_TYPE_AUTO
) {
1217 currentMixerConfig
.platformType
== PLATFORM_AIRPLANE
||
1218 currentMixerConfig
.platformType
== PLATFORM_BOAT
||
1219 currentMixerConfig
.platformType
== PLATFORM_ROVER
1221 usedPidControllerType
= PID_TYPE_PIFF
;
1223 usedPidControllerType
= PID_TYPE_PID
;
1226 usedPidControllerType
= pidProfile()->pidControllerType
;
1229 assignFilterApplyFn(pidProfile()->dterm_lpf_type
, pidProfile()->dterm_lpf_hz
, &dTermLpfFilterApplyFn
);
1231 if (usedPidControllerType
== PID_TYPE_PIFF
) {
1232 pidControllerApplyFn
= pidApplyFixedWingRateController
;
1233 } else if (usedPidControllerType
== PID_TYPE_PID
) {
1234 pidControllerApplyFn
= pidApplyMulticopterRateController
;
1236 pidControllerApplyFn
= nullRateController
;
1239 pidResetTPAFilter();
1241 fixedWingLevelTrim
= pidProfile()->fixedWingLevelTrim
;
1244 &fixedWingLevelTrimController
,
1246 (float)pidProfile()->fixedWingLevelTrimGain
/ 50.0f
,
1255 const pidBank_t
* pidBank(void) {
1256 return usedPidControllerType
== PID_TYPE_PIFF
? &pidProfile()->bank_fw
: &pidProfile()->bank_mc
;
1259 pidBank_t
* pidBankMutable(void) {
1260 return usedPidControllerType
== PID_TYPE_PIFF
? &pidProfileMutable()->bank_fw
: &pidProfileMutable()->bank_mc
;
1263 bool isFixedWingLevelTrimActive(void)
1265 return IS_RC_MODE_ACTIVE(BOXAUTOLEVEL
) && !areSticksDeflected() &&
1266 (FLIGHT_MODE(ANGLE_MODE
) || FLIGHT_MODE(HORIZON_MODE
)) && !FLIGHT_MODE(SOARING_MODE
) &&
1267 !navigationIsControllingAltitude();
1270 void updateFixedWingLevelTrim(timeUs_t currentTimeUs
)
1272 if (!STATE(AIRPLANE
)) {
1276 static bool previousArmingState
= false;
1278 if (ARMING_FLAG(ARMED
)) {
1279 if (!previousArmingState
) { // On every ARM reset the controller
1280 navPidReset(&fixedWingLevelTrimController
);
1282 } else if (previousArmingState
) { // On disarm update the default value
1283 pidProfileMutable()->fixedWingLevelTrim
= constrainf(fixedWingLevelTrim
, -FIXED_WING_LEVEL_TRIM_MAX_ANGLE
, FIXED_WING_LEVEL_TRIM_MAX_ANGLE
);
1285 previousArmingState
= ARMING_FLAG(ARMED
);
1287 // return if not active or disarmed
1288 if (!IS_RC_MODE_ACTIVE(BOXAUTOLEVEL
) || !ARMING_FLAG(ARMED
)) {
1292 static timeUs_t previousUpdateTimeUs
;
1293 const float dT
= US2S(currentTimeUs
- previousUpdateTimeUs
);
1294 previousUpdateTimeUs
= currentTimeUs
;
1297 * Prepare flags for the PID controller
1299 pidControllerFlags_e flags
= PID_LIMIT_INTEGRATOR
;
1301 // Iterm should freeze when conditions for setting level trim aren't met
1302 if (!isFixedWingLevelTrimActive()) {
1303 flags
|= PID_FREEZE_INTEGRATOR
;
1306 const float output
= navPidApply3(
1307 &fixedWingLevelTrimController
,
1308 0, //Setpoint is always 0 as we try to keep level flight
1309 getEstimatedActualVelocity(Z
),
1311 -FIXED_WING_LEVEL_TRIM_CONTROLLER_LIMIT
,
1312 FIXED_WING_LEVEL_TRIM_CONTROLLER_LIMIT
,
1318 DEBUG_SET(DEBUG_AUTOLEVEL
, 4, output
);
1319 fixedWingLevelTrim
= pidProfile()->fixedWingLevelTrim
+ (output
* FIXED_WING_LEVEL_TRIM_MULTIPLIER
);
1322 float getFixedWingLevelTrim(void)
1324 return STATE(AIRPLANE
) ? fixedWingLevelTrim
: 0;