2 * This file is part of Cleanflight and Betaflight.
4 * Cleanflight and Betaflight are free software. You can redistribute
5 * this software and/or modify this software under the terms of the
6 * GNU General Public License as published by the Free Software
7 * Foundation, either version 3 of the License, or (at your option)
10 * Cleanflight and Betaflight are distributed in the hope that they
11 * will be useful, but WITHOUT ANY WARRANTY; without even the implied
12 * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
13 * See the GNU General Public License for more details.
15 * You should have received a copy of the GNU General Public License
16 * along with this software.
18 * If not, see <http://www.gnu.org/licenses/>.
28 #include "build/build_config.h"
29 #include "build/debug.h"
31 #include "common/axis.h"
32 #include "common/filter.h"
34 #include "config/config_reset.h"
35 #include "config/simplified_tuning.h"
37 #include "drivers/pwm_output.h"
38 #include "drivers/sound_beeper.h"
39 #include "drivers/time.h"
41 #include "fc/controlrate_profile.h"
44 #include "fc/rc_controls.h"
45 #include "fc/runtime_config.h"
47 #include "flight/gps_rescue.h"
48 #include "flight/imu.h"
49 #include "flight/mixer.h"
50 #include "flight/rpm_filter.h"
51 #include "flight/feedforward.h"
56 #include "pg/pg_ids.h"
58 #include "sensors/acceleration.h"
59 #include "sensors/battery.h"
60 #include "sensors/gyro.h"
70 const char pidNames
[] =
77 FAST_DATA_ZERO_INIT
uint32_t targetPidLooptime
;
78 FAST_DATA_ZERO_INIT pidAxisData_t pidData
[XYZ_AXIS_COUNT
];
79 FAST_DATA_ZERO_INIT pidRuntime_t pidRuntime
;
81 #if defined(USE_ABSOLUTE_CONTROL)
82 STATIC_UNIT_TESTED FAST_DATA_ZERO_INIT
float axisError
[XYZ_AXIS_COUNT
];
85 #if defined(USE_THROTTLE_BOOST)
86 FAST_DATA_ZERO_INIT
float throttleBoost
;
87 pt1Filter_t throttleLpf
;
90 PG_REGISTER_WITH_RESET_TEMPLATE(pidConfig_t
, pidConfig
, PG_PID_CONFIG
, 3);
92 #if defined(STM32F411xE)
93 #define PID_PROCESS_DENOM_DEFAULT 2
95 #define PID_PROCESS_DENOM_DEFAULT 1
98 #ifdef USE_RUNAWAY_TAKEOFF
99 PG_RESET_TEMPLATE(pidConfig_t
, pidConfig
,
100 .pid_process_denom
= PID_PROCESS_DENOM_DEFAULT
,
101 .runaway_takeoff_prevention
= true,
102 .runaway_takeoff_deactivate_throttle
= 20, // throttle level % needed to accumulate deactivation time
103 .runaway_takeoff_deactivate_delay
= 500 // Accumulated time (in milliseconds) before deactivation in successful takeoff
106 PG_RESET_TEMPLATE(pidConfig_t
, pidConfig
,
107 .pid_process_denom
= PID_PROCESS_DENOM_DEFAULT
111 #ifdef USE_ACRO_TRAINER
112 #define ACRO_TRAINER_LOOKAHEAD_RATE_LIMIT 500.0f // Max gyro rate for lookahead time scaling
113 #define ACRO_TRAINER_SETPOINT_LIMIT 1000.0f // Limit the correcting setpoint
114 #endif // USE_ACRO_TRAINER
116 #define CRASH_RECOVERY_DETECTION_DELAY_US 1000000 // 1 second delay before crash recovery detection is active after entering a self-level mode
118 #define LAUNCH_CONTROL_YAW_ITERM_LIMIT 50 // yaw iterm windup limit when launch mode is "FULL" (all axes)
120 PG_REGISTER_ARRAY_WITH_RESET_FN(pidProfile_t
, PID_PROFILE_COUNT
, pidProfiles
, PG_PID_PROFILE
, 4);
122 void resetPidProfile(pidProfile_t
*pidProfile
)
124 RESET_CONFIG(pidProfile_t
, pidProfile
,
126 [PID_ROLL
] = PID_ROLL_DEFAULT
,
127 [PID_PITCH
] = PID_PITCH_DEFAULT
,
128 [PID_YAW
] = PID_YAW_DEFAULT
,
129 [PID_LEVEL
] = { 50, 50, 75, 0 },
130 [PID_MAG
] = { 40, 0, 0, 0 },
132 .pidSumLimit
= PIDSUM_LIMIT
,
133 .pidSumLimitYaw
= PIDSUM_LIMIT_YAW
,
134 .yaw_lowpass_hz
= 100,
136 .dterm_notch_cutoff
= 0,
137 .itermWindupPointPercent
= 85,
138 .pidAtMinThrottle
= PID_STABILISATION_ON
,
139 .levelAngleLimit
= 55,
140 .feedforward_transition
= 0,
141 .yawRateAccelLimit
= 0,
143 .anti_gravity_gain
= 80,
144 .crash_time
= 500, // ms
145 .crash_delay
= 0, // ms
146 .crash_recovery_angle
= 10, // degrees
147 .crash_recovery_rate
= 100, // degrees/second
148 .crash_dthreshold
= 50, // degrees/second/second
149 .crash_gthreshold
= 400, // degrees/second
150 .crash_setpoint_threshold
= 350, // degrees/second
151 .crash_recovery
= PID_CRASH_RECOVERY_OFF
, // off by default
152 .horizon_tilt_effect
= 75,
153 .horizon_tilt_expert_mode
= false,
154 .crash_limit_yaw
= 200,
157 .throttle_boost_cutoff
= 15,
158 .iterm_rotation
= false,
159 .iterm_relax
= ITERM_RELAX_RP
,
160 .iterm_relax_cutoff
= ITERM_RELAX_CUTOFF_DEFAULT
,
161 .iterm_relax_type
= ITERM_RELAX_SETPOINT
,
162 .acro_trainer_angle_limit
= 20,
163 .acro_trainer_lookahead_ms
= 50,
164 .acro_trainer_debug_axis
= FD_ROLL
,
165 .acro_trainer_gain
= 75,
166 .abs_control_gain
= 0,
167 .abs_control_limit
= 90,
168 .abs_control_error_limit
= 20,
169 .abs_control_cutoff
= 11,
170 .dterm_lpf1_static_hz
= DTERM_LPF1_DYN_MIN_HZ_DEFAULT
,
171 // NOTE: dynamic lpf is enabled by default so this setting is actually
172 // overridden and the static lowpass 1 is disabled. We can't set this
173 // value to 0 otherwise Configurator versions 10.4 and earlier will also
174 // reset the lowpass filter type to PT1 overriding the desired BIQUAD setting.
175 .dterm_lpf2_static_hz
= DTERM_LPF2_HZ_DEFAULT
, // second Dterm LPF ON by default
176 .dterm_lpf1_type
= FILTER_PT1
,
177 .dterm_lpf2_type
= FILTER_PT1
,
178 .dterm_lpf1_dyn_min_hz
= DTERM_LPF1_DYN_MIN_HZ_DEFAULT
,
179 .dterm_lpf1_dyn_max_hz
= DTERM_LPF1_DYN_MAX_HZ_DEFAULT
,
180 .launchControlMode
= LAUNCH_CONTROL_MODE_NORMAL
,
181 .launchControlThrottlePercent
= 20,
182 .launchControlAngleLimit
= 0,
183 .launchControlGain
= 40,
184 .launchControlAllowTriggerReset
= true,
185 .use_integrated_yaw
= false,
186 .integrated_yaw_relax
= 200,
187 .thrustLinearization
= 0,
188 .d_min
= D_MIN_DEFAULT
,
191 .motor_output_limit
= 100,
192 .auto_profile_cell_count
= AUTO_PROFILE_CELL_COUNT_STAY
,
193 .transient_throttle_limit
= 0,
194 .profileName
= { 0 },
195 .dyn_idle_min_rpm
= 0,
196 .dyn_idle_p_gain
= 50,
197 .dyn_idle_i_gain
= 50,
198 .dyn_idle_d_gain
= 50,
199 .dyn_idle_max_increase
= 150,
200 .feedforward_averaging
= FEEDFORWARD_AVERAGING_OFF
,
201 .feedforward_max_rate_limit
= 90,
202 .feedforward_smooth_factor
= 25,
203 .feedforward_jitter_factor
= 7,
204 .feedforward_boost
= 15,
205 .dterm_lpf1_dyn_expo
= 5,
206 .level_race_mode
= false,
207 .vbat_sag_compensation
= 0,
208 .simplified_pids_mode
= PID_SIMPLIFIED_TUNING_RPY
,
209 .simplified_master_multiplier
= SIMPLIFIED_TUNING_DEFAULT
,
210 .simplified_roll_pitch_ratio
= SIMPLIFIED_TUNING_DEFAULT
,
211 .simplified_i_gain
= SIMPLIFIED_TUNING_DEFAULT
,
212 .simplified_d_gain
= SIMPLIFIED_TUNING_D_DEFAULT
,
213 .simplified_pi_gain
= SIMPLIFIED_TUNING_DEFAULT
,
214 .simplified_dmin_ratio
= SIMPLIFIED_TUNING_D_DEFAULT
,
215 .simplified_feedforward_gain
= SIMPLIFIED_TUNING_DEFAULT
,
216 .simplified_pitch_pi_gain
= SIMPLIFIED_TUNING_DEFAULT
,
217 .simplified_dterm_filter
= true,
218 .simplified_dterm_filter_multiplier
= SIMPLIFIED_TUNING_DEFAULT
,
219 .anti_gravity_cutoff_hz
= 5,
220 .anti_gravity_p_gain
= 100,
224 pidProfile
->pid
[PID_ROLL
].D
= 30;
225 pidProfile
->pid
[PID_PITCH
].D
= 32;
229 void pgResetFn_pidProfiles(pidProfile_t
*pidProfiles
)
231 for (int i
= 0; i
< PID_PROFILE_COUNT
; i
++) {
232 resetPidProfile(&pidProfiles
[i
]);
236 // Scale factors to make best use of range with D_LPF debugging, aiming for max +/-16K as debug values are 16 bit
237 #define D_LPF_RAW_SCALE 25
238 #define D_LPF_FILT_SCALE 22
241 void pidSetItermAccelerator(float newItermAccelerator
)
243 pidRuntime
.itermAccelerator
= newItermAccelerator
;
246 bool pidOsdAntiGravityActive(void)
248 return (pidRuntime
.itermAccelerator
> pidRuntime
.antiGravityOsdCutoff
);
251 void pidStabilisationState(pidStabilisationState_e pidControllerState
)
253 pidRuntime
.pidStabilisationEnabled
= (pidControllerState
== PID_STABILISATION_ON
) ? true : false;
256 const angle_index_t rcAliasToAngleIndexMap
[] = { AI_ROLL
, AI_PITCH
};
258 #ifdef USE_FEEDFORWARD
259 float pidGetFeedforwardTransitionFactor()
261 return pidRuntime
.feedforwardTransitionFactor
;
264 float pidGetFeedforwardSmoothFactor()
266 return pidRuntime
.feedforwardSmoothFactor
;
269 float pidGetFeedforwardJitterFactor()
271 return pidRuntime
.feedforwardJitterFactor
;
274 float pidGetFeedforwardBoostFactor()
276 return pidRuntime
.feedforwardBoostFactor
;
280 void pidResetIterm(void)
282 for (int axis
= 0; axis
< 3; axis
++) {
283 pidData
[axis
].I
= 0.0f
;
284 #if defined(USE_ABSOLUTE_CONTROL)
285 axisError
[axis
] = 0.0f
;
290 void pidUpdateTpaFactor(float throttle
)
292 const float tpaBreakpoint
= (currentControlRateProfile
->tpa_breakpoint
- 1000) / 1000.0f
;
293 float tpaRate
= currentControlRateProfile
->tpa_rate
/ 100.0f
;
294 if (throttle
> tpaBreakpoint
) {
295 if (throttle
< 1.0f
) {
296 tpaRate
*= (throttle
- tpaBreakpoint
) / (1.0f
- tpaBreakpoint
);
301 pidRuntime
.tpaFactor
= 1.0f
- tpaRate
;
304 void pidUpdateAntiGravityThrottleFilter(float throttle
)
306 static float previousThrottle
= 0.0f
;
307 const float throttleInv
= 1.0f
- throttle
;
308 float throttleDerivative
= fabsf(throttle
- previousThrottle
) * pidRuntime
.pidFrequency
;
309 DEBUG_SET(DEBUG_ANTI_GRAVITY
, 0, lrintf(throttleDerivative
* 100));
310 throttleDerivative
*= throttleInv
* throttleInv
;
311 // generally focus on the low throttle period
312 if (throttle
> previousThrottle
) {
313 throttleDerivative
*= throttleInv
* 0.5f
;
314 // when increasing throttle, focus even more on the low throttle range
316 previousThrottle
= throttle
;
317 throttleDerivative
= pt2FilterApply(&pidRuntime
.antiGravityLpf
, throttleDerivative
);
318 // lower cutoff suppresses peaks relative to troughs and prolongs the effects
319 // PT2 smoothing of throttle derivative.
320 // 6 is a typical value for the peak boost factor with default cutoff of 6Hz
321 DEBUG_SET(DEBUG_ANTI_GRAVITY
, 1, lrintf(throttleDerivative
* 100));
322 pidRuntime
.antiGravityThrottleD
= throttleDerivative
;
325 #ifdef USE_ACRO_TRAINER
326 void pidAcroTrainerInit(void)
328 pidRuntime
.acroTrainerAxisState
[FD_ROLL
] = 0;
329 pidRuntime
.acroTrainerAxisState
[FD_PITCH
] = 0;
331 #endif // USE_ACRO_TRAINER
333 #ifdef USE_THRUST_LINEARIZATION
334 float pidCompensateThrustLinearization(float throttle
)
336 if (pidRuntime
.thrustLinearization
!= 0.0f
) {
337 // for whoops where a lot of TL is needed, allow more throttle boost
338 const float throttleReversed
= (1.0f
- throttle
);
339 throttle
/= 1.0f
+ pidRuntime
.throttleCompensateAmount
* sq(throttleReversed
);
344 float pidApplyThrustLinearization(float motorOutput
)
346 if (pidRuntime
.thrustLinearization
!= 0.0f
) {
347 if (motorOutput
> 0.0f
) {
348 const float motorOutputReversed
= (1.0f
- motorOutput
);
349 motorOutput
*= 1.0f
+ sq(motorOutputReversed
) * pidRuntime
.thrustLinearization
;
357 // calculate the stick deflection while applying level mode expo
358 static float getLevelModeRcDeflection(uint8_t axis
)
360 const float stickDeflection
= getRcDeflection(axis
);
362 const float expof
= currentControlRateProfile
->levelExpo
[axis
] / 100.0f
;
363 return power3(stickDeflection
) * expof
+ stickDeflection
* (1 - expof
);
365 return stickDeflection
;
369 // calculates strength of horizon leveling; 0 = none, 1.0 = most leveling
370 STATIC_UNIT_TESTED FAST_CODE_NOINLINE
float calcHorizonLevelStrength()
372 // start with 1.0 at center stick, 0.0 at max stick deflection:
373 float horizonLevelStrength
= 1.0f
- MAX(fabsf(getLevelModeRcDeflection(FD_ROLL
)), fabsf(getLevelModeRcDeflection(FD_PITCH
)));
375 // 0 at level, 90 at vertical, 180 at inverted (degrees):
376 const float currentInclination
= MAX(ABS(attitude
.values
.roll
), ABS(attitude
.values
.pitch
)) / 10.0f
;
378 // horizonTiltExpertMode: 0 = leveling always active when sticks centered,
379 // 1 = leveling can be totally off when inverted
380 if (pidRuntime
.horizonTiltExpertMode
) {
381 if (pidRuntime
.horizonTransition
> 0 && pidRuntime
.horizonCutoffDegrees
> 0) {
382 // if d_level > 0 and horizonTiltEffect < 175
383 // horizonCutoffDegrees: 0 to 125 => 270 to 90 (represents where leveling goes to zero)
384 // inclinationLevelRatio (0.0 to 1.0) is smaller (less leveling)
385 // for larger inclinations; 0.0 at horizonCutoffDegrees value:
386 const float inclinationLevelRatio
= constrainf((pidRuntime
.horizonCutoffDegrees
-currentInclination
) / pidRuntime
.horizonCutoffDegrees
, 0, 1);
387 // apply configured horizon sensitivity:
388 // when stick is near center (horizonLevelStrength ~= 1.0)
389 // H_sensitivity value has little effect,
390 // when stick is deflected (horizonLevelStrength near 0.0)
391 // H_sensitivity value has more effect:
392 horizonLevelStrength
= (horizonLevelStrength
- 1) * 100 / pidRuntime
.horizonTransition
+ 1;
393 // apply inclination ratio, which may lower leveling
394 // to zero regardless of stick position:
395 horizonLevelStrength
*= inclinationLevelRatio
;
396 } else { // d_level=0 or horizon_tilt_effect>=175 means no leveling
397 horizonLevelStrength
= 0;
399 } else { // horizon_tilt_expert_mode = 0 (leveling always active when sticks centered)
401 if (pidRuntime
.horizonFactorRatio
< 1.0f
) { // if horizonTiltEffect > 0
402 // horizonFactorRatio: 1.0 to 0.0 (larger means more leveling)
403 // inclinationLevelRatio (0.0 to 1.0) is smaller (less leveling)
404 // for larger inclinations, goes to 1.0 at inclination==level:
405 const float inclinationLevelRatio
= (180 - currentInclination
) / 180 * (1.0f
- pidRuntime
.horizonFactorRatio
) + pidRuntime
.horizonFactorRatio
;
406 // apply ratio to configured horizon sensitivity:
407 sensitFact
= pidRuntime
.horizonTransition
* inclinationLevelRatio
;
408 } else { // horizonTiltEffect=0 for "old" functionality
409 sensitFact
= pidRuntime
.horizonTransition
;
412 if (sensitFact
<= 0) { // zero means no leveling
413 horizonLevelStrength
= 0;
415 // when stick is near center (horizonLevelStrength ~= 1.0)
416 // sensitFact value has little effect,
417 // when stick is deflected (horizonLevelStrength near 0.0)
418 // sensitFact value has more effect:
419 horizonLevelStrength
= ((horizonLevelStrength
- 1) * (100 / sensitFact
)) + 1;
423 return constrainf(horizonLevelStrength
, 0, 1);
426 // Use the FAST_CODE_NOINLINE directive to avoid this code from being inlined into ITCM RAM to avoid overflow.
427 // The impact is possibly slightly slower performance on F7/H7 but they have more than enough
428 // processing power that it should be a non-issue.
429 STATIC_UNIT_TESTED FAST_CODE_NOINLINE
float pidLevel(int axis
, const pidProfile_t
*pidProfile
, const rollAndPitchTrims_t
*angleTrim
,
430 float currentPidSetpoint
, float horizonLevelStrength
)
432 const float levelAngleLimit
= pidProfile
->levelAngleLimit
;
433 // calculate error angle and limit the angle to the max inclination
434 // rcDeflection is in range [-1.0, 1.0]
435 float angle
= levelAngleLimit
* getLevelModeRcDeflection(axis
);
436 #ifdef USE_GPS_RESCUE
437 angle
+= gpsRescueAngle
[axis
] / 100; // ANGLE IS IN CENTIDEGREES
439 angle
= constrainf(angle
, -levelAngleLimit
, levelAngleLimit
);
440 const float errorAngle
= angle
- ((attitude
.raw
[axis
] - angleTrim
->raw
[axis
]) / 10.0f
);
441 if (FLIGHT_MODE(ANGLE_MODE
) || FLIGHT_MODE(GPS_RESCUE_MODE
)) {
442 // ANGLE mode - control is angle based
443 const float setpointCorrection
= errorAngle
* pidRuntime
.levelGain
;
444 currentPidSetpoint
= pt3FilterApply(&pidRuntime
.attitudeFilter
[axis
], setpointCorrection
);
446 // HORIZON mode - mix of ANGLE and ACRO modes
447 // mix in errorAngle to currentPidSetpoint to add a little auto-level feel
448 const float setpointCorrection
= errorAngle
* pidRuntime
.horizonGain
* horizonLevelStrength
;
449 currentPidSetpoint
+= pt3FilterApply(&pidRuntime
.attitudeFilter
[axis
], setpointCorrection
);
451 return currentPidSetpoint
;
454 static void handleCrashRecovery(
455 const pidCrashRecovery_e crash_recovery
, const rollAndPitchTrims_t
*angleTrim
,
456 const int axis
, const timeUs_t currentTimeUs
, const float gyroRate
, float *currentPidSetpoint
, float *errorRate
)
458 if (pidRuntime
.inCrashRecoveryMode
&& cmpTimeUs(currentTimeUs
, pidRuntime
.crashDetectedAtUs
) > pidRuntime
.crashTimeDelayUs
) {
459 if (crash_recovery
== PID_CRASH_RECOVERY_BEEP
) {
462 if (axis
== FD_YAW
) {
463 *errorRate
= constrainf(*errorRate
, -pidRuntime
.crashLimitYaw
, pidRuntime
.crashLimitYaw
);
465 // on roll and pitch axes calculate currentPidSetpoint and errorRate to level the aircraft to recover from crash
466 if (sensors(SENSOR_ACC
)) {
467 // errorAngle is deviation from horizontal
468 const float errorAngle
= -(attitude
.raw
[axis
] - angleTrim
->raw
[axis
]) / 10.0f
;
469 *currentPidSetpoint
= errorAngle
* pidRuntime
.levelGain
;
470 *errorRate
= *currentPidSetpoint
- gyroRate
;
473 // reset iterm, since accumulated error before crash is now meaningless
474 // and iterm windup during crash recovery can be extreme, especially on yaw axis
475 pidData
[axis
].I
= 0.0f
;
476 if (cmpTimeUs(currentTimeUs
, pidRuntime
.crashDetectedAtUs
) > pidRuntime
.crashTimeLimitUs
477 || (getMotorMixRange() < 1.0f
478 && fabsf(gyro
.gyroADCf
[FD_ROLL
]) < pidRuntime
.crashRecoveryRate
479 && fabsf(gyro
.gyroADCf
[FD_PITCH
]) < pidRuntime
.crashRecoveryRate
480 && fabsf(gyro
.gyroADCf
[FD_YAW
]) < pidRuntime
.crashRecoveryRate
)) {
481 if (sensors(SENSOR_ACC
)) {
482 // check aircraft nearly level
483 if (ABS(attitude
.raw
[FD_ROLL
] - angleTrim
->raw
[FD_ROLL
]) < pidRuntime
.crashRecoveryAngleDeciDegrees
484 && ABS(attitude
.raw
[FD_PITCH
] - angleTrim
->raw
[FD_PITCH
]) < pidRuntime
.crashRecoveryAngleDeciDegrees
) {
485 pidRuntime
.inCrashRecoveryMode
= false;
489 pidRuntime
.inCrashRecoveryMode
= false;
496 static void detectAndSetCrashRecovery(
497 const pidCrashRecovery_e crash_recovery
, const int axis
,
498 const timeUs_t currentTimeUs
, const float delta
, const float errorRate
)
500 // if crash recovery is on and accelerometer enabled and there is no gyro overflow, then check for a crash
501 // no point in trying to recover if the crash is so severe that the gyro overflows
502 if ((crash_recovery
|| FLIGHT_MODE(GPS_RESCUE_MODE
)) && !gyroOverflowDetected()) {
503 if (ARMING_FLAG(ARMED
)) {
504 if (getMotorMixRange() >= 1.0f
&& !pidRuntime
.inCrashRecoveryMode
505 && fabsf(delta
) > pidRuntime
.crashDtermThreshold
506 && fabsf(errorRate
) > pidRuntime
.crashGyroThreshold
507 && fabsf(getSetpointRate(axis
)) < pidRuntime
.crashSetpointThreshold
) {
508 if (crash_recovery
== PID_CRASH_RECOVERY_DISARM
) {
509 setArmingDisabled(ARMING_DISABLED_CRASH_DETECTED
);
510 disarm(DISARM_REASON_CRASH_PROTECTION
);
512 pidRuntime
.inCrashRecoveryMode
= true;
513 pidRuntime
.crashDetectedAtUs
= currentTimeUs
;
516 if (pidRuntime
.inCrashRecoveryMode
&& cmpTimeUs(currentTimeUs
, pidRuntime
.crashDetectedAtUs
) < pidRuntime
.crashTimeDelayUs
&& (fabsf(errorRate
) < pidRuntime
.crashGyroThreshold
517 || fabsf(getSetpointRate(axis
)) > pidRuntime
.crashSetpointThreshold
)) {
518 pidRuntime
.inCrashRecoveryMode
= false;
521 } else if (pidRuntime
.inCrashRecoveryMode
) {
522 pidRuntime
.inCrashRecoveryMode
= false;
529 #ifdef USE_ACRO_TRAINER
531 int acroTrainerSign(float x
)
533 return x
> 0 ? 1 : -1;
536 // Acro Trainer - Manipulate the setPoint to limit axis angle while in acro mode
537 // There are three states:
538 // 1. Current angle has exceeded limit
539 // Apply correction to return to limit (similar to pidLevel)
540 // 2. Future overflow has been projected based on current angle and gyro rate
541 // Manage the setPoint to control the gyro rate as the actual angle approaches the limit (try to prevent overshoot)
542 // 3. If no potential overflow is detected, then return the original setPoint
544 // Use the FAST_CODE_NOINLINE directive to avoid this code from being inlined into ITCM RAM. We accept the
545 // performance decrease when Acro Trainer mode is active under the assumption that user is unlikely to be
546 // expecting ultimate flight performance at very high loop rates when in this mode.
547 static FAST_CODE_NOINLINE
float applyAcroTrainer(int axis
, const rollAndPitchTrims_t
*angleTrim
, float setPoint
)
549 float ret
= setPoint
;
551 if (!FLIGHT_MODE(ANGLE_MODE
) && !FLIGHT_MODE(HORIZON_MODE
) && !FLIGHT_MODE(GPS_RESCUE_MODE
)) {
552 bool resetIterm
= false;
553 float projectedAngle
= 0;
554 const int setpointSign
= acroTrainerSign(setPoint
);
555 const float currentAngle
= (attitude
.raw
[axis
] - angleTrim
->raw
[axis
]) / 10.0f
;
556 const int angleSign
= acroTrainerSign(currentAngle
);
558 if ((pidRuntime
.acroTrainerAxisState
[axis
] != 0) && (pidRuntime
.acroTrainerAxisState
[axis
] != setpointSign
)) { // stick has reversed - stop limiting
559 pidRuntime
.acroTrainerAxisState
[axis
] = 0;
562 // Limit and correct the angle when it exceeds the limit
563 if ((fabsf(currentAngle
) > pidRuntime
.acroTrainerAngleLimit
) && (pidRuntime
.acroTrainerAxisState
[axis
] == 0)) {
564 if (angleSign
== setpointSign
) {
565 pidRuntime
.acroTrainerAxisState
[axis
] = angleSign
;
570 if (pidRuntime
.acroTrainerAxisState
[axis
] != 0) {
571 ret
= constrainf(((pidRuntime
.acroTrainerAngleLimit
* angleSign
) - currentAngle
) * pidRuntime
.acroTrainerGain
, -ACRO_TRAINER_SETPOINT_LIMIT
, ACRO_TRAINER_SETPOINT_LIMIT
);
574 // Not currently over the limit so project the angle based on current angle and
575 // gyro angular rate using a sliding window based on gyro rate (faster rotation means larger window.
576 // If the projected angle exceeds the limit then apply limiting to minimize overshoot.
577 // Calculate the lookahead window by scaling proportionally with gyro rate from 0-500dps
578 float checkInterval
= constrainf(fabsf(gyro
.gyroADCf
[axis
]) / ACRO_TRAINER_LOOKAHEAD_RATE_LIMIT
, 0.0f
, 1.0f
) * pidRuntime
.acroTrainerLookaheadTime
;
579 projectedAngle
= (gyro
.gyroADCf
[axis
] * checkInterval
) + currentAngle
;
580 const int projectedAngleSign
= acroTrainerSign(projectedAngle
);
581 if ((fabsf(projectedAngle
) > pidRuntime
.acroTrainerAngleLimit
) && (projectedAngleSign
== setpointSign
)) {
582 ret
= ((pidRuntime
.acroTrainerAngleLimit
* projectedAngleSign
) - projectedAngle
) * pidRuntime
.acroTrainerGain
;
591 if (axis
== pidRuntime
.acroTrainerDebugAxis
) {
592 DEBUG_SET(DEBUG_ACRO_TRAINER
, 0, lrintf(currentAngle
* 10.0f
));
593 DEBUG_SET(DEBUG_ACRO_TRAINER
, 1, pidRuntime
.acroTrainerAxisState
[axis
]);
594 DEBUG_SET(DEBUG_ACRO_TRAINER
, 2, lrintf(ret
));
595 DEBUG_SET(DEBUG_ACRO_TRAINER
, 3, lrintf(projectedAngle
* 10.0f
));
601 #endif // USE_ACRO_TRAINER
603 static float accelerationLimit(int axis
, float currentPidSetpoint
)
605 static float previousSetpoint
[XYZ_AXIS_COUNT
];
606 const float currentVelocity
= currentPidSetpoint
- previousSetpoint
[axis
];
608 if (fabsf(currentVelocity
) > pidRuntime
.maxVelocity
[axis
]) {
609 currentPidSetpoint
= (currentVelocity
> 0) ? previousSetpoint
[axis
] + pidRuntime
.maxVelocity
[axis
] : previousSetpoint
[axis
] - pidRuntime
.maxVelocity
[axis
];
612 previousSetpoint
[axis
] = currentPidSetpoint
;
613 return currentPidSetpoint
;
616 static void rotateVector(float v
[XYZ_AXIS_COUNT
], float rotation
[XYZ_AXIS_COUNT
])
618 // rotate v around rotation vector rotation
619 // rotation in radians, all elements must be small
620 for (int i
= 0; i
< XYZ_AXIS_COUNT
; i
++) {
621 int i_1
= (i
+ 1) % 3;
622 int i_2
= (i
+ 2) % 3;
623 float newV
= v
[i_1
] + v
[i_2
] * rotation
[i
];
624 v
[i_2
] -= v
[i_1
] * rotation
[i
];
629 STATIC_UNIT_TESTED
void rotateItermAndAxisError()
631 if (pidRuntime
.itermRotation
632 #if defined(USE_ABSOLUTE_CONTROL)
633 || pidRuntime
.acGain
> 0 || debugMode
== DEBUG_AC_ERROR
636 const float gyroToAngle
= pidRuntime
.dT
* RAD
;
637 float rotationRads
[XYZ_AXIS_COUNT
];
638 for (int i
= FD_ROLL
; i
<= FD_YAW
; i
++) {
639 rotationRads
[i
] = gyro
.gyroADCf
[i
] * gyroToAngle
;
641 #if defined(USE_ABSOLUTE_CONTROL)
642 if (pidRuntime
.acGain
> 0 || debugMode
== DEBUG_AC_ERROR
) {
643 rotateVector(axisError
, rotationRads
);
646 if (pidRuntime
.itermRotation
) {
647 float v
[XYZ_AXIS_COUNT
];
648 for (int i
= 0; i
< XYZ_AXIS_COUNT
; i
++) {
651 rotateVector(v
, rotationRads
);
652 for (int i
= 0; i
< XYZ_AXIS_COUNT
; i
++) {
659 #ifdef USE_RC_SMOOTHING_FILTER
660 float FAST_CODE
applyRcSmoothingFeedforwardFilter(int axis
, float pidSetpointDelta
)
662 float ret
= pidSetpointDelta
;
663 if (axis
== pidRuntime
.rcSmoothingDebugAxis
) {
664 DEBUG_SET(DEBUG_RC_SMOOTHING
, 1, lrintf(pidSetpointDelta
* 100.0f
));
666 if (pidRuntime
.feedforwardLpfInitialized
) {
667 ret
= pt3FilterApply(&pidRuntime
.feedforwardPt3
[axis
], pidSetpointDelta
);
668 if (axis
== pidRuntime
.rcSmoothingDebugAxis
) {
669 DEBUG_SET(DEBUG_RC_SMOOTHING
, 2, lrintf(ret
* 100.0f
));
674 #endif // USE_RC_SMOOTHING_FILTER
676 #if defined(USE_ITERM_RELAX)
677 #if defined(USE_ABSOLUTE_CONTROL)
678 STATIC_UNIT_TESTED
void applyAbsoluteControl(const int axis
, const float gyroRate
, float *currentPidSetpoint
, float *itermErrorRate
)
680 if (pidRuntime
.acGain
> 0 || debugMode
== DEBUG_AC_ERROR
) {
681 const float setpointLpf
= pt1FilterApply(&pidRuntime
.acLpf
[axis
], *currentPidSetpoint
);
682 const float setpointHpf
= fabsf(*currentPidSetpoint
- setpointLpf
);
683 float acErrorRate
= 0;
684 const float gmaxac
= setpointLpf
+ 2 * setpointHpf
;
685 const float gminac
= setpointLpf
- 2 * setpointHpf
;
686 if (gyroRate
>= gminac
&& gyroRate
<= gmaxac
) {
687 const float acErrorRate1
= gmaxac
- gyroRate
;
688 const float acErrorRate2
= gminac
- gyroRate
;
689 if (acErrorRate1
* axisError
[axis
] < 0) {
690 acErrorRate
= acErrorRate1
;
692 acErrorRate
= acErrorRate2
;
694 if (fabsf(acErrorRate
* pidRuntime
.dT
) > fabsf(axisError
[axis
]) ) {
695 acErrorRate
= -axisError
[axis
] * pidRuntime
.pidFrequency
;
698 acErrorRate
= (gyroRate
> gmaxac
? gmaxac
: gminac
) - gyroRate
;
701 if (isAirmodeActivated()) {
702 axisError
[axis
] = constrainf(axisError
[axis
] + acErrorRate
* pidRuntime
.dT
,
703 -pidRuntime
.acErrorLimit
, pidRuntime
.acErrorLimit
);
704 const float acCorrection
= constrainf(axisError
[axis
] * pidRuntime
.acGain
, -pidRuntime
.acLimit
, pidRuntime
.acLimit
);
705 *currentPidSetpoint
+= acCorrection
;
706 *itermErrorRate
+= acCorrection
;
707 DEBUG_SET(DEBUG_AC_CORRECTION
, axis
, lrintf(acCorrection
* 10));
708 if (axis
== FD_ROLL
) {
709 DEBUG_SET(DEBUG_ITERM_RELAX
, 3, lrintf(acCorrection
* 10));
712 DEBUG_SET(DEBUG_AC_ERROR
, axis
, lrintf(axisError
[axis
] * 10));
717 STATIC_UNIT_TESTED
void applyItermRelax(const int axis
, const float iterm
,
718 const float gyroRate
, float *itermErrorRate
, float *currentPidSetpoint
)
720 const float setpointLpf
= pt1FilterApply(&pidRuntime
.windupLpf
[axis
], *currentPidSetpoint
);
721 const float setpointHpf
= fabsf(*currentPidSetpoint
- setpointLpf
);
723 if (pidRuntime
.itermRelax
) {
724 if (axis
< FD_YAW
|| pidRuntime
.itermRelax
== ITERM_RELAX_RPY
|| pidRuntime
.itermRelax
== ITERM_RELAX_RPY_INC
) {
725 const float itermRelaxFactor
= MAX(0, 1 - setpointHpf
/ ITERM_RELAX_SETPOINT_THRESHOLD
);
726 const bool isDecreasingI
=
727 ((iterm
> 0) && (*itermErrorRate
< 0)) || ((iterm
< 0) && (*itermErrorRate
> 0));
728 if ((pidRuntime
.itermRelax
>= ITERM_RELAX_RP_INC
) && isDecreasingI
) {
729 // Do Nothing, use the precalculed itermErrorRate
730 } else if (pidRuntime
.itermRelaxType
== ITERM_RELAX_SETPOINT
) {
731 *itermErrorRate
*= itermRelaxFactor
;
732 } else if (pidRuntime
.itermRelaxType
== ITERM_RELAX_GYRO
) {
733 *itermErrorRate
= fapplyDeadband(setpointLpf
- gyroRate
, setpointHpf
);
735 *itermErrorRate
= 0.0f
;
738 if (axis
== FD_ROLL
) {
739 DEBUG_SET(DEBUG_ITERM_RELAX
, 0, lrintf(setpointHpf
));
740 DEBUG_SET(DEBUG_ITERM_RELAX
, 1, lrintf(itermRelaxFactor
* 100.0f
));
741 DEBUG_SET(DEBUG_ITERM_RELAX
, 2, lrintf(*itermErrorRate
));
745 #if defined(USE_ABSOLUTE_CONTROL)
746 applyAbsoluteControl(axis
, gyroRate
, currentPidSetpoint
, itermErrorRate
);
752 #ifdef USE_AIRMODE_LPF
753 void pidUpdateAirmodeLpf(float currentOffset
)
755 if (pidRuntime
.airmodeThrottleOffsetLimit
== 0.0f
) {
759 float offsetHpf
= currentOffset
* 2.5f
;
760 offsetHpf
= offsetHpf
- pt1FilterApply(&pidRuntime
.airmodeThrottleLpf2
, offsetHpf
);
762 // During high frequency oscillation 2 * currentOffset averages to the offset required to avoid mirroring of the waveform
763 pt1FilterApply(&pidRuntime
.airmodeThrottleLpf1
, offsetHpf
);
764 // Bring offset up immediately so the filter only applies to the decline
765 if (currentOffset
* pidRuntime
.airmodeThrottleLpf1
.state
>= 0 && fabsf(currentOffset
) > pidRuntime
.airmodeThrottleLpf1
.state
) {
766 pidRuntime
.airmodeThrottleLpf1
.state
= currentOffset
;
768 pidRuntime
.airmodeThrottleLpf1
.state
= constrainf(pidRuntime
.airmodeThrottleLpf1
.state
, -pidRuntime
.airmodeThrottleOffsetLimit
, pidRuntime
.airmodeThrottleOffsetLimit
);
771 float pidGetAirmodeThrottleOffset()
773 return pidRuntime
.airmodeThrottleLpf1
.state
;
777 #ifdef USE_LAUNCH_CONTROL
778 #define LAUNCH_CONTROL_MAX_RATE 100.0f
779 #define LAUNCH_CONTROL_MIN_RATE 5.0f
780 #define LAUNCH_CONTROL_ANGLE_WINDOW 10.0f // The remaining angle degrees where rate dampening starts
782 // Use the FAST_CODE_NOINLINE directive to avoid this code from being inlined into ITCM RAM to avoid overflow.
783 // The impact is possibly slightly slower performance on F7/H7 but they have more than enough
784 // processing power that it should be a non-issue.
785 static FAST_CODE_NOINLINE
float applyLaunchControl(int axis
, const rollAndPitchTrims_t
*angleTrim
)
789 // Scale the rates based on stick deflection only. Fixed rates with a max of 100deg/sec
790 // reached at 50% stick deflection. This keeps the launch control positioning consistent
791 // regardless of the user's rates.
792 if ((axis
== FD_PITCH
) || (pidRuntime
.launchControlMode
!= LAUNCH_CONTROL_MODE_PITCHONLY
)) {
793 const float stickDeflection
= constrainf(getRcDeflection(axis
), -0.5f
, 0.5f
);
794 ret
= LAUNCH_CONTROL_MAX_RATE
* stickDeflection
* 2;
798 // If ACC is enabled and a limit angle is set, then try to limit forward tilt
799 // to that angle and slow down the rate as the limit is approached to reduce overshoot
800 if ((axis
== FD_PITCH
) && (pidRuntime
.launchControlAngleLimit
> 0) && (ret
> 0)) {
801 const float currentAngle
= (attitude
.raw
[axis
] - angleTrim
->raw
[axis
]) / 10.0f
;
802 if (currentAngle
>= pidRuntime
.launchControlAngleLimit
) {
805 //for the last 10 degrees scale the rate from the current input to 5 dps
806 const float angleDelta
= pidRuntime
.launchControlAngleLimit
- currentAngle
;
807 if (angleDelta
<= LAUNCH_CONTROL_ANGLE_WINDOW
) {
808 ret
= scaleRangef(angleDelta
, 0, LAUNCH_CONTROL_ANGLE_WINDOW
, LAUNCH_CONTROL_MIN_RATE
, ret
);
820 // Betaflight pid controller, which will be maintained in the future with additional features specialised for current (mini) multirotor usage.
821 // Based on 2DOF reference design (matlab)
822 void FAST_CODE
pidController(const pidProfile_t
*pidProfile
, timeUs_t currentTimeUs
)
824 static float previousGyroRateDterm
[XYZ_AXIS_COUNT
];
825 static float previousRawGyroRateDterm
[XYZ_AXIS_COUNT
];
828 const float tpaFactorKp
= (currentControlRateProfile
->tpaMode
== TPA_MODE_PD
) ? pidRuntime
.tpaFactor
: 1.0f
;
830 const float tpaFactorKp
= pidRuntime
.tpaFactor
;
833 #ifdef USE_YAW_SPIN_RECOVERY
834 const bool yawSpinActive
= gyroYawSpinDetected();
837 const bool launchControlActive
= isLaunchControlActive();
840 static timeUs_t levelModeStartTimeUs
= 0;
841 static bool gpsRescuePreviousState
= false;
842 const rollAndPitchTrims_t
*angleTrim
= &accelerometerConfig()->accelerometerTrims
;
843 float horizonLevelStrength
= 0.0f
;
845 const bool gpsRescueIsActive
= FLIGHT_MODE(GPS_RESCUE_MODE
);
846 levelMode_e levelMode
;
847 if (FLIGHT_MODE(ANGLE_MODE
) || FLIGHT_MODE(HORIZON_MODE
) || gpsRescueIsActive
) {
848 if (pidRuntime
.levelRaceMode
&& !gpsRescueIsActive
) {
849 levelMode
= LEVEL_MODE_R
;
851 levelMode
= LEVEL_MODE_RP
;
854 // Keep track of when we entered a self-level mode so that we can
855 // add a guard time before crash recovery can activate.
856 // Also reset the guard time whenever GPS Rescue is activated.
857 if ((levelModeStartTimeUs
== 0) || (gpsRescueIsActive
&& !gpsRescuePreviousState
)) {
858 levelModeStartTimeUs
= currentTimeUs
;
861 // Calc horizonLevelStrength if needed
862 if (FLIGHT_MODE(HORIZON_MODE
)) {
863 horizonLevelStrength
= calcHorizonLevelStrength();
866 levelMode
= LEVEL_MODE_OFF
;
867 levelModeStartTimeUs
= 0;
870 gpsRescuePreviousState
= gpsRescueIsActive
;
873 UNUSED(currentTimeUs
);
877 if (pidRuntime
.antiGravityEnabled
) {
878 pidRuntime
.antiGravityThrottleD
*= pidRuntime
.antiGravityGain
;
879 // used later to increase pTerm
880 pidRuntime
.itermAccelerator
= pidRuntime
.antiGravityThrottleD
* ANTIGRAVITY_KI
;
882 pidRuntime
.antiGravityThrottleD
= 0.0f
;
883 pidRuntime
.itermAccelerator
= 0.0f
;
885 DEBUG_SET(DEBUG_ANTI_GRAVITY
, 2, lrintf((1 + (pidRuntime
.itermAccelerator
/ pidRuntime
.pidCoefficient
[FD_PITCH
].Ki
)) * 1000));
886 // amount of antigravity added relative to user's pitch iTerm coefficient
887 pidRuntime
.itermAccelerator
*= pidRuntime
.dT
;
888 // used later to increase iTerm
890 // iTerm windup (attenuation of iTerm if motorMix range is large)
891 float dynCi
= pidRuntime
.dT
;
892 if (pidRuntime
.itermWindupPointInv
> 1.0f
) {
893 dynCi
*= constrainf((1.0f
- getMotorMixRange()) * pidRuntime
.itermWindupPointInv
, 0.0f
, 1.0f
);
896 // Precalculate gyro delta for D-term here, this allows loop unrolling
897 float gyroRateDterm
[XYZ_AXIS_COUNT
];
898 for (int axis
= FD_ROLL
; axis
<= FD_YAW
; ++axis
) {
899 gyroRateDterm
[axis
] = gyro
.gyroADCf
[axis
];
900 // -----calculate raw, unfiltered D component
902 // Divide rate change by dT to get differential (ie dr/dt).
903 // dT is fixed and calculated from the target PID loop time
904 // This is done to avoid DTerm spikes that occur with dynamically
905 // calculated deltaT whenever another task causes the PID
906 // loop execution to be delayed.
908 // Log the unfiltered D for ROLL and PITCH
909 if (axis
!= FD_YAW
) {
910 const float delta
= (previousRawGyroRateDterm
[axis
] - gyroRateDterm
[axis
]) * pidRuntime
.pidFrequency
/ D_LPF_RAW_SCALE
;
911 previousRawGyroRateDterm
[axis
] = gyroRateDterm
[axis
];
912 DEBUG_SET(DEBUG_D_LPF
, axis
, lrintf(delta
));
915 gyroRateDterm
[axis
] = pidRuntime
.dtermNotchApplyFn((filter_t
*) &pidRuntime
.dtermNotch
[axis
], gyroRateDterm
[axis
]);
916 gyroRateDterm
[axis
] = pidRuntime
.dtermLowpassApplyFn((filter_t
*) &pidRuntime
.dtermLowpass
[axis
], gyroRateDterm
[axis
]);
917 gyroRateDterm
[axis
] = pidRuntime
.dtermLowpass2ApplyFn((filter_t
*) &pidRuntime
.dtermLowpass2
[axis
], gyroRateDterm
[axis
]);
920 rotateItermAndAxisError();
922 #ifdef USE_RPM_FILTER
926 #ifdef USE_FEEDFORWARD
927 const bool newRcFrame
= getShouldUpdateFeedforward();
930 // ----------PID controller----------
931 for (int axis
= FD_ROLL
; axis
<= FD_YAW
; ++axis
) {
933 float currentPidSetpoint
= getSetpointRate(axis
);
934 if (pidRuntime
.maxVelocity
[axis
]) {
935 currentPidSetpoint
= accelerationLimit(axis
, currentPidSetpoint
);
937 // Yaw control is GYRO based, direct sticks control is applied to rate PID
938 // When Race Mode is active PITCH control is also GYRO based in level or horizon mode
940 if ((levelMode
== LEVEL_MODE_R
&& axis
== FD_ROLL
)
941 || (levelMode
== LEVEL_MODE_RP
&& (axis
== FD_ROLL
|| axis
== FD_PITCH
)) ) {
942 currentPidSetpoint
= pidLevel(axis
, pidProfile
, angleTrim
, currentPidSetpoint
, horizonLevelStrength
);
943 DEBUG_SET(DEBUG_ATTITUDE
, axis
- FD_ROLL
+ 2, currentPidSetpoint
);
947 #ifdef USE_ACRO_TRAINER
948 if ((axis
!= FD_YAW
) && pidRuntime
.acroTrainerActive
&& !pidRuntime
.inCrashRecoveryMode
&& !launchControlActive
) {
949 currentPidSetpoint
= applyAcroTrainer(axis
, angleTrim
, currentPidSetpoint
);
951 #endif // USE_ACRO_TRAINER
953 #ifdef USE_LAUNCH_CONTROL
954 if (launchControlActive
) {
956 currentPidSetpoint
= applyLaunchControl(axis
, angleTrim
);
958 currentPidSetpoint
= applyLaunchControl(axis
, NULL
);
963 // Handle yaw spin recovery - zero the setpoint on yaw to aid in recovery
964 // It's not necessary to zero the set points for R/P because the PIDs will be zeroed below
965 #ifdef USE_YAW_SPIN_RECOVERY
966 if ((axis
== FD_YAW
) && yawSpinActive
) {
967 currentPidSetpoint
= 0.0f
;
969 #endif // USE_YAW_SPIN_RECOVERY
971 // -----calculate error rate
972 const float gyroRate
= gyro
.gyroADCf
[axis
]; // Process variable from gyro output in deg/sec
973 float errorRate
= currentPidSetpoint
- gyroRate
; // r - y
976 pidProfile
->crash_recovery
, angleTrim
, axis
, currentTimeUs
, gyroRate
,
977 ¤tPidSetpoint
, &errorRate
);
980 const float previousIterm
= pidData
[axis
].I
;
981 float itermErrorRate
= errorRate
;
982 #ifdef USE_ABSOLUTE_CONTROL
983 const float uncorrectedSetpoint
= currentPidSetpoint
;
986 #if defined(USE_ITERM_RELAX)
987 if (!launchControlActive
&& !pidRuntime
.inCrashRecoveryMode
) {
988 applyItermRelax(axis
, previousIterm
, gyroRate
, &itermErrorRate
, ¤tPidSetpoint
);
989 errorRate
= currentPidSetpoint
- gyroRate
;
992 #ifdef USE_ABSOLUTE_CONTROL
993 const float setpointCorrection
= currentPidSetpoint
- uncorrectedSetpoint
;
996 // --------low-level gyro-based PID based on 2DOF PID controller. ----------
997 // 2-DOF PID controller with optional filter on derivative term.
998 // b = 1 and only c (feedforward weight) can be tuned (amount derivative on measurement or error).
1000 // -----calculate P component
1001 pidData
[axis
].P
= pidRuntime
.pidCoefficient
[axis
].Kp
* errorRate
* tpaFactorKp
;
1002 if (axis
== FD_YAW
) {
1003 pidData
[axis
].P
= pidRuntime
.ptermYawLowpassApplyFn((filter_t
*) &pidRuntime
.ptermYawLowpass
, pidData
[axis
].P
);
1006 // -----calculate I component
1007 float Ki
= pidRuntime
.pidCoefficient
[axis
].Ki
;
1008 #ifdef USE_LAUNCH_CONTROL
1009 // if launch control is active override the iterm gains and apply iterm windup protection to all axes
1010 if (launchControlActive
) {
1011 Ki
= pidRuntime
.launchControlKi
;
1015 if (axis
== FD_YAW
) {
1016 pidRuntime
.itermAccelerator
= 0.0f
; // no antigravity on yaw iTerm
1020 pidData
[axis
].I
= constrainf(previousIterm
+ (Ki
* dynCi
+ pidRuntime
.itermAccelerator
) * itermErrorRate
, -pidRuntime
.itermLimit
, pidRuntime
.itermLimit
);
1022 // -----calculate pidSetpointDelta
1023 float pidSetpointDelta
= 0;
1024 #ifdef USE_FEEDFORWARD
1025 pidSetpointDelta
= feedforwardApply(axis
, newRcFrame
, pidRuntime
.feedforwardAveraging
);
1027 pidRuntime
.previousPidSetpoint
[axis
] = currentPidSetpoint
;
1029 // -----calculate D component
1030 // disable D if launch control is active
1031 if ((pidRuntime
.pidCoefficient
[axis
].Kd
> 0) && !launchControlActive
) {
1033 // Divide rate change by dT to get differential (ie dr/dt).
1034 // dT is fixed and calculated from the target PID loop time
1035 // This is done to avoid DTerm spikes that occur with dynamically
1036 // calculated deltaT whenever another task causes the PID
1037 // loop execution to be delayed.
1039 - (gyroRateDterm
[axis
] - previousGyroRateDterm
[axis
]) * pidRuntime
.pidFrequency
;
1040 float preTpaD
= pidRuntime
.pidCoefficient
[axis
].Kd
* delta
;
1042 #if defined(USE_ACC)
1043 if (cmpTimeUs(currentTimeUs
, levelModeStartTimeUs
) > CRASH_RECOVERY_DETECTION_DELAY_US
) {
1044 detectAndSetCrashRecovery(pidProfile
->crash_recovery
, axis
, currentTimeUs
, delta
, errorRate
);
1048 #if defined(USE_D_MIN)
1049 float dMinFactor
= 1.0f
;
1050 if (pidRuntime
.dMinPercent
[axis
] > 0) {
1051 float dMinGyroFactor
= pt2FilterApply(&pidRuntime
.dMinRange
[axis
], delta
);
1052 dMinGyroFactor
= fabsf(dMinGyroFactor
) * pidRuntime
.dMinGyroGain
;
1053 const float dMinSetpointFactor
= (fabsf(pidSetpointDelta
)) * pidRuntime
.dMinSetpointGain
;
1054 dMinFactor
= MAX(dMinGyroFactor
, dMinSetpointFactor
);
1055 dMinFactor
= pidRuntime
.dMinPercent
[axis
] + (1.0f
- pidRuntime
.dMinPercent
[axis
]) * dMinFactor
;
1056 dMinFactor
= pt2FilterApply(&pidRuntime
.dMinLowpass
[axis
], dMinFactor
);
1057 dMinFactor
= MIN(dMinFactor
, 1.0f
);
1058 if (axis
== FD_ROLL
) {
1059 DEBUG_SET(DEBUG_D_MIN
, 0, lrintf(dMinGyroFactor
* 100));
1060 DEBUG_SET(DEBUG_D_MIN
, 1, lrintf(dMinSetpointFactor
* 100));
1061 DEBUG_SET(DEBUG_D_MIN
, 2, lrintf(pidRuntime
.pidCoefficient
[axis
].Kd
* dMinFactor
* 10 / DTERM_SCALE
));
1062 } else if (axis
== FD_PITCH
) {
1063 DEBUG_SET(DEBUG_D_MIN
, 3, lrintf(pidRuntime
.pidCoefficient
[axis
].Kd
* dMinFactor
* 10 / DTERM_SCALE
));
1067 // Apply the dMinFactor
1068 preTpaD
*= dMinFactor
;
1070 pidData
[axis
].D
= preTpaD
* pidRuntime
.tpaFactor
;
1072 // Log the value of D pre application of TPA
1073 preTpaD
*= D_LPF_FILT_SCALE
;
1075 if (axis
!= FD_YAW
) {
1076 DEBUG_SET(DEBUG_D_LPF
, axis
- FD_ROLL
+ 2, lrintf(preTpaD
));
1079 pidData
[axis
].D
= 0;
1080 if (axis
!= FD_YAW
) {
1081 DEBUG_SET(DEBUG_D_LPF
, axis
- FD_ROLL
+ 2, 0);
1085 previousGyroRateDterm
[axis
] = gyroRateDterm
[axis
];
1087 // -----calculate feedforward component
1088 #ifdef USE_ABSOLUTE_CONTROL
1089 // include abs control correction in feedforward
1090 pidSetpointDelta
+= setpointCorrection
- pidRuntime
.oldSetpointCorrection
[axis
];
1091 pidRuntime
.oldSetpointCorrection
[axis
] = setpointCorrection
;
1094 // no feedforward in launch control
1095 float feedforwardGain
= launchControlActive
? 0.0f
: pidRuntime
.pidCoefficient
[axis
].Kf
;
1096 if (feedforwardGain
> 0) {
1097 // halve feedforward in Level mode since stick sensitivity is weaker by about half
1098 feedforwardGain
*= FLIGHT_MODE(ANGLE_MODE
) ? 0.5f
: 1.0f
;
1099 // transition now calculated in feedforward.c when new RC data arrives
1100 float feedForward
= feedforwardGain
* pidSetpointDelta
* pidRuntime
.pidFrequency
;
1102 #ifdef USE_FEEDFORWARD
1103 pidData
[axis
].F
= shouldApplyFeedforwardLimits(axis
) ?
1104 applyFeedforwardLimit(axis
, feedForward
, pidRuntime
.pidCoefficient
[axis
].Kp
, currentPidSetpoint
) : feedForward
;
1106 pidData
[axis
].F
= feedForward
;
1108 #ifdef USE_RC_SMOOTHING_FILTER
1109 pidData
[axis
].F
= applyRcSmoothingFeedforwardFilter(axis
, pidData
[axis
].F
);
1110 #endif // USE_RC_SMOOTHING_FILTER
1112 pidData
[axis
].F
= 0;
1115 #ifdef USE_YAW_SPIN_RECOVERY
1116 if (yawSpinActive
) {
1117 pidData
[axis
].I
= 0; // in yaw spin always disable I
1118 if (axis
<= FD_PITCH
) {
1119 // zero PIDs on pitch and roll leaving yaw P to correct spin
1120 pidData
[axis
].P
= 0;
1121 pidData
[axis
].D
= 0;
1122 pidData
[axis
].F
= 0;
1125 #endif // USE_YAW_SPIN_RECOVERY
1127 #ifdef USE_LAUNCH_CONTROL
1128 // Disable P/I appropriately based on the launch control mode
1129 if (launchControlActive
) {
1130 // if not using FULL mode then disable I accumulation on yaw as
1131 // yaw has a tendency to windup. Otherwise limit yaw iterm accumulation.
1132 const int launchControlYawItermLimit
= (pidRuntime
.launchControlMode
== LAUNCH_CONTROL_MODE_FULL
) ? LAUNCH_CONTROL_YAW_ITERM_LIMIT
: 0;
1133 pidData
[FD_YAW
].I
= constrainf(pidData
[FD_YAW
].I
, -launchControlYawItermLimit
, launchControlYawItermLimit
);
1135 // for pitch-only mode we disable everything except pitch P/I
1136 if (pidRuntime
.launchControlMode
== LAUNCH_CONTROL_MODE_PITCHONLY
) {
1137 pidData
[FD_ROLL
].P
= 0;
1138 pidData
[FD_ROLL
].I
= 0;
1139 pidData
[FD_YAW
].P
= 0;
1140 // don't let I go negative (pitch backwards) as front motors are limited in the mixer
1141 pidData
[FD_PITCH
].I
= MAX(0.0f
, pidData
[FD_PITCH
].I
);
1146 // Add P boost from antiGravity when sticks are close to zero
1147 if (axis
!= FD_YAW
) {
1148 float agSetpointAttenuator
= fabsf(currentPidSetpoint
) / 50.0f
;
1149 agSetpointAttenuator
= MAX(agSetpointAttenuator
, 1.0f
);
1150 // attenuate effect if turning more than 50 deg/s, half at 100 deg/s
1151 const float antiGravityPBoost
= 1.0f
+ (pidRuntime
.antiGravityThrottleD
/ agSetpointAttenuator
) * pidRuntime
.antiGravityPGain
;
1152 pidData
[axis
].P
*= antiGravityPBoost
;
1153 if (axis
== FD_PITCH
) {
1154 DEBUG_SET(DEBUG_ANTI_GRAVITY
, 3, lrintf(antiGravityPBoost
* 1000));
1158 // calculating the PID sum
1159 const float pidSum
= pidData
[axis
].P
+ pidData
[axis
].I
+ pidData
[axis
].D
+ pidData
[axis
].F
;
1160 #ifdef USE_INTEGRATED_YAW_CONTROL
1161 if (axis
== FD_YAW
&& pidRuntime
.useIntegratedYaw
) {
1162 pidData
[axis
].Sum
+= pidSum
* pidRuntime
.dT
* 100.0f
;
1163 pidData
[axis
].Sum
-= pidData
[axis
].Sum
* pidRuntime
.integratedYawRelax
/ 100000.0f
* pidRuntime
.dT
/ 0.000125f
;
1167 pidData
[axis
].Sum
= pidSum
;
1171 // Disable PID control if at zero throttle or if gyro overflow detected
1172 // This may look very innefficient, but it is done on purpose to always show real CPU usage as in flight
1173 if (!pidRuntime
.pidStabilisationEnabled
|| gyroOverflowDetected()) {
1174 for (int axis
= FD_ROLL
; axis
<= FD_YAW
; ++axis
) {
1175 pidData
[axis
].P
= 0;
1176 pidData
[axis
].I
= 0;
1177 pidData
[axis
].D
= 0;
1178 pidData
[axis
].F
= 0;
1180 pidData
[axis
].Sum
= 0;
1182 } else if (pidRuntime
.zeroThrottleItermReset
) {
1187 bool crashRecoveryModeActive(void)
1189 return pidRuntime
.inCrashRecoveryMode
;
1192 #ifdef USE_ACRO_TRAINER
1193 void pidSetAcroTrainerState(bool newState
)
1195 if (pidRuntime
.acroTrainerActive
!= newState
) {
1197 pidAcroTrainerInit();
1199 pidRuntime
.acroTrainerActive
= newState
;
1202 #endif // USE_ACRO_TRAINER
1204 void pidSetAntiGravityState(bool newState
)
1206 if (newState
!= pidRuntime
.antiGravityEnabled
) {
1207 // reset the accelerator on state changes
1208 pidRuntime
.itermAccelerator
= 0.0f
;
1210 pidRuntime
.antiGravityEnabled
= newState
;
1213 bool pidAntiGravityEnabled(void)
1215 return pidRuntime
.antiGravityEnabled
;
1219 void dynLpfDTermUpdate(float throttle
)
1221 if (pidRuntime
.dynLpfFilter
!= DYN_LPF_NONE
) {
1223 if (pidRuntime
.dynLpfCurveExpo
> 0) {
1224 cutoffFreq
= dynLpfCutoffFreq(throttle
, pidRuntime
.dynLpfMin
, pidRuntime
.dynLpfMax
, pidRuntime
.dynLpfCurveExpo
);
1226 cutoffFreq
= fmaxf(dynThrottle(throttle
) * pidRuntime
.dynLpfMax
, pidRuntime
.dynLpfMin
);
1229 switch (pidRuntime
.dynLpfFilter
) {
1231 for (int axis
= 0; axis
< XYZ_AXIS_COUNT
; axis
++) {
1232 pt1FilterUpdateCutoff(&pidRuntime
.dtermLowpass
[axis
].pt1Filter
, pt1FilterGain(cutoffFreq
, pidRuntime
.dT
));
1235 case DYN_LPF_BIQUAD
:
1236 for (int axis
= 0; axis
< XYZ_AXIS_COUNT
; axis
++) {
1237 biquadFilterUpdateLPF(&pidRuntime
.dtermLowpass
[axis
].biquadFilter
, cutoffFreq
, targetPidLooptime
);
1241 for (int axis
= 0; axis
< XYZ_AXIS_COUNT
; axis
++) {
1242 pt2FilterUpdateCutoff(&pidRuntime
.dtermLowpass
[axis
].pt2Filter
, pt2FilterGain(cutoffFreq
, pidRuntime
.dT
));
1246 for (int axis
= 0; axis
< XYZ_AXIS_COUNT
; axis
++) {
1247 pt3FilterUpdateCutoff(&pidRuntime
.dtermLowpass
[axis
].pt3Filter
, pt3FilterGain(cutoffFreq
, pidRuntime
.dT
));
1255 float dynLpfCutoffFreq(float throttle
, uint16_t dynLpfMin
, uint16_t dynLpfMax
, uint8_t expo
)
1257 const float expof
= expo
/ 10.0f
;
1258 const float curve
= throttle
* (1 - throttle
) * expof
+ throttle
;
1259 return (dynLpfMax
- dynLpfMin
) * curve
+ dynLpfMin
;
1262 void pidSetItermReset(bool enabled
)
1264 pidRuntime
.zeroThrottleItermReset
= enabled
;
1267 float pidGetPreviousSetpoint(int axis
)
1269 return pidRuntime
.previousPidSetpoint
[axis
];
1274 return pidRuntime
.dT
;
1277 float pidGetPidFrequency()
1279 return pidRuntime
.pidFrequency
;