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);
93 #define PID_PROCESS_DENOM_DEFAULT 8
94 #elif defined(STM32F3)
95 #define PID_PROCESS_DENOM_DEFAULT 4
96 #elif defined(STM32F411xE) || defined(STM32G4) //G4 sometimes cpu overflow when PID rate set to higher than 4k
97 #define PID_PROCESS_DENOM_DEFAULT 2
99 #define PID_PROCESS_DENOM_DEFAULT 1
102 #ifdef USE_RUNAWAY_TAKEOFF
103 PG_RESET_TEMPLATE(pidConfig_t
, pidConfig
,
104 .pid_process_denom
= PID_PROCESS_DENOM_DEFAULT
,
105 .runaway_takeoff_prevention
= true,
106 .runaway_takeoff_deactivate_throttle
= 20, // throttle level % needed to accumulate deactivation time
107 .runaway_takeoff_deactivate_delay
= 500 // Accumulated time (in milliseconds) before deactivation in successful takeoff
110 PG_RESET_TEMPLATE(pidConfig_t
, pidConfig
,
111 .pid_process_denom
= PID_PROCESS_DENOM_DEFAULT
115 #ifdef USE_ACRO_TRAINER
116 #define ACRO_TRAINER_LOOKAHEAD_RATE_LIMIT 500.0f // Max gyro rate for lookahead time scaling
117 #define ACRO_TRAINER_SETPOINT_LIMIT 1000.0f // Limit the correcting setpoint
118 #endif // USE_ACRO_TRAINER
120 #define CRASH_RECOVERY_DETECTION_DELAY_US 1000000 // 1 second delay before crash recovery detection is active after entering a self-level mode
122 #define LAUNCH_CONTROL_YAW_ITERM_LIMIT 50 // yaw iterm windup limit when launch mode is "FULL" (all axes)
124 PG_REGISTER_ARRAY_WITH_RESET_FN(pidProfile_t
, PID_PROFILE_COUNT
, pidProfiles
, PG_PID_PROFILE
, 3);
126 void resetPidProfile(pidProfile_t
*pidProfile
)
128 RESET_CONFIG(pidProfile_t
, pidProfile
,
130 [PID_ROLL
] = PID_ROLL_DEFAULT
,
131 [PID_PITCH
] = PID_PITCH_DEFAULT
,
132 [PID_YAW
] = PID_YAW_DEFAULT
,
133 [PID_LEVEL
] = { 50, 50, 75, 0 },
134 [PID_MAG
] = { 40, 0, 0, 0 },
136 .pidSumLimit
= PIDSUM_LIMIT
,
137 .pidSumLimitYaw
= PIDSUM_LIMIT_YAW
,
138 .yaw_lowpass_hz
= 100,
140 .dterm_notch_cutoff
= 0,
141 .itermWindupPointPercent
= 85,
142 .pidAtMinThrottle
= PID_STABILISATION_ON
,
143 .levelAngleLimit
= 55,
144 .feedforward_transition
= 0,
145 .yawRateAccelLimit
= 0,
147 .itermThrottleThreshold
= 250,
148 .itermAcceleratorGain
= 3500,
149 .crash_time
= 500, // ms
150 .crash_delay
= 0, // ms
151 .crash_recovery_angle
= 10, // degrees
152 .crash_recovery_rate
= 100, // degrees/second
153 .crash_dthreshold
= 50, // degrees/second/second
154 .crash_gthreshold
= 400, // degrees/second
155 .crash_setpoint_threshold
= 350, // degrees/second
156 .crash_recovery
= PID_CRASH_RECOVERY_OFF
, // off by default
157 .horizon_tilt_effect
= 75,
158 .horizon_tilt_expert_mode
= false,
159 .crash_limit_yaw
= 200,
162 .throttle_boost_cutoff
= 15,
163 .iterm_rotation
= false,
164 .iterm_relax
= ITERM_RELAX_RP
,
165 .iterm_relax_cutoff
= ITERM_RELAX_CUTOFF_DEFAULT
,
166 .iterm_relax_type
= ITERM_RELAX_SETPOINT
,
167 .acro_trainer_angle_limit
= 20,
168 .acro_trainer_lookahead_ms
= 50,
169 .acro_trainer_debug_axis
= FD_ROLL
,
170 .acro_trainer_gain
= 75,
171 .abs_control_gain
= 0,
172 .abs_control_limit
= 90,
173 .abs_control_error_limit
= 20,
174 .abs_control_cutoff
= 11,
175 .antiGravityMode
= ANTI_GRAVITY_SMOOTH
,
176 .dterm_lpf1_static_hz
= DTERM_LPF1_DYN_MIN_HZ_DEFAULT
,
177 // NOTE: dynamic lpf is enabled by default so this setting is actually
178 // overridden and the static lowpass 1 is disabled. We can't set this
179 // value to 0 otherwise Configurator versions 10.4 and earlier will also
180 // reset the lowpass filter type to PT1 overriding the desired BIQUAD setting.
181 .dterm_lpf2_static_hz
= DTERM_LPF2_HZ_DEFAULT
, // second Dterm LPF ON by default
182 .dterm_lpf1_type
= FILTER_PT1
,
183 .dterm_lpf2_type
= FILTER_PT1
,
184 .dterm_lpf1_dyn_min_hz
= DTERM_LPF1_DYN_MIN_HZ_DEFAULT
,
185 .dterm_lpf1_dyn_max_hz
= DTERM_LPF1_DYN_MAX_HZ_DEFAULT
,
186 .launchControlMode
= LAUNCH_CONTROL_MODE_NORMAL
,
187 .launchControlThrottlePercent
= 20,
188 .launchControlAngleLimit
= 0,
189 .launchControlGain
= 40,
190 .launchControlAllowTriggerReset
= true,
191 .use_integrated_yaw
= false,
192 .integrated_yaw_relax
= 200,
193 .thrustLinearization
= 0,
194 .d_min
= D_MIN_DEFAULT
,
197 .motor_output_limit
= 100,
198 .auto_profile_cell_count
= AUTO_PROFILE_CELL_COUNT_STAY
,
199 .transient_throttle_limit
= 0,
200 .profileName
= { 0 },
201 .dyn_idle_min_rpm
= 0,
202 .dyn_idle_p_gain
= 50,
203 .dyn_idle_i_gain
= 50,
204 .dyn_idle_d_gain
= 50,
205 .dyn_idle_max_increase
= 150,
206 .feedforward_averaging
= FEEDFORWARD_AVERAGING_OFF
,
207 .feedforward_max_rate_limit
= 90,
208 .feedforward_smooth_factor
= 25,
209 .feedforward_jitter_factor
= 7,
210 .feedforward_boost
= 15,
211 .dterm_lpf1_dyn_expo
= 5,
212 .level_race_mode
= false,
213 .vbat_sag_compensation
= 0,
214 .simplified_pids_mode
= PID_SIMPLIFIED_TUNING_RPY
,
215 .simplified_master_multiplier
= SIMPLIFIED_TUNING_DEFAULT
,
216 .simplified_roll_pitch_ratio
= SIMPLIFIED_TUNING_DEFAULT
,
217 .simplified_i_gain
= SIMPLIFIED_TUNING_DEFAULT
,
218 .simplified_d_gain
= SIMPLIFIED_TUNING_D_DEFAULT
,
219 .simplified_pi_gain
= SIMPLIFIED_TUNING_DEFAULT
,
220 .simplified_dmin_ratio
= SIMPLIFIED_TUNING_D_DEFAULT
,
221 .simplified_feedforward_gain
= SIMPLIFIED_TUNING_DEFAULT
,
222 .simplified_pitch_pi_gain
= SIMPLIFIED_TUNING_DEFAULT
,
223 .simplified_dterm_filter
= true,
224 .simplified_dterm_filter_multiplier
= SIMPLIFIED_TUNING_DEFAULT
,
228 pidProfile
->pid
[PID_ROLL
].D
= 30;
229 pidProfile
->pid
[PID_PITCH
].D
= 32;
233 void pgResetFn_pidProfiles(pidProfile_t
*pidProfiles
)
235 for (int i
= 0; i
< PID_PROFILE_COUNT
; i
++) {
236 resetPidProfile(&pidProfiles
[i
]);
240 // Scale factors to make best use of range with D_LPF debugging, aiming for max +/-16K as debug values are 16 bit
241 #define D_LPF_RAW_SCALE 25
242 #define D_LPF_FILT_SCALE 22
245 void pidSetItermAccelerator(float newItermAccelerator
)
247 pidRuntime
.itermAccelerator
= newItermAccelerator
;
250 bool pidOsdAntiGravityActive(void)
252 return (pidRuntime
.itermAccelerator
> pidRuntime
.antiGravityOsdCutoff
);
255 void pidStabilisationState(pidStabilisationState_e pidControllerState
)
257 pidRuntime
.pidStabilisationEnabled
= (pidControllerState
== PID_STABILISATION_ON
) ? true : false;
260 const angle_index_t rcAliasToAngleIndexMap
[] = { AI_ROLL
, AI_PITCH
};
262 #ifdef USE_FEEDFORWARD
263 float pidGetFeedforwardTransitionFactor()
265 return pidRuntime
.feedforwardTransitionFactor
;
268 float pidGetFeedforwardSmoothFactor()
270 return pidRuntime
.feedforwardSmoothFactor
;
273 float pidGetFeedforwardJitterFactor()
275 return pidRuntime
.feedforwardJitterFactor
;
278 float pidGetFeedforwardBoostFactor()
280 return pidRuntime
.feedforwardBoostFactor
;
284 void pidResetIterm(void)
286 for (int axis
= 0; axis
< 3; axis
++) {
287 pidData
[axis
].I
= 0.0f
;
288 #if defined(USE_ABSOLUTE_CONTROL)
289 axisError
[axis
] = 0.0f
;
294 void pidUpdateAntiGravityThrottleFilter(float throttle
)
296 if (pidRuntime
.antiGravityMode
== ANTI_GRAVITY_SMOOTH
) {
297 // calculate a boost factor for P in the same way as for I when throttle changes quickly
298 const float antiGravityThrottleLpf
= pt1FilterApply(&pidRuntime
.antiGravityThrottleLpf
, throttle
);
299 // focus P boost on low throttle range only
300 if (throttle
< 0.5f
) {
301 pidRuntime
.antiGravityPBoost
= 0.5f
- throttle
;
303 pidRuntime
.antiGravityPBoost
= 0.0f
;
305 // use lowpass to identify start of a throttle up, use this to reduce boost at start by half
306 if (antiGravityThrottleLpf
< throttle
) {
307 pidRuntime
.antiGravityPBoost
*= 0.5f
;
309 // high-passed throttle focuses boost on faster throttle changes
310 pidRuntime
.antiGravityThrottleHpf
= fabsf(throttle
- antiGravityThrottleLpf
);
311 pidRuntime
.antiGravityPBoost
= pidRuntime
.antiGravityPBoost
* pidRuntime
.antiGravityThrottleHpf
;
312 // smooth the P boost at 3hz to remove the jagged edges and prolong the effect after throttle stops
313 pidRuntime
.antiGravityPBoost
= pt1FilterApply(&pidRuntime
.antiGravitySmoothLpf
, pidRuntime
.antiGravityPBoost
);
317 #ifdef USE_ACRO_TRAINER
318 void pidAcroTrainerInit(void)
320 pidRuntime
.acroTrainerAxisState
[FD_ROLL
] = 0;
321 pidRuntime
.acroTrainerAxisState
[FD_PITCH
] = 0;
323 #endif // USE_ACRO_TRAINER
325 #ifdef USE_THRUST_LINEARIZATION
326 float pidCompensateThrustLinearization(float throttle
)
328 if (pidRuntime
.thrustLinearization
!= 0.0f
) {
329 // for whoops where a lot of TL is needed, allow more throttle boost
330 const float throttleReversed
= (1.0f
- throttle
);
331 throttle
/= 1.0f
+ pidRuntime
.throttleCompensateAmount
* powf(throttleReversed
, 2);
336 float pidApplyThrustLinearization(float motorOutput
)
338 if (pidRuntime
.thrustLinearization
!= 0.0f
) {
339 if (motorOutput
> 0.0f
) {
340 const float motorOutputReversed
= (1.0f
- motorOutput
);
341 motorOutput
*= 1.0f
+ powf(motorOutputReversed
, 2) * pidRuntime
.thrustLinearization
;
349 // calculate the stick deflection while applying level mode expo
350 static float getLevelModeRcDeflection(uint8_t axis
)
352 const float stickDeflection
= getRcDeflection(axis
);
354 const float expof
= currentControlRateProfile
->levelExpo
[axis
] / 100.0f
;
355 return power3(stickDeflection
) * expof
+ stickDeflection
* (1 - expof
);
357 return stickDeflection
;
361 // calculates strength of horizon leveling; 0 = none, 1.0 = most leveling
362 STATIC_UNIT_TESTED
float calcHorizonLevelStrength(void)
364 // start with 1.0 at center stick, 0.0 at max stick deflection:
365 float horizonLevelStrength
= 1.0f
- MAX(fabsf(getLevelModeRcDeflection(FD_ROLL
)), fabsf(getLevelModeRcDeflection(FD_PITCH
)));
367 // 0 at level, 90 at vertical, 180 at inverted (degrees):
368 const float currentInclination
= MAX(ABS(attitude
.values
.roll
), ABS(attitude
.values
.pitch
)) / 10.0f
;
370 // horizonTiltExpertMode: 0 = leveling always active when sticks centered,
371 // 1 = leveling can be totally off when inverted
372 if (pidRuntime
.horizonTiltExpertMode
) {
373 if (pidRuntime
.horizonTransition
> 0 && pidRuntime
.horizonCutoffDegrees
> 0) {
374 // if d_level > 0 and horizonTiltEffect < 175
375 // horizonCutoffDegrees: 0 to 125 => 270 to 90 (represents where leveling goes to zero)
376 // inclinationLevelRatio (0.0 to 1.0) is smaller (less leveling)
377 // for larger inclinations; 0.0 at horizonCutoffDegrees value:
378 const float inclinationLevelRatio
= constrainf((pidRuntime
.horizonCutoffDegrees
-currentInclination
) / pidRuntime
.horizonCutoffDegrees
, 0, 1);
379 // apply configured horizon sensitivity:
380 // when stick is near center (horizonLevelStrength ~= 1.0)
381 // H_sensitivity value has little effect,
382 // when stick is deflected (horizonLevelStrength near 0.0)
383 // H_sensitivity value has more effect:
384 horizonLevelStrength
= (horizonLevelStrength
- 1) * 100 / pidRuntime
.horizonTransition
+ 1;
385 // apply inclination ratio, which may lower leveling
386 // to zero regardless of stick position:
387 horizonLevelStrength
*= inclinationLevelRatio
;
388 } else { // d_level=0 or horizon_tilt_effect>=175 means no leveling
389 horizonLevelStrength
= 0;
391 } else { // horizon_tilt_expert_mode = 0 (leveling always active when sticks centered)
393 if (pidRuntime
.horizonFactorRatio
< 1.0f
) { // if horizonTiltEffect > 0
394 // horizonFactorRatio: 1.0 to 0.0 (larger means more leveling)
395 // inclinationLevelRatio (0.0 to 1.0) is smaller (less leveling)
396 // for larger inclinations, goes to 1.0 at inclination==level:
397 const float inclinationLevelRatio
= (180 - currentInclination
) / 180 * (1.0f
- pidRuntime
.horizonFactorRatio
) + pidRuntime
.horizonFactorRatio
;
398 // apply ratio to configured horizon sensitivity:
399 sensitFact
= pidRuntime
.horizonTransition
* inclinationLevelRatio
;
400 } else { // horizonTiltEffect=0 for "old" functionality
401 sensitFact
= pidRuntime
.horizonTransition
;
404 if (sensitFact
<= 0) { // zero means no leveling
405 horizonLevelStrength
= 0;
407 // when stick is near center (horizonLevelStrength ~= 1.0)
408 // sensitFact value has little effect,
409 // when stick is deflected (horizonLevelStrength near 0.0)
410 // sensitFact value has more effect:
411 horizonLevelStrength
= ((horizonLevelStrength
- 1) * (100 / sensitFact
)) + 1;
414 return constrainf(horizonLevelStrength
, 0, 1);
417 // Use the FAST_CODE_NOINLINE directive to avoid this code from being inlined into ITCM RAM to avoid overflow.
418 // The impact is possibly slightly slower performance on F7/H7 but they have more than enough
419 // processing power that it should be a non-issue.
420 STATIC_UNIT_TESTED FAST_CODE_NOINLINE
float pidLevel(int axis
, const pidProfile_t
*pidProfile
, const rollAndPitchTrims_t
*angleTrim
, float currentPidSetpoint
) {
421 // calculate error angle and limit the angle to the max inclination
422 // rcDeflection is in range [-1.0, 1.0]
423 float angle
= pidProfile
->levelAngleLimit
* getLevelModeRcDeflection(axis
);
424 #ifdef USE_GPS_RESCUE
425 angle
+= gpsRescueAngle
[axis
] / 100; // ANGLE IS IN CENTIDEGREES
427 angle
= constrainf(angle
, -pidProfile
->levelAngleLimit
, pidProfile
->levelAngleLimit
);
428 const float errorAngle
= angle
- ((attitude
.raw
[axis
] - angleTrim
->raw
[axis
]) / 10.0f
);
429 if (FLIGHT_MODE(ANGLE_MODE
) || FLIGHT_MODE(GPS_RESCUE_MODE
)) {
430 // ANGLE mode - control is angle based
431 currentPidSetpoint
= errorAngle
* pidRuntime
.levelGain
;
433 // HORIZON mode - mix of ANGLE and ACRO modes
434 // mix in errorAngle to currentPidSetpoint to add a little auto-level feel
435 const float horizonLevelStrength
= calcHorizonLevelStrength();
436 currentPidSetpoint
= currentPidSetpoint
+ (errorAngle
* pidRuntime
.horizonGain
* horizonLevelStrength
);
438 return currentPidSetpoint
;
441 static void handleCrashRecovery(
442 const pidCrashRecovery_e crash_recovery
, const rollAndPitchTrims_t
*angleTrim
,
443 const int axis
, const timeUs_t currentTimeUs
, const float gyroRate
, float *currentPidSetpoint
, float *errorRate
)
445 if (pidRuntime
.inCrashRecoveryMode
&& cmpTimeUs(currentTimeUs
, pidRuntime
.crashDetectedAtUs
) > pidRuntime
.crashTimeDelayUs
) {
446 if (crash_recovery
== PID_CRASH_RECOVERY_BEEP
) {
449 if (axis
== FD_YAW
) {
450 *errorRate
= constrainf(*errorRate
, -pidRuntime
.crashLimitYaw
, pidRuntime
.crashLimitYaw
);
452 // on roll and pitch axes calculate currentPidSetpoint and errorRate to level the aircraft to recover from crash
453 if (sensors(SENSOR_ACC
)) {
454 // errorAngle is deviation from horizontal
455 const float errorAngle
= -(attitude
.raw
[axis
] - angleTrim
->raw
[axis
]) / 10.0f
;
456 *currentPidSetpoint
= errorAngle
* pidRuntime
.levelGain
;
457 *errorRate
= *currentPidSetpoint
- gyroRate
;
460 // reset iterm, since accumulated error before crash is now meaningless
461 // and iterm windup during crash recovery can be extreme, especially on yaw axis
462 pidData
[axis
].I
= 0.0f
;
463 if (cmpTimeUs(currentTimeUs
, pidRuntime
.crashDetectedAtUs
) > pidRuntime
.crashTimeLimitUs
464 || (getMotorMixRange() < 1.0f
465 && fabsf(gyro
.gyroADCf
[FD_ROLL
]) < pidRuntime
.crashRecoveryRate
466 && fabsf(gyro
.gyroADCf
[FD_PITCH
]) < pidRuntime
.crashRecoveryRate
467 && fabsf(gyro
.gyroADCf
[FD_YAW
]) < pidRuntime
.crashRecoveryRate
)) {
468 if (sensors(SENSOR_ACC
)) {
469 // check aircraft nearly level
470 if (ABS(attitude
.raw
[FD_ROLL
] - angleTrim
->raw
[FD_ROLL
]) < pidRuntime
.crashRecoveryAngleDeciDegrees
471 && ABS(attitude
.raw
[FD_PITCH
] - angleTrim
->raw
[FD_PITCH
]) < pidRuntime
.crashRecoveryAngleDeciDegrees
) {
472 pidRuntime
.inCrashRecoveryMode
= false;
476 pidRuntime
.inCrashRecoveryMode
= false;
483 static void detectAndSetCrashRecovery(
484 const pidCrashRecovery_e crash_recovery
, const int axis
,
485 const timeUs_t currentTimeUs
, const float delta
, const float errorRate
)
487 // if crash recovery is on and accelerometer enabled and there is no gyro overflow, then check for a crash
488 // no point in trying to recover if the crash is so severe that the gyro overflows
489 if ((crash_recovery
|| FLIGHT_MODE(GPS_RESCUE_MODE
)) && !gyroOverflowDetected()) {
490 if (ARMING_FLAG(ARMED
)) {
491 if (getMotorMixRange() >= 1.0f
&& !pidRuntime
.inCrashRecoveryMode
492 && fabsf(delta
) > pidRuntime
.crashDtermThreshold
493 && fabsf(errorRate
) > pidRuntime
.crashGyroThreshold
494 && fabsf(getSetpointRate(axis
)) < pidRuntime
.crashSetpointThreshold
) {
495 if (crash_recovery
== PID_CRASH_RECOVERY_DISARM
) {
496 setArmingDisabled(ARMING_DISABLED_CRASH_DETECTED
);
497 disarm(DISARM_REASON_CRASH_PROTECTION
);
499 pidRuntime
.inCrashRecoveryMode
= true;
500 pidRuntime
.crashDetectedAtUs
= currentTimeUs
;
503 if (pidRuntime
.inCrashRecoveryMode
&& cmpTimeUs(currentTimeUs
, pidRuntime
.crashDetectedAtUs
) < pidRuntime
.crashTimeDelayUs
&& (fabsf(errorRate
) < pidRuntime
.crashGyroThreshold
504 || fabsf(getSetpointRate(axis
)) > pidRuntime
.crashSetpointThreshold
)) {
505 pidRuntime
.inCrashRecoveryMode
= false;
508 } else if (pidRuntime
.inCrashRecoveryMode
) {
509 pidRuntime
.inCrashRecoveryMode
= false;
516 #ifdef USE_ACRO_TRAINER
518 int acroTrainerSign(float x
)
520 return x
> 0 ? 1 : -1;
523 // Acro Trainer - Manipulate the setPoint to limit axis angle while in acro mode
524 // There are three states:
525 // 1. Current angle has exceeded limit
526 // Apply correction to return to limit (similar to pidLevel)
527 // 2. Future overflow has been projected based on current angle and gyro rate
528 // Manage the setPoint to control the gyro rate as the actual angle approaches the limit (try to prevent overshoot)
529 // 3. If no potential overflow is detected, then return the original setPoint
531 // Use the FAST_CODE_NOINLINE directive to avoid this code from being inlined into ITCM RAM. We accept the
532 // performance decrease when Acro Trainer mode is active under the assumption that user is unlikely to be
533 // expecting ultimate flight performance at very high loop rates when in this mode.
534 static FAST_CODE_NOINLINE
float applyAcroTrainer(int axis
, const rollAndPitchTrims_t
*angleTrim
, float setPoint
)
536 float ret
= setPoint
;
538 if (!FLIGHT_MODE(ANGLE_MODE
) && !FLIGHT_MODE(HORIZON_MODE
) && !FLIGHT_MODE(GPS_RESCUE_MODE
)) {
539 bool resetIterm
= false;
540 float projectedAngle
= 0;
541 const int setpointSign
= acroTrainerSign(setPoint
);
542 const float currentAngle
= (attitude
.raw
[axis
] - angleTrim
->raw
[axis
]) / 10.0f
;
543 const int angleSign
= acroTrainerSign(currentAngle
);
545 if ((pidRuntime
.acroTrainerAxisState
[axis
] != 0) && (pidRuntime
.acroTrainerAxisState
[axis
] != setpointSign
)) { // stick has reversed - stop limiting
546 pidRuntime
.acroTrainerAxisState
[axis
] = 0;
549 // Limit and correct the angle when it exceeds the limit
550 if ((fabsf(currentAngle
) > pidRuntime
.acroTrainerAngleLimit
) && (pidRuntime
.acroTrainerAxisState
[axis
] == 0)) {
551 if (angleSign
== setpointSign
) {
552 pidRuntime
.acroTrainerAxisState
[axis
] = angleSign
;
557 if (pidRuntime
.acroTrainerAxisState
[axis
] != 0) {
558 ret
= constrainf(((pidRuntime
.acroTrainerAngleLimit
* angleSign
) - currentAngle
) * pidRuntime
.acroTrainerGain
, -ACRO_TRAINER_SETPOINT_LIMIT
, ACRO_TRAINER_SETPOINT_LIMIT
);
561 // Not currently over the limit so project the angle based on current angle and
562 // gyro angular rate using a sliding window based on gyro rate (faster rotation means larger window.
563 // If the projected angle exceeds the limit then apply limiting to minimize overshoot.
564 // Calculate the lookahead window by scaling proportionally with gyro rate from 0-500dps
565 float checkInterval
= constrainf(fabsf(gyro
.gyroADCf
[axis
]) / ACRO_TRAINER_LOOKAHEAD_RATE_LIMIT
, 0.0f
, 1.0f
) * pidRuntime
.acroTrainerLookaheadTime
;
566 projectedAngle
= (gyro
.gyroADCf
[axis
] * checkInterval
) + currentAngle
;
567 const int projectedAngleSign
= acroTrainerSign(projectedAngle
);
568 if ((fabsf(projectedAngle
) > pidRuntime
.acroTrainerAngleLimit
) && (projectedAngleSign
== setpointSign
)) {
569 ret
= ((pidRuntime
.acroTrainerAngleLimit
* projectedAngleSign
) - projectedAngle
) * pidRuntime
.acroTrainerGain
;
578 if (axis
== pidRuntime
.acroTrainerDebugAxis
) {
579 DEBUG_SET(DEBUG_ACRO_TRAINER
, 0, lrintf(currentAngle
* 10.0f
));
580 DEBUG_SET(DEBUG_ACRO_TRAINER
, 1, pidRuntime
.acroTrainerAxisState
[axis
]);
581 DEBUG_SET(DEBUG_ACRO_TRAINER
, 2, lrintf(ret
));
582 DEBUG_SET(DEBUG_ACRO_TRAINER
, 3, lrintf(projectedAngle
* 10.0f
));
588 #endif // USE_ACRO_TRAINER
590 static float accelerationLimit(int axis
, float currentPidSetpoint
)
592 static float previousSetpoint
[XYZ_AXIS_COUNT
];
593 const float currentVelocity
= currentPidSetpoint
- previousSetpoint
[axis
];
595 if (fabsf(currentVelocity
) > pidRuntime
.maxVelocity
[axis
]) {
596 currentPidSetpoint
= (currentVelocity
> 0) ? previousSetpoint
[axis
] + pidRuntime
.maxVelocity
[axis
] : previousSetpoint
[axis
] - pidRuntime
.maxVelocity
[axis
];
599 previousSetpoint
[axis
] = currentPidSetpoint
;
600 return currentPidSetpoint
;
603 static void rotateVector(float v
[XYZ_AXIS_COUNT
], float rotation
[XYZ_AXIS_COUNT
])
605 // rotate v around rotation vector rotation
606 // rotation in radians, all elements must be small
607 for (int i
= 0; i
< XYZ_AXIS_COUNT
; i
++) {
608 int i_1
= (i
+ 1) % 3;
609 int i_2
= (i
+ 2) % 3;
610 float newV
= v
[i_1
] + v
[i_2
] * rotation
[i
];
611 v
[i_2
] -= v
[i_1
] * rotation
[i
];
616 STATIC_UNIT_TESTED
void rotateItermAndAxisError()
618 if (pidRuntime
.itermRotation
619 #if defined(USE_ABSOLUTE_CONTROL)
620 || pidRuntime
.acGain
> 0 || debugMode
== DEBUG_AC_ERROR
623 const float gyroToAngle
= pidRuntime
.dT
* RAD
;
624 float rotationRads
[XYZ_AXIS_COUNT
];
625 for (int i
= FD_ROLL
; i
<= FD_YAW
; i
++) {
626 rotationRads
[i
] = gyro
.gyroADCf
[i
] * gyroToAngle
;
628 #if defined(USE_ABSOLUTE_CONTROL)
629 if (pidRuntime
.acGain
> 0 || debugMode
== DEBUG_AC_ERROR
) {
630 rotateVector(axisError
, rotationRads
);
633 if (pidRuntime
.itermRotation
) {
634 float v
[XYZ_AXIS_COUNT
];
635 for (int i
= 0; i
< XYZ_AXIS_COUNT
; i
++) {
638 rotateVector(v
, rotationRads
);
639 for (int i
= 0; i
< XYZ_AXIS_COUNT
; i
++) {
646 #ifdef USE_RC_SMOOTHING_FILTER
647 float FAST_CODE
applyRcSmoothingFeedforwardFilter(int axis
, float pidSetpointDelta
)
649 float ret
= pidSetpointDelta
;
650 if (axis
== pidRuntime
.rcSmoothingDebugAxis
) {
651 DEBUG_SET(DEBUG_RC_SMOOTHING
, 1, lrintf(pidSetpointDelta
* 100.0f
));
653 if (pidRuntime
.feedforwardLpfInitialized
) {
654 ret
= pt3FilterApply(&pidRuntime
.feedforwardPt3
[axis
], pidSetpointDelta
);
655 if (axis
== pidRuntime
.rcSmoothingDebugAxis
) {
656 DEBUG_SET(DEBUG_RC_SMOOTHING
, 2, lrintf(ret
* 100.0f
));
661 #endif // USE_RC_SMOOTHING_FILTER
663 #if defined(USE_ITERM_RELAX)
664 #if defined(USE_ABSOLUTE_CONTROL)
665 STATIC_UNIT_TESTED
void applyAbsoluteControl(const int axis
, const float gyroRate
, float *currentPidSetpoint
, float *itermErrorRate
)
667 if (pidRuntime
.acGain
> 0 || debugMode
== DEBUG_AC_ERROR
) {
668 const float setpointLpf
= pt1FilterApply(&pidRuntime
.acLpf
[axis
], *currentPidSetpoint
);
669 const float setpointHpf
= fabsf(*currentPidSetpoint
- setpointLpf
);
670 float acErrorRate
= 0;
671 const float gmaxac
= setpointLpf
+ 2 * setpointHpf
;
672 const float gminac
= setpointLpf
- 2 * setpointHpf
;
673 if (gyroRate
>= gminac
&& gyroRate
<= gmaxac
) {
674 const float acErrorRate1
= gmaxac
- gyroRate
;
675 const float acErrorRate2
= gminac
- gyroRate
;
676 if (acErrorRate1
* axisError
[axis
] < 0) {
677 acErrorRate
= acErrorRate1
;
679 acErrorRate
= acErrorRate2
;
681 if (fabsf(acErrorRate
* pidRuntime
.dT
) > fabsf(axisError
[axis
]) ) {
682 acErrorRate
= -axisError
[axis
] * pidRuntime
.pidFrequency
;
685 acErrorRate
= (gyroRate
> gmaxac
? gmaxac
: gminac
) - gyroRate
;
688 if (isAirmodeActivated()) {
689 axisError
[axis
] = constrainf(axisError
[axis
] + acErrorRate
* pidRuntime
.dT
,
690 -pidRuntime
.acErrorLimit
, pidRuntime
.acErrorLimit
);
691 const float acCorrection
= constrainf(axisError
[axis
] * pidRuntime
.acGain
, -pidRuntime
.acLimit
, pidRuntime
.acLimit
);
692 *currentPidSetpoint
+= acCorrection
;
693 *itermErrorRate
+= acCorrection
;
694 DEBUG_SET(DEBUG_AC_CORRECTION
, axis
, lrintf(acCorrection
* 10));
695 if (axis
== FD_ROLL
) {
696 DEBUG_SET(DEBUG_ITERM_RELAX
, 3, lrintf(acCorrection
* 10));
699 DEBUG_SET(DEBUG_AC_ERROR
, axis
, lrintf(axisError
[axis
] * 10));
704 STATIC_UNIT_TESTED
void applyItermRelax(const int axis
, const float iterm
,
705 const float gyroRate
, float *itermErrorRate
, float *currentPidSetpoint
)
707 const float setpointLpf
= pt1FilterApply(&pidRuntime
.windupLpf
[axis
], *currentPidSetpoint
);
708 const float setpointHpf
= fabsf(*currentPidSetpoint
- setpointLpf
);
710 if (pidRuntime
.itermRelax
) {
711 if (axis
< FD_YAW
|| pidRuntime
.itermRelax
== ITERM_RELAX_RPY
|| pidRuntime
.itermRelax
== ITERM_RELAX_RPY_INC
) {
712 const float itermRelaxFactor
= MAX(0, 1 - setpointHpf
/ ITERM_RELAX_SETPOINT_THRESHOLD
);
713 const bool isDecreasingI
=
714 ((iterm
> 0) && (*itermErrorRate
< 0)) || ((iterm
< 0) && (*itermErrorRate
> 0));
715 if ((pidRuntime
.itermRelax
>= ITERM_RELAX_RP_INC
) && isDecreasingI
) {
716 // Do Nothing, use the precalculed itermErrorRate
717 } else if (pidRuntime
.itermRelaxType
== ITERM_RELAX_SETPOINT
) {
718 *itermErrorRate
*= itermRelaxFactor
;
719 } else if (pidRuntime
.itermRelaxType
== ITERM_RELAX_GYRO
) {
720 *itermErrorRate
= fapplyDeadband(setpointLpf
- gyroRate
, setpointHpf
);
722 *itermErrorRate
= 0.0f
;
725 if (axis
== FD_ROLL
) {
726 DEBUG_SET(DEBUG_ITERM_RELAX
, 0, lrintf(setpointHpf
));
727 DEBUG_SET(DEBUG_ITERM_RELAX
, 1, lrintf(itermRelaxFactor
* 100.0f
));
728 DEBUG_SET(DEBUG_ITERM_RELAX
, 2, lrintf(*itermErrorRate
));
732 #if defined(USE_ABSOLUTE_CONTROL)
733 applyAbsoluteControl(axis
, gyroRate
, currentPidSetpoint
, itermErrorRate
);
739 #ifdef USE_AIRMODE_LPF
740 void pidUpdateAirmodeLpf(float currentOffset
)
742 if (pidRuntime
.airmodeThrottleOffsetLimit
== 0.0f
) {
746 float offsetHpf
= currentOffset
* 2.5f
;
747 offsetHpf
= offsetHpf
- pt1FilterApply(&pidRuntime
.airmodeThrottleLpf2
, offsetHpf
);
749 // During high frequency oscillation 2 * currentOffset averages to the offset required to avoid mirroring of the waveform
750 pt1FilterApply(&pidRuntime
.airmodeThrottleLpf1
, offsetHpf
);
751 // Bring offset up immediately so the filter only applies to the decline
752 if (currentOffset
* pidRuntime
.airmodeThrottleLpf1
.state
>= 0 && fabsf(currentOffset
) > pidRuntime
.airmodeThrottleLpf1
.state
) {
753 pidRuntime
.airmodeThrottleLpf1
.state
= currentOffset
;
755 pidRuntime
.airmodeThrottleLpf1
.state
= constrainf(pidRuntime
.airmodeThrottleLpf1
.state
, -pidRuntime
.airmodeThrottleOffsetLimit
, pidRuntime
.airmodeThrottleOffsetLimit
);
758 float pidGetAirmodeThrottleOffset()
760 return pidRuntime
.airmodeThrottleLpf1
.state
;
764 #ifdef USE_LAUNCH_CONTROL
765 #define LAUNCH_CONTROL_MAX_RATE 100.0f
766 #define LAUNCH_CONTROL_MIN_RATE 5.0f
767 #define LAUNCH_CONTROL_ANGLE_WINDOW 10.0f // The remaining angle degrees where rate dampening starts
769 // Use the FAST_CODE_NOINLINE directive to avoid this code from being inlined into ITCM RAM to avoid overflow.
770 // The impact is possibly slightly slower performance on F7/H7 but they have more than enough
771 // processing power that it should be a non-issue.
772 static FAST_CODE_NOINLINE
float applyLaunchControl(int axis
, const rollAndPitchTrims_t
*angleTrim
)
776 // Scale the rates based on stick deflection only. Fixed rates with a max of 100deg/sec
777 // reached at 50% stick deflection. This keeps the launch control positioning consistent
778 // regardless of the user's rates.
779 if ((axis
== FD_PITCH
) || (pidRuntime
.launchControlMode
!= LAUNCH_CONTROL_MODE_PITCHONLY
)) {
780 const float stickDeflection
= constrainf(getRcDeflection(axis
), -0.5f
, 0.5f
);
781 ret
= LAUNCH_CONTROL_MAX_RATE
* stickDeflection
* 2;
785 // If ACC is enabled and a limit angle is set, then try to limit forward tilt
786 // to that angle and slow down the rate as the limit is approached to reduce overshoot
787 if ((axis
== FD_PITCH
) && (pidRuntime
.launchControlAngleLimit
> 0) && (ret
> 0)) {
788 const float currentAngle
= (attitude
.raw
[axis
] - angleTrim
->raw
[axis
]) / 10.0f
;
789 if (currentAngle
>= pidRuntime
.launchControlAngleLimit
) {
792 //for the last 10 degrees scale the rate from the current input to 5 dps
793 const float angleDelta
= pidRuntime
.launchControlAngleLimit
- currentAngle
;
794 if (angleDelta
<= LAUNCH_CONTROL_ANGLE_WINDOW
) {
795 ret
= scaleRangef(angleDelta
, 0, LAUNCH_CONTROL_ANGLE_WINDOW
, LAUNCH_CONTROL_MIN_RATE
, ret
);
807 // Betaflight pid controller, which will be maintained in the future with additional features specialised for current (mini) multirotor usage.
808 // Based on 2DOF reference design (matlab)
809 void FAST_CODE
pidController(const pidProfile_t
*pidProfile
, timeUs_t currentTimeUs
)
811 static float previousGyroRateDterm
[XYZ_AXIS_COUNT
];
812 static float previousRawGyroRateDterm
[XYZ_AXIS_COUNT
];
815 static timeUs_t levelModeStartTimeUs
= 0;
816 static bool gpsRescuePreviousState
= false;
819 const float tpaFactor
= getThrottlePIDAttenuation();
822 const rollAndPitchTrims_t
*angleTrim
= &accelerometerConfig()->accelerometerTrims
;
825 UNUSED(currentTimeUs
);
829 const float tpaFactorKp
= (currentControlRateProfile
->tpaMode
== TPA_MODE_PD
) ? tpaFactor
: 1.0f
;
831 const float tpaFactorKp
= tpaFactor
;
834 #ifdef USE_YAW_SPIN_RECOVERY
835 const bool yawSpinActive
= gyroYawSpinDetected();
838 const bool launchControlActive
= isLaunchControlActive();
841 const bool gpsRescueIsActive
= FLIGHT_MODE(GPS_RESCUE_MODE
);
842 levelMode_e levelMode
;
843 if (FLIGHT_MODE(ANGLE_MODE
) || FLIGHT_MODE(HORIZON_MODE
) || gpsRescueIsActive
) {
844 if (pidRuntime
.levelRaceMode
&& !gpsRescueIsActive
) {
845 levelMode
= LEVEL_MODE_R
;
847 levelMode
= LEVEL_MODE_RP
;
850 levelMode
= LEVEL_MODE_OFF
;
853 // Keep track of when we entered a self-level mode so that we can
854 // add a guard time before crash recovery can activate.
855 // Also reset the guard time whenever GPS Rescue is activated.
857 if ((levelModeStartTimeUs
== 0) || (gpsRescueIsActive
&& !gpsRescuePreviousState
)) {
858 levelModeStartTimeUs
= currentTimeUs
;
861 levelModeStartTimeUs
= 0;
863 gpsRescuePreviousState
= gpsRescueIsActive
;
866 // Dynamic i component,
867 if ((pidRuntime
.antiGravityMode
== ANTI_GRAVITY_SMOOTH
) && pidRuntime
.antiGravityEnabled
) {
868 // traditional itermAccelerator factor for iTerm
869 pidRuntime
.itermAccelerator
= pidRuntime
.antiGravityThrottleHpf
* 0.01f
* pidRuntime
.itermAcceleratorGain
;
870 DEBUG_SET(DEBUG_ANTI_GRAVITY
, 1, lrintf(pidRuntime
.itermAccelerator
* 1000));
871 // users AG Gain changes P boost
872 pidRuntime
.antiGravityPBoost
*= pidRuntime
.itermAcceleratorGain
;
873 // add some percentage of that slower, longer acting P boost factor to prolong AG effect on iTerm
874 pidRuntime
.itermAccelerator
+= pidRuntime
.antiGravityPBoost
* 0.05f
;
875 // set the final P boost amount
876 pidRuntime
.antiGravityPBoost
*= 0.02f
;
878 pidRuntime
.antiGravityPBoost
= 0.0f
;
880 DEBUG_SET(DEBUG_ANTI_GRAVITY
, 0, lrintf(pidRuntime
.itermAccelerator
* 1000));
882 float agGain
= pidRuntime
.dT
* pidRuntime
.itermAccelerator
* AG_KI
;
884 // gradually scale back integration when above windup point
885 float dynCi
= pidRuntime
.dT
;
886 if (pidRuntime
.itermWindupPointInv
> 1.0f
) {
887 dynCi
*= constrainf((1.0f
- getMotorMixRange()) * pidRuntime
.itermWindupPointInv
, 0.0f
, 1.0f
);
890 // Precalculate gyro deta for D-term here, this allows loop unrolling
891 float gyroRateDterm
[XYZ_AXIS_COUNT
];
892 for (int axis
= FD_ROLL
; axis
<= FD_YAW
; ++axis
) {
893 gyroRateDterm
[axis
] = gyro
.gyroADCf
[axis
];
894 // -----calculate raw, unfiltered D component
896 // Divide rate change by dT to get differential (ie dr/dt).
897 // dT is fixed and calculated from the target PID loop time
898 // This is done to avoid DTerm spikes that occur with dynamically
899 // calculated deltaT whenever another task causes the PID
900 // loop execution to be delayed.
902 - (gyroRateDterm
[axis
] - previousRawGyroRateDterm
[axis
]) * pidRuntime
.pidFrequency
/ D_LPF_RAW_SCALE
;
903 previousRawGyroRateDterm
[axis
] = gyroRateDterm
[axis
];
905 // Log the unfiltered D
906 if (axis
== FD_ROLL
) {
907 DEBUG_SET(DEBUG_D_LPF
, 0, lrintf(delta
));
908 } else if (axis
== FD_PITCH
) {
909 DEBUG_SET(DEBUG_D_LPF
, 1, lrintf(delta
));
912 gyroRateDterm
[axis
] = pidRuntime
.dtermNotchApplyFn((filter_t
*) &pidRuntime
.dtermNotch
[axis
], gyroRateDterm
[axis
]);
913 gyroRateDterm
[axis
] = pidRuntime
.dtermLowpassApplyFn((filter_t
*) &pidRuntime
.dtermLowpass
[axis
], gyroRateDterm
[axis
]);
914 gyroRateDterm
[axis
] = pidRuntime
.dtermLowpass2ApplyFn((filter_t
*) &pidRuntime
.dtermLowpass2
[axis
], gyroRateDterm
[axis
]);
917 rotateItermAndAxisError();
919 #ifdef USE_RPM_FILTER
923 #ifdef USE_FEEDFORWARD
924 bool newRcFrame
= false;
925 if (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
945 if (axis
== FD_PITCH
) {
951 if (axis
== FD_YAW
) {
954 currentPidSetpoint
= pidLevel(axis
, pidProfile
, angleTrim
, currentPidSetpoint
);
958 #ifdef USE_ACRO_TRAINER
959 if ((axis
!= FD_YAW
) && pidRuntime
.acroTrainerActive
&& !pidRuntime
.inCrashRecoveryMode
&& !launchControlActive
) {
960 currentPidSetpoint
= applyAcroTrainer(axis
, angleTrim
, currentPidSetpoint
);
962 #endif // USE_ACRO_TRAINER
964 #ifdef USE_LAUNCH_CONTROL
965 if (launchControlActive
) {
967 currentPidSetpoint
= applyLaunchControl(axis
, angleTrim
);
969 currentPidSetpoint
= applyLaunchControl(axis
, NULL
);
974 // Handle yaw spin recovery - zero the setpoint on yaw to aid in recovery
975 // It's not necessary to zero the set points for R/P because the PIDs will be zeroed below
976 #ifdef USE_YAW_SPIN_RECOVERY
977 if ((axis
== FD_YAW
) && yawSpinActive
) {
978 currentPidSetpoint
= 0.0f
;
980 #endif // USE_YAW_SPIN_RECOVERY
982 // -----calculate error rate
983 const float gyroRate
= gyro
.gyroADCf
[axis
]; // Process variable from gyro output in deg/sec
984 float errorRate
= currentPidSetpoint
- gyroRate
; // r - y
987 pidProfile
->crash_recovery
, angleTrim
, axis
, currentTimeUs
, gyroRate
,
988 ¤tPidSetpoint
, &errorRate
);
991 const float previousIterm
= pidData
[axis
].I
;
992 float itermErrorRate
= errorRate
;
993 #ifdef USE_ABSOLUTE_CONTROL
994 float uncorrectedSetpoint
= currentPidSetpoint
;
997 #if defined(USE_ITERM_RELAX)
998 if (!launchControlActive
&& !pidRuntime
.inCrashRecoveryMode
) {
999 applyItermRelax(axis
, previousIterm
, gyroRate
, &itermErrorRate
, ¤tPidSetpoint
);
1000 errorRate
= currentPidSetpoint
- gyroRate
;
1003 #ifdef USE_ABSOLUTE_CONTROL
1004 float setpointCorrection
= currentPidSetpoint
- uncorrectedSetpoint
;
1007 // --------low-level gyro-based PID based on 2DOF PID controller. ----------
1008 // 2-DOF PID controller with optional filter on derivative term.
1009 // b = 1 and only c (feedforward weight) can be tuned (amount derivative on measurement or error).
1011 // -----calculate P component
1012 pidData
[axis
].P
= pidRuntime
.pidCoefficient
[axis
].Kp
* errorRate
* tpaFactorKp
;
1013 if (axis
== FD_YAW
) {
1014 pidData
[axis
].P
= pidRuntime
.ptermYawLowpassApplyFn((filter_t
*) &pidRuntime
.ptermYawLowpass
, pidData
[axis
].P
);
1017 // -----calculate I component
1020 #ifdef USE_LAUNCH_CONTROL
1021 // if launch control is active override the iterm gains and apply iterm windup protection to all axes
1022 if (launchControlActive
) {
1023 Ki
= pidRuntime
.launchControlKi
;
1028 Ki
= pidRuntime
.pidCoefficient
[axis
].Ki
;
1029 axisDynCi
= (axis
== FD_YAW
) ? dynCi
: pidRuntime
.dT
; // only apply windup protection to yaw
1032 pidData
[axis
].I
= constrainf(previousIterm
+ (Ki
* axisDynCi
+ agGain
) * itermErrorRate
, -pidRuntime
.itermLimit
, pidRuntime
.itermLimit
);
1034 // -----calculate pidSetpointDelta
1035 float pidSetpointDelta
= 0;
1036 #ifdef USE_FEEDFORWARD
1037 pidSetpointDelta
= feedforwardApply(axis
, newRcFrame
, pidRuntime
.feedforwardAveraging
);
1039 pidRuntime
.previousPidSetpoint
[axis
] = currentPidSetpoint
;
1041 // -----calculate D component
1042 // disable D if launch control is active
1043 if ((pidRuntime
.pidCoefficient
[axis
].Kd
> 0) && !launchControlActive
) {
1045 // Divide rate change by dT to get differential (ie dr/dt).
1046 // dT is fixed and calculated from the target PID loop time
1047 // This is done to avoid DTerm spikes that occur with dynamically
1048 // calculated deltaT whenever another task causes the PID
1049 // loop execution to be delayed.
1051 - (gyroRateDterm
[axis
] - previousGyroRateDterm
[axis
]) * pidRuntime
.pidFrequency
;
1052 float preTpaD
= pidRuntime
.pidCoefficient
[axis
].Kd
* delta
;
1054 #if defined(USE_ACC)
1055 if (cmpTimeUs(currentTimeUs
, levelModeStartTimeUs
) > CRASH_RECOVERY_DETECTION_DELAY_US
) {
1056 detectAndSetCrashRecovery(pidProfile
->crash_recovery
, axis
, currentTimeUs
, delta
, errorRate
);
1060 #if defined(USE_D_MIN)
1061 float dMinFactor
= 1.0f
;
1062 if (pidRuntime
.dMinPercent
[axis
] > 0) {
1063 float dMinGyroFactor
= pt2FilterApply(&pidRuntime
.dMinRange
[axis
], delta
);
1064 dMinGyroFactor
= fabsf(dMinGyroFactor
) * pidRuntime
.dMinGyroGain
;
1065 const float dMinSetpointFactor
= (fabsf(pidSetpointDelta
)) * pidRuntime
.dMinSetpointGain
;
1066 dMinFactor
= MAX(dMinGyroFactor
, dMinSetpointFactor
);
1067 dMinFactor
= pidRuntime
.dMinPercent
[axis
] + (1.0f
- pidRuntime
.dMinPercent
[axis
]) * dMinFactor
;
1068 dMinFactor
= pt2FilterApply(&pidRuntime
.dMinLowpass
[axis
], dMinFactor
);
1069 dMinFactor
= MIN(dMinFactor
, 1.0f
);
1070 if (axis
== FD_ROLL
) {
1071 DEBUG_SET(DEBUG_D_MIN
, 0, lrintf(dMinGyroFactor
* 100));
1072 DEBUG_SET(DEBUG_D_MIN
, 1, lrintf(dMinSetpointFactor
* 100));
1073 DEBUG_SET(DEBUG_D_MIN
, 2, lrintf(pidRuntime
.pidCoefficient
[axis
].Kd
* dMinFactor
* 10 / DTERM_SCALE
));
1074 } else if (axis
== FD_PITCH
) {
1075 DEBUG_SET(DEBUG_D_MIN
, 3, lrintf(pidRuntime
.pidCoefficient
[axis
].Kd
* dMinFactor
* 10 / DTERM_SCALE
));
1079 // Apply the dMinFactor
1080 preTpaD
*= dMinFactor
;
1082 pidData
[axis
].D
= preTpaD
* tpaFactor
;
1084 // Log the value of D pre application of TPA
1085 preTpaD
*= D_LPF_FILT_SCALE
;
1087 if (axis
== FD_ROLL
) {
1088 DEBUG_SET(DEBUG_D_LPF
, 2, lrintf(preTpaD
));
1089 } else if (axis
== FD_PITCH
) {
1090 DEBUG_SET(DEBUG_D_LPF
, 3, lrintf(preTpaD
));
1093 pidData
[axis
].D
= 0;
1095 if (axis
== FD_ROLL
) {
1096 DEBUG_SET(DEBUG_D_LPF
, 2, 0);
1097 } else if (axis
== FD_PITCH
) {
1098 DEBUG_SET(DEBUG_D_LPF
, 3, 0);
1102 previousGyroRateDterm
[axis
] = gyroRateDterm
[axis
];
1104 // -----calculate feedforward component
1105 #ifdef USE_ABSOLUTE_CONTROL
1106 // include abs control correction in feedforward
1107 pidSetpointDelta
+= setpointCorrection
- pidRuntime
.oldSetpointCorrection
[axis
];
1108 pidRuntime
.oldSetpointCorrection
[axis
] = setpointCorrection
;
1111 // no feedforward in launch control
1112 float feedforwardGain
= launchControlActive
? 0.0f
: pidRuntime
.pidCoefficient
[axis
].Kf
;
1113 if (feedforwardGain
> 0) {
1114 // halve feedforward in Level mode since stick sensitivity is weaker by about half
1115 feedforwardGain
*= FLIGHT_MODE(ANGLE_MODE
) ? 0.5f
: 1.0f
;
1116 // transition now calculated in feedforward.c when new RC data arrives
1117 float feedForward
= feedforwardGain
* pidSetpointDelta
* pidRuntime
.pidFrequency
;
1119 #ifdef USE_FEEDFORWARD
1120 pidData
[axis
].F
= shouldApplyFeedforwardLimits(axis
) ?
1121 applyFeedforwardLimit(axis
, feedForward
, pidRuntime
.pidCoefficient
[axis
].Kp
, currentPidSetpoint
) : feedForward
;
1123 pidData
[axis
].F
= feedForward
;
1125 #ifdef USE_RC_SMOOTHING_FILTER
1126 pidData
[axis
].F
= applyRcSmoothingFeedforwardFilter(axis
, pidData
[axis
].F
);
1127 #endif // USE_RC_SMOOTHING_FILTER
1129 pidData
[axis
].F
= 0;
1132 #ifdef USE_YAW_SPIN_RECOVERY
1133 if (yawSpinActive
) {
1134 pidData
[axis
].I
= 0; // in yaw spin always disable I
1135 if (axis
<= FD_PITCH
) {
1136 // zero PIDs on pitch and roll leaving yaw P to correct spin
1137 pidData
[axis
].P
= 0;
1138 pidData
[axis
].D
= 0;
1139 pidData
[axis
].F
= 0;
1142 #endif // USE_YAW_SPIN_RECOVERY
1144 #ifdef USE_LAUNCH_CONTROL
1145 // Disable P/I appropriately based on the launch control mode
1146 if (launchControlActive
) {
1147 // if not using FULL mode then disable I accumulation on yaw as
1148 // yaw has a tendency to windup. Otherwise limit yaw iterm accumulation.
1149 const int launchControlYawItermLimit
= (pidRuntime
.launchControlMode
== LAUNCH_CONTROL_MODE_FULL
) ? LAUNCH_CONTROL_YAW_ITERM_LIMIT
: 0;
1150 pidData
[FD_YAW
].I
= constrainf(pidData
[FD_YAW
].I
, -launchControlYawItermLimit
, launchControlYawItermLimit
);
1152 // for pitch-only mode we disable everything except pitch P/I
1153 if (pidRuntime
.launchControlMode
== LAUNCH_CONTROL_MODE_PITCHONLY
) {
1154 pidData
[FD_ROLL
].P
= 0;
1155 pidData
[FD_ROLL
].I
= 0;
1156 pidData
[FD_YAW
].P
= 0;
1157 // don't let I go negative (pitch backwards) as front motors are limited in the mixer
1158 pidData
[FD_PITCH
].I
= MAX(0.0f
, pidData
[FD_PITCH
].I
);
1162 // calculating the PID sum
1164 // P boost at the end of throttle chop
1165 // attenuate effect if turning more than 50 deg/s, half at 100 deg/s
1166 float agBoostAttenuator
= fabsf(currentPidSetpoint
) / 50.0f
;
1167 agBoostAttenuator
= MAX(agBoostAttenuator
, 1.0f
);
1168 const float agBoost
= 1.0f
+ (pidRuntime
.antiGravityPBoost
/ agBoostAttenuator
);
1169 if (axis
!= FD_YAW
) {
1170 pidData
[axis
].P
*= agBoost
;
1171 DEBUG_SET(DEBUG_ANTI_GRAVITY
, axis
+ 2, lrintf(agBoost
* 1000));
1174 const float pidSum
= pidData
[axis
].P
+ pidData
[axis
].I
+ pidData
[axis
].D
+ pidData
[axis
].F
;
1175 #ifdef USE_INTEGRATED_YAW_CONTROL
1176 if (axis
== FD_YAW
&& pidRuntime
.useIntegratedYaw
) {
1177 pidData
[axis
].Sum
+= pidSum
* pidRuntime
.dT
* 100.0f
;
1178 pidData
[axis
].Sum
-= pidData
[axis
].Sum
* pidRuntime
.integratedYawRelax
/ 100000.0f
* pidRuntime
.dT
/ 0.000125f
;
1182 pidData
[axis
].Sum
= pidSum
;
1186 // Disable PID control if at zero throttle or if gyro overflow detected
1187 // This may look very innefficient, but it is done on purpose to always show real CPU usage as in flight
1188 if (!pidRuntime
.pidStabilisationEnabled
|| gyroOverflowDetected()) {
1189 for (int axis
= FD_ROLL
; axis
<= FD_YAW
; ++axis
) {
1190 pidData
[axis
].P
= 0;
1191 pidData
[axis
].I
= 0;
1192 pidData
[axis
].D
= 0;
1193 pidData
[axis
].F
= 0;
1195 pidData
[axis
].Sum
= 0;
1197 } else if (pidRuntime
.zeroThrottleItermReset
) {
1202 bool crashRecoveryModeActive(void)
1204 return pidRuntime
.inCrashRecoveryMode
;
1207 #ifdef USE_ACRO_TRAINER
1208 void pidSetAcroTrainerState(bool newState
)
1210 if (pidRuntime
.acroTrainerActive
!= newState
) {
1212 pidAcroTrainerInit();
1214 pidRuntime
.acroTrainerActive
= newState
;
1217 #endif // USE_ACRO_TRAINER
1219 void pidSetAntiGravityState(bool newState
)
1221 if (newState
!= pidRuntime
.antiGravityEnabled
) {
1222 // reset the accelerator on state changes
1223 pidRuntime
.itermAccelerator
= 0.0f
;
1225 pidRuntime
.antiGravityEnabled
= newState
;
1228 bool pidAntiGravityEnabled(void)
1230 return pidRuntime
.antiGravityEnabled
;
1234 void dynLpfDTermUpdate(float throttle
)
1236 if (pidRuntime
.dynLpfFilter
!= DYN_LPF_NONE
) {
1238 if (pidRuntime
.dynLpfCurveExpo
> 0) {
1239 cutoffFreq
= dynLpfCutoffFreq(throttle
, pidRuntime
.dynLpfMin
, pidRuntime
.dynLpfMax
, pidRuntime
.dynLpfCurveExpo
);
1241 cutoffFreq
= fmaxf(dynThrottle(throttle
) * pidRuntime
.dynLpfMax
, pidRuntime
.dynLpfMin
);
1244 switch (pidRuntime
.dynLpfFilter
) {
1246 for (int axis
= 0; axis
< XYZ_AXIS_COUNT
; axis
++) {
1247 pt1FilterUpdateCutoff(&pidRuntime
.dtermLowpass
[axis
].pt1Filter
, pt1FilterGain(cutoffFreq
, pidRuntime
.dT
));
1250 case DYN_LPF_BIQUAD
:
1251 for (int axis
= 0; axis
< XYZ_AXIS_COUNT
; axis
++) {
1252 biquadFilterUpdateLPF(&pidRuntime
.dtermLowpass
[axis
].biquadFilter
, cutoffFreq
, targetPidLooptime
);
1256 for (int axis
= 0; axis
< XYZ_AXIS_COUNT
; axis
++) {
1257 pt2FilterUpdateCutoff(&pidRuntime
.dtermLowpass
[axis
].pt2Filter
, pt2FilterGain(cutoffFreq
, pidRuntime
.dT
));
1261 for (int axis
= 0; axis
< XYZ_AXIS_COUNT
; axis
++) {
1262 pt3FilterUpdateCutoff(&pidRuntime
.dtermLowpass
[axis
].pt3Filter
, pt3FilterGain(cutoffFreq
, pidRuntime
.dT
));
1270 float dynLpfCutoffFreq(float throttle
, uint16_t dynLpfMin
, uint16_t dynLpfMax
, uint8_t expo
) {
1271 const float expof
= expo
/ 10.0f
;
1273 curve
= throttle
* (1 - throttle
) * expof
+ throttle
;
1274 return (dynLpfMax
- dynLpfMin
) * curve
+ dynLpfMin
;
1277 void pidSetItermReset(bool enabled
)
1279 pidRuntime
.zeroThrottleItermReset
= enabled
;
1282 float pidGetPreviousSetpoint(int axis
)
1284 return pidRuntime
.previousPidSetpoint
[axis
];
1289 return pidRuntime
.dT
;
1292 float pidGetPidFrequency()
1294 return pidRuntime
.pidFrequency
;