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/>.
29 #include "build/build_config.h"
30 #include "build/debug.h"
32 #include "common/axis.h"
33 #include "common/filter.h"
35 #include "config/config.h"
36 #include "config/config_reset.h"
37 #include "config/simplified_tuning.h"
39 #include "drivers/pwm_output.h"
40 #include "drivers/sound_beeper.h"
41 #include "drivers/time.h"
43 #include "fc/controlrate_profile.h"
46 #include "fc/rc_controls.h"
47 #include "fc/runtime_config.h"
49 #include "flight/alt_hold.h"
50 #include "flight/autopilot.h"
51 #include "flight/gps_rescue.h"
52 #include "flight/imu.h"
53 #include "flight/mixer.h"
54 #include "flight/rpm_filter.h"
59 #include "pg/pg_ids.h"
61 #include "sensors/acceleration.h"
62 #include "sensors/battery.h"
63 #include "sensors/gyro.h"
73 const char pidNames
[] =
80 FAST_DATA_ZERO_INIT
uint32_t targetPidLooptime
;
81 FAST_DATA_ZERO_INIT pidAxisData_t pidData
[XYZ_AXIS_COUNT
];
82 FAST_DATA_ZERO_INIT pidRuntime_t pidRuntime
;
84 #if defined(USE_ABSOLUTE_CONTROL)
85 STATIC_UNIT_TESTED FAST_DATA_ZERO_INIT
float axisError
[XYZ_AXIS_COUNT
];
88 #if defined(USE_THROTTLE_BOOST)
89 FAST_DATA_ZERO_INIT
float throttleBoost
;
90 pt1Filter_t throttleLpf
;
93 PG_REGISTER_WITH_RESET_TEMPLATE(pidConfig_t
, pidConfig
, PG_PID_CONFIG
, 4);
95 #ifndef DEFAULT_PID_PROCESS_DENOM
96 #define DEFAULT_PID_PROCESS_DENOM 1
99 #ifdef USE_RUNAWAY_TAKEOFF
100 PG_RESET_TEMPLATE(pidConfig_t
, pidConfig
,
101 .pid_process_denom
= DEFAULT_PID_PROCESS_DENOM
,
102 .runaway_takeoff_prevention
= true,
103 .runaway_takeoff_deactivate_throttle
= 20, // throttle level % needed to accumulate deactivation time
104 .runaway_takeoff_deactivate_delay
= 500, // Accumulated time (in milliseconds) before deactivation in successful takeoff
107 PG_RESET_TEMPLATE(pidConfig_t
, pidConfig
,
108 .pid_process_denom
= DEFAULT_PID_PROCESS_DENOM
,
112 #ifdef USE_ACRO_TRAINER
113 #define ACRO_TRAINER_LOOKAHEAD_RATE_LIMIT 500.0f // Max gyro rate for lookahead time scaling
114 #define ACRO_TRAINER_SETPOINT_LIMIT 1000.0f // Limit the correcting setpoint
115 #endif // USE_ACRO_TRAINER
117 #define CRASH_RECOVERY_DETECTION_DELAY_US 1000000 // 1 second delay before crash recovery detection is active after entering a self-level mode
119 #define LAUNCH_CONTROL_YAW_ITERM_LIMIT 50 // yaw iterm windup limit when launch mode is "FULL" (all axes)
122 #define IS_AXIS_IN_ANGLE_MODE(i) (pidRuntime.axisInAngleMode[(i)])
124 #define IS_AXIS_IN_ANGLE_MODE(i) false
127 PG_REGISTER_ARRAY_WITH_RESET_FN(pidProfile_t
, PID_PROFILE_COUNT
, pidProfiles
, PG_PID_PROFILE
, 11);
129 void resetPidProfile(pidProfile_t
*pidProfile
)
131 RESET_CONFIG(pidProfile_t
, pidProfile
,
133 [PID_ROLL
] = PID_ROLL_DEFAULT
,
134 [PID_PITCH
] = PID_PITCH_DEFAULT
,
135 [PID_YAW
] = PID_YAW_DEFAULT
,
136 [PID_LEVEL
] = { 50, 75, 75, 50, 0 },
137 [PID_MAG
] = { 40, 0, 0, 0, 0 },
139 .pidSumLimit
= PIDSUM_LIMIT
,
140 .pidSumLimitYaw
= PIDSUM_LIMIT_YAW
,
141 .yaw_lowpass_hz
= 100,
143 .dterm_notch_cutoff
= 0,
144 .itermWindup
= 80, // sets iTerm limit to this percentage below pidSumLimit
145 .pidAtMinThrottle
= PID_STABILISATION_ON
,
147 .feedforward_transition
= 0,
148 .yawRateAccelLimit
= 0,
150 .anti_gravity_gain
= 80,
151 .crash_time
= 500, // ms
152 .crash_delay
= 0, // ms
153 .crash_recovery_angle
= 10, // degrees
154 .crash_recovery_rate
= 100, // degrees/second
155 .crash_dthreshold
= 50, // degrees/second/second
156 .crash_gthreshold
= 400, // degrees/second
157 .crash_setpoint_threshold
= 350, // degrees/second
158 .crash_recovery
= PID_CRASH_RECOVERY_OFF
, // off by default
159 .horizon_limit_degrees
= 135,
160 .horizon_ignore_sticks
= false,
161 .crash_limit_yaw
= 200,
164 .throttle_boost_cutoff
= 15,
165 .iterm_rotation
= false,
166 .iterm_relax
= ITERM_RELAX_RP
,
167 .iterm_relax_cutoff
= ITERM_RELAX_CUTOFF_DEFAULT
,
168 .iterm_relax_type
= ITERM_RELAX_SETPOINT
,
169 .acro_trainer_angle_limit
= 20,
170 .acro_trainer_lookahead_ms
= 50,
171 .acro_trainer_debug_axis
= FD_ROLL
,
172 .acro_trainer_gain
= 75,
173 .abs_control_gain
= 0,
174 .abs_control_limit
= 90,
175 .abs_control_error_limit
= 20,
176 .abs_control_cutoff
= 11,
177 .dterm_lpf1_static_hz
= DTERM_LPF1_DYN_MIN_HZ_DEFAULT
,
178 // NOTE: dynamic lpf is enabled by default so this setting is actually
179 // overridden and the static lowpass 1 is disabled. We can't set this
180 // value to 0 otherwise Configurator versions 10.4 and earlier will also
181 // reset the lowpass filter type to PT1 overriding the desired BIQUAD setting.
182 .dterm_lpf2_static_hz
= DTERM_LPF2_HZ_DEFAULT
, // second Dterm LPF ON by default
183 .dterm_lpf1_type
= FILTER_PT1
,
184 .dterm_lpf2_type
= FILTER_PT1
,
185 .dterm_lpf1_dyn_min_hz
= DTERM_LPF1_DYN_MIN_HZ_DEFAULT
,
186 .dterm_lpf1_dyn_max_hz
= DTERM_LPF1_DYN_MAX_HZ_DEFAULT
,
187 .launchControlMode
= LAUNCH_CONTROL_MODE_PITCHONLY
,
188 .launchControlThrottlePercent
= 20,
189 .launchControlAngleLimit
= 0,
190 .launchControlGain
= 40,
191 .launchControlAllowTriggerReset
= true,
192 .use_integrated_yaw
= false,
193 .integrated_yaw_relax
= 200,
194 .thrustLinearization
= 0,
195 .d_max
= D_MAX_DEFAULT
,
198 .motor_output_limit
= 100,
199 .auto_profile_cell_count
= AUTO_PROFILE_CELL_COUNT_STAY
,
200 .transient_throttle_limit
= 0,
201 .profileName
= { 0 },
202 .dyn_idle_min_rpm
= 0,
203 .dyn_idle_p_gain
= 50,
204 .dyn_idle_i_gain
= 50,
205 .dyn_idle_d_gain
= 50,
206 .dyn_idle_max_increase
= 150,
207 .feedforward_averaging
= FEEDFORWARD_AVERAGING_OFF
,
208 .feedforward_max_rate_limit
= 90,
209 .feedforward_smooth_factor
= 25,
210 .feedforward_jitter_factor
= 7,
211 .feedforward_boost
= 15,
212 .dterm_lpf1_dyn_expo
= 5,
213 .level_race_mode
= false,
214 .vbat_sag_compensation
= 0,
215 .simplified_pids_mode
= PID_SIMPLIFIED_TUNING_RPY
,
216 .simplified_master_multiplier
= SIMPLIFIED_TUNING_DEFAULT
,
217 .simplified_roll_pitch_ratio
= SIMPLIFIED_TUNING_DEFAULT
,
218 .simplified_i_gain
= SIMPLIFIED_TUNING_DEFAULT
,
219 .simplified_d_gain
= SIMPLIFIED_TUNING_D_DEFAULT
,
220 .simplified_pi_gain
= SIMPLIFIED_TUNING_DEFAULT
,
221 .simplified_d_max_gain
= SIMPLIFIED_TUNING_D_DEFAULT
,
222 .simplified_feedforward_gain
= SIMPLIFIED_TUNING_DEFAULT
,
223 .simplified_pitch_pi_gain
= SIMPLIFIED_TUNING_DEFAULT
,
224 .simplified_dterm_filter
= true,
225 .simplified_dterm_filter_multiplier
= SIMPLIFIED_TUNING_DEFAULT
,
226 .anti_gravity_cutoff_hz
= 5,
227 .anti_gravity_p_gain
= 100,
228 .tpa_mode
= TPA_MODE_D
,
230 .tpa_breakpoint
= 1350,
231 .angle_feedforward_smoothing_ms
= 80,
232 .angle_earth_ref
= 100,
233 .horizon_delay_ms
= 500, // 500ms time constant on any increase in horizon strength
235 .tpa_low_breakpoint
= 1050,
237 .ez_landing_threshold
= 25,
238 .ez_landing_limit
= 15,
239 .ez_landing_speed
= 50,
240 .spa_center
= { 0, 0, 0 },
241 .spa_width
= { 0, 0, 0 },
242 .spa_mode
= { 0, 0, 0 },
243 .landing_disarm_threshold
= 0, // relatively safe values are around 100
244 .feedforward_yaw_hold_gain
= 15, // zero disables; 15-20 is OK for 5in
245 .feedforward_yaw_hold_time
= 100, // a value of 100 is a time constant of about 100ms, and is OK for a 5in; smaller values decay faster, eg for smaller props
246 .tpa_curve_type
= TPA_CURVE_CLASSIC
,
247 .tpa_curve_stall_throttle
= 30,
248 .tpa_curve_pid_thr0
= 200,
249 .tpa_curve_pid_thr100
= 70,
250 .tpa_curve_expo
= 20,
251 .tpa_speed_type
= TPA_SPEED_BASIC
,
252 .tpa_speed_basic_delay
= 1000,
253 .tpa_speed_basic_gravity
= 50,
254 .tpa_speed_adv_prop_pitch
= 370,
255 .tpa_speed_adv_mass
= 1000,
256 .tpa_speed_adv_drag_k
= 1000,
257 .tpa_speed_adv_thrust
= 2000,
258 .tpa_speed_max_voltage
= 2520,
259 .tpa_speed_pitch_offset
= 0,
260 .yaw_type
= YAW_TYPE_RUDDER
,
261 .angle_pitch_offset
= 0,
265 static bool isTpaActive(tpaMode_e tpaMode
, term_e term
) {
268 return term
== TERM_P
|| term
== TERM_D
;
270 return term
== TERM_D
;
273 return term
== TERM_P
|| term
== TERM_D
|| term
== TERM_S
;
280 void pgResetFn_pidProfiles(pidProfile_t
*pidProfiles
)
282 for (int i
= 0; i
< PID_PROFILE_COUNT
; i
++) {
283 resetPidProfile(&pidProfiles
[i
]);
287 // Scale factors to make best use of range with D_LPF debugging, aiming for max +/-16K as debug values are 16 bit
288 #define D_LPF_RAW_SCALE 25
289 #define D_LPF_PRE_TPA_SCALE 10
291 void pidSetItermAccelerator(float newItermAccelerator
)
293 pidRuntime
.itermAccelerator
= newItermAccelerator
;
296 bool pidOsdAntiGravityActive(void)
298 return (pidRuntime
.itermAccelerator
> pidRuntime
.antiGravityOsdCutoff
);
301 void pidStabilisationState(pidStabilisationState_e pidControllerState
)
303 pidRuntime
.pidStabilisationEnabled
= (pidControllerState
== PID_STABILISATION_ON
) ? true : false;
306 const angle_index_t rcAliasToAngleIndexMap
[] = { AI_ROLL
, AI_PITCH
};
308 void pidResetIterm(void)
310 for (int axis
= 0; axis
< 3; axis
++) {
311 pidData
[axis
].I
= 0.0f
;
312 #if defined(USE_ABSOLUTE_CONTROL)
313 axisError
[axis
] = 0.0f
;
319 static float calcWingThrottle(void)
321 float batteryThrottleFactor
= 1.0f
;
322 if (pidRuntime
.tpaSpeed
.maxVoltage
> 0.0f
) {
323 batteryThrottleFactor
= getBatteryVoltageLatest() / 100.0f
/ pidRuntime
.tpaSpeed
.maxVoltage
;
324 batteryThrottleFactor
= constrainf(batteryThrottleFactor
, 0.0f
, 1.0f
);
327 return getMotorOutputRms() * batteryThrottleFactor
;
330 static float calcWingAcceleration(float throttle
, float pitchAngleRadians
)
332 const tpaSpeedParams_t
*tpa
= &pidRuntime
.tpaSpeed
;
334 const float thrust
= (throttle
* throttle
- throttle
* tpa
->speed
* tpa
->inversePropMaxSpeed
) * tpa
->twr
* G_ACCELERATION
;
335 const float drag
= tpa
->speed
* tpa
->speed
* tpa
->dragMassRatio
;
336 const float gravity
= G_ACCELERATION
* sin_approx(pitchAngleRadians
);
338 return thrust
- drag
+ gravity
;
341 static float calcWingTpaArgument(void)
343 const float t
= calcWingThrottle();
344 const float pitchRadians
= DECIDEGREES_TO_RADIANS(attitude
.values
.pitch
);
345 const float rollRadians
= DECIDEGREES_TO_RADIANS(attitude
.values
.roll
);
347 DEBUG_SET(DEBUG_TPA
, 1, lrintf(attitude
.values
.roll
)); // decidegrees
348 DEBUG_SET(DEBUG_TPA
, 2, lrintf(attitude
.values
.pitch
)); // decidegrees
349 DEBUG_SET(DEBUG_TPA
, 3, lrintf(t
* 1000.0f
)); // calculated throttle in the range of 0 - 1000
351 // pitchRadians is always -90 to 90 degrees. The bigger the ABS(pitch) the less portion of pitchOffset is needed.
352 // If ABS(roll) > 90 degrees - flying inverted, then negative portion of pitchOffset is needed.
353 // If ABS(roll) ~ 90 degrees - flying sideways, no pitchOffset is applied.
354 const float correctedPitchAnge
= pitchRadians
+ cos_approx(pitchRadians
) * cos_approx(rollRadians
) * pidRuntime
.tpaSpeed
.pitchOffset
;
356 const float a
= calcWingAcceleration(t
, correctedPitchAnge
);
358 pidRuntime
.tpaSpeed
.speed
+= a
* pidRuntime
.dT
;
359 pidRuntime
.tpaSpeed
.speed
= MAX(0.0f
, pidRuntime
.tpaSpeed
.speed
);
360 const float tpaArgument
= constrainf(pidRuntime
.tpaSpeed
.speed
/ pidRuntime
.tpaSpeed
.maxSpeed
, 0.0f
, 1.0f
);
362 DEBUG_SET(DEBUG_TPA
, 4, lrintf(pidRuntime
.tpaSpeed
.speed
* 10.0f
));
363 DEBUG_SET(DEBUG_TPA
, 5, lrintf(tpaArgument
* 1000.0f
));
368 static void updateStermTpaFactor(int axis
, float tpaFactor
)
370 float tpaFactorSterm
= tpaFactor
;
371 if (pidRuntime
.tpaCurveType
== TPA_CURVE_HYPERBOLIC
) {
372 const float maxSterm
= tpaFactorSterm
* (float)currentPidProfile
->pid
[axis
].S
* S_TERM_SCALE
;
373 if (maxSterm
> 1.0f
) {
374 tpaFactorSterm
*= 1.0f
/ maxSterm
;
377 pidRuntime
.tpaFactorSterm
[axis
] = tpaFactorSterm
;
380 static void updateStermTpaFactors(void) {
381 for (int i
= 0; i
< XYZ_AXIS_COUNT
; i
++) {
382 float tpaFactor
= pidRuntime
.tpaFactor
;
383 if (i
== FD_YAW
&& currentPidProfile
->yaw_type
== YAW_TYPE_DIFF_THRUST
) {
384 tpaFactor
= pidRuntime
.tpaFactorYaw
;
386 updateStermTpaFactor(i
, tpaFactor
);
391 static float wingAdjustSetpoint(float currentPidSetpoint
, int axis
)
394 float adjustedSetpoint
= currentPidSetpoint
;
395 if (!IS_AXIS_IN_ANGLE_MODE(axis
)) {
396 const bool skipYaw
= axis
== FD_YAW
&& currentPidProfile
->yaw_type
== YAW_TYPE_DIFF_THRUST
;
397 if (pidRuntime
.tpaFactorSterm
[axis
] > 0.0f
&& pidRuntime
.tpaFactor
> 0.0f
&& !skipYaw
) {
398 adjustedSetpoint
= currentPidSetpoint
* pidRuntime
.tpaFactorSterm
[axis
] / pidRuntime
.tpaFactor
;
402 DEBUG_SET(DEBUG_WING_SETPOINT
, 2 * axis
, lrintf(currentPidSetpoint
));
403 DEBUG_SET(DEBUG_WING_SETPOINT
, 2 * axis
+ 1, lrintf(adjustedSetpoint
));
404 return adjustedSetpoint
;
407 return currentPidSetpoint
;
411 float getTpaFactorClassic(float tpaArgument
)
413 static bool isTpaLowFaded
= false;
414 bool isThrottlePastTpaLowBreakpoint
= (tpaArgument
>= pidRuntime
.tpaLowBreakpoint
|| pidRuntime
.tpaLowBreakpoint
<= 0.01f
);
415 float tpaRate
= 0.0f
;
416 if (isThrottlePastTpaLowBreakpoint
|| isTpaLowFaded
) {
417 tpaRate
= pidRuntime
.tpaMultiplier
* fmaxf(tpaArgument
- pidRuntime
.tpaBreakpoint
, 0.0f
);
418 if (!pidRuntime
.tpaLowAlways
&& !isTpaLowFaded
) {
419 isTpaLowFaded
= true;
422 tpaRate
= pidRuntime
.tpaLowMultiplier
* (pidRuntime
.tpaLowBreakpoint
- tpaArgument
);
425 return 1.0f
- tpaRate
;
428 void pidUpdateTpaFactor(float throttle
)
430 throttle
= constrainf(throttle
, 0.0f
, 1.0f
);
434 const float tpaArgument
= isFixedWing() ? calcWingTpaArgument() : throttle
;
436 const float tpaArgument
= throttle
;
439 #ifdef USE_ADVANCED_TPA
440 switch (pidRuntime
.tpaCurveType
) {
441 case TPA_CURVE_HYPERBOLIC
:
442 tpaFactor
= pwlInterpolate(&pidRuntime
.tpaCurvePwl
, tpaArgument
);
444 case TPA_CURVE_CLASSIC
:
446 tpaFactor
= getTpaFactorClassic(tpaArgument
);
449 tpaFactor
= getTpaFactorClassic(tpaArgument
);
452 DEBUG_SET(DEBUG_TPA
, 0, lrintf(tpaFactor
* 1000));
453 pidRuntime
.tpaFactor
= tpaFactor
;
456 switch (currentPidProfile
->yaw_type
) {
457 case YAW_TYPE_DIFF_THRUST
:
458 pidRuntime
.tpaFactorYaw
= getTpaFactorClassic(tpaArgument
);
460 case YAW_TYPE_RUDDER
:
462 pidRuntime
.tpaFactorYaw
= pidRuntime
.tpaFactor
;
465 updateStermTpaFactors();
469 void pidUpdateAntiGravityThrottleFilter(float throttle
)
471 static float previousThrottle
= 0.0f
;
472 const float throttleInv
= 1.0f
- throttle
;
473 float throttleDerivative
= fabsf(throttle
- previousThrottle
) * pidRuntime
.pidFrequency
;
474 DEBUG_SET(DEBUG_ANTI_GRAVITY
, 0, lrintf(throttleDerivative
* 100));
475 throttleDerivative
*= throttleInv
* throttleInv
;
476 // generally focus on the low throttle period
477 if (throttle
> previousThrottle
) {
478 throttleDerivative
*= throttleInv
* 0.5f
;
479 // when increasing throttle, focus even more on the low throttle range
481 previousThrottle
= throttle
;
482 throttleDerivative
= pt2FilterApply(&pidRuntime
.antiGravityLpf
, throttleDerivative
);
483 // lower cutoff suppresses peaks relative to troughs and prolongs the effects
484 // PT2 smoothing of throttle derivative.
485 // 6 is a typical value for the peak boost factor with default cutoff of 6Hz
486 DEBUG_SET(DEBUG_ANTI_GRAVITY
, 1, lrintf(throttleDerivative
* 100));
487 pidRuntime
.antiGravityThrottleD
= throttleDerivative
;
490 #ifdef USE_ACRO_TRAINER
491 void pidAcroTrainerInit(void)
493 pidRuntime
.acroTrainerAxisState
[FD_ROLL
] = 0;
494 pidRuntime
.acroTrainerAxisState
[FD_PITCH
] = 0;
496 #endif // USE_ACRO_TRAINER
498 #ifdef USE_THRUST_LINEARIZATION
499 float pidCompensateThrustLinearization(float throttle
)
501 if (pidRuntime
.thrustLinearization
!= 0.0f
) {
502 // for whoops where a lot of TL is needed, allow more throttle boost
503 const float throttleReversed
= (1.0f
- throttle
);
504 throttle
/= 1.0f
+ pidRuntime
.throttleCompensateAmount
* sq(throttleReversed
);
509 float pidApplyThrustLinearization(float motorOutput
)
511 motorOutput
*= 1.0f
+ pidRuntime
.thrustLinearization
* sq(1.0f
- motorOutput
);
517 // Calculate strength of horizon leveling; 0 = none, 1.0 = most leveling
518 STATIC_UNIT_TESTED FAST_CODE_NOINLINE
float calcHorizonLevelStrength(void)
520 const float currentInclination
= MAX(abs(attitude
.values
.roll
), abs(attitude
.values
.pitch
)) * 0.1f
;
521 // 0 when level, 90 when vertical, 180 when inverted (degrees):
522 float absMaxStickDeflection
= MAX(fabsf(getRcDeflection(FD_ROLL
)), fabsf(getRcDeflection(FD_PITCH
)));
523 // 0-1, smoothed if RC smoothing is enabled
525 float horizonLevelStrength
= MAX((pidRuntime
.horizonLimitDegrees
- currentInclination
) * pidRuntime
.horizonLimitDegreesInv
, 0.0f
);
526 // 1.0 when attitude is 'flat', 0 when angle is equal to, or greater than, horizonLimitDegrees
527 horizonLevelStrength
*= MAX((pidRuntime
.horizonLimitSticks
- absMaxStickDeflection
) * pidRuntime
.horizonLimitSticksInv
, pidRuntime
.horizonIgnoreSticks
);
528 // use the value of horizonIgnoreSticks to enable/disable this effect.
529 // value should be 1.0 at center stick, 0.0 at max stick deflection:
530 horizonLevelStrength
*= pidRuntime
.horizonGain
;
532 if (pidRuntime
.horizonDelayMs
) {
533 const float horizonLevelStrengthSmoothed
= pt1FilterApply(&pidRuntime
.horizonSmoothingPt1
, horizonLevelStrength
);
534 horizonLevelStrength
= MIN(horizonLevelStrength
, horizonLevelStrengthSmoothed
);
536 return horizonLevelStrength
;
537 // 1 means full levelling, 0 means none
540 // Use the FAST_CODE_NOINLINE directive to avoid this code from being inlined into ITCM RAM to avoid overflow.
541 // The impact is possibly slightly slower performance on F7/H7 but they have more than enough
542 // processing power that it should be a non-issue.
543 STATIC_UNIT_TESTED FAST_CODE_NOINLINE
float pidLevel(int axis
, const pidProfile_t
*pidProfile
, const rollAndPitchTrims_t
*angleTrim
,
544 float currentPidSetpoint
, float horizonLevelStrength
)
546 // Applies only to axes that are in Angle mode
547 // We now use Acro Rates, transformed into the range +/- 1, to provide setpoints
548 const float angleLimit
= pidProfile
->angle_limit
;
549 float angleFeedforward
= 0.0f
;
550 // if user changes rates profile, update the max setpoint for angle mode
551 const float maxSetpointRateInv
= 1.0f
/ getMaxRcRate(axis
);
553 #ifdef USE_FEEDFORWARD
554 angleFeedforward
= angleLimit
* getFeedforward(axis
) * pidRuntime
.angleFeedforwardGain
* maxSetpointRateInv
;
555 // angle feedforward must be heavily filtered, at the PID loop rate, with limited user control over time constant
556 // it MUST be very delayed to avoid early overshoot and being too aggressive
557 angleFeedforward
= pt3FilterApply(&pidRuntime
.angleFeedforwardPt3
[axis
], angleFeedforward
);
560 float angleTarget
= angleLimit
* currentPidSetpoint
* maxSetpointRateInv
;
561 // use acro rates for the angle target in both horizon and angle modes, converted to -1 to +1 range using maxRate
564 if (axis
== FD_PITCH
) {
565 angleTarget
+= (float)pidProfile
->angle_pitch_offset
/ 10.0f
;
569 #ifdef USE_GPS_RESCUE
570 angleTarget
+= gpsRescueAngle
[axis
] / 100.0f
; // Angle is in centidegrees, stepped on roll at 10Hz but not on pitch
572 const float currentAngle
= (attitude
.raw
[axis
] - angleTrim
->raw
[axis
]) / 10.0f
; // stepped at 500hz with some 4ms flat spots
573 const float errorAngle
= angleTarget
- currentAngle
;
574 float angleRate
= errorAngle
* pidRuntime
.angleGain
+ angleFeedforward
;
576 // minimise cross-axis wobble due to faster yaw responses than roll or pitch, and make co-ordinated yaw turns
577 // by compensating for the effect of yaw on roll while pitched, and on pitch while rolled
578 // earthRef code here takes about 76 cycles, if conditional on angleEarthRef it takes about 100. sin_approx costs most of those cycles.
579 float sinAngle
= sin_approx(DEGREES_TO_RADIANS(pidRuntime
.angleTarget
[axis
== FD_ROLL
? FD_PITCH
: FD_ROLL
]));
580 sinAngle
*= (axis
== FD_ROLL
) ? -1.0f
: 1.0f
; // must be negative for Roll
581 const float earthRefGain
= FLIGHT_MODE(GPS_RESCUE_MODE
| ALT_HOLD_MODE
) ? 1.0f
: pidRuntime
.angleEarthRef
;
582 angleRate
+= pidRuntime
.angleYawSetpoint
* sinAngle
* earthRefGain
;
583 pidRuntime
.angleTarget
[axis
] = angleTarget
; // set target for alternate axis to current axis, for use in preceding calculation
585 // smooth final angle rate output to clean up attitude signal steps (500hz), GPS steps (10 or 100hz), RC steps etc
586 // this filter runs at ATTITUDE_CUTOFF_HZ, currently 50hz, so GPS roll may be a bit steppy
587 angleRate
= pt3FilterApply(&pidRuntime
.attitudeFilter
[axis
], angleRate
);
589 if (FLIGHT_MODE(ANGLE_MODE
| GPS_RESCUE_MODE
)) {
590 currentPidSetpoint
= angleRate
;
592 // can only be HORIZON mode - crossfade Angle rate and Acro rate
593 currentPidSetpoint
= currentPidSetpoint
* (1.0f
- horizonLevelStrength
) + angleRate
* horizonLevelStrength
;
597 if (axis
== FD_ROLL
) {
598 DEBUG_SET(DEBUG_ANGLE_MODE
, 0, lrintf(angleTarget
* 10.0f
)); // target angle
599 DEBUG_SET(DEBUG_ANGLE_MODE
, 1, lrintf(errorAngle
* pidRuntime
.angleGain
* 10.0f
)); // un-smoothed error correction in degrees
600 DEBUG_SET(DEBUG_ANGLE_MODE
, 2, lrintf(angleFeedforward
* 10.0f
)); // feedforward amount in degrees
601 DEBUG_SET(DEBUG_ANGLE_MODE
, 3, lrintf(currentAngle
* 10.0f
)); // angle returned
603 DEBUG_SET(DEBUG_ANGLE_TARGET
, 0, lrintf(angleTarget
* 10.0f
));
604 DEBUG_SET(DEBUG_ANGLE_TARGET
, 1, lrintf(sinAngle
* 10.0f
)); // modification factor from earthRef
605 // debug ANGLE_TARGET 2 is yaw attenuation
606 DEBUG_SET(DEBUG_ANGLE_TARGET
, 3, lrintf(currentAngle
* 10.0f
)); // angle returned
609 DEBUG_SET(DEBUG_CURRENT_ANGLE
, axis
, lrintf(currentAngle
* 10.0f
)); // current angle
610 return currentPidSetpoint
;
613 static FAST_CODE_NOINLINE
void handleCrashRecovery(
614 const pidCrashRecovery_e crash_recovery
, const rollAndPitchTrims_t
*angleTrim
,
615 const int axis
, const timeUs_t currentTimeUs
, const float gyroRate
, float *currentPidSetpoint
, float *errorRate
)
617 if (pidRuntime
.inCrashRecoveryMode
&& cmpTimeUs(currentTimeUs
, pidRuntime
.crashDetectedAtUs
) > pidRuntime
.crashTimeDelayUs
) {
618 if (crash_recovery
== PID_CRASH_RECOVERY_BEEP
) {
621 if (axis
== FD_YAW
) {
622 *errorRate
= constrainf(*errorRate
, -pidRuntime
.crashLimitYaw
, pidRuntime
.crashLimitYaw
);
624 // on roll and pitch axes calculate currentPidSetpoint and errorRate to level the aircraft to recover from crash
625 if (sensors(SENSOR_ACC
)) {
626 // errorAngle is deviation from horizontal
627 const float errorAngle
= -(attitude
.raw
[axis
] - angleTrim
->raw
[axis
]) / 10.0f
;
628 *currentPidSetpoint
= errorAngle
* pidRuntime
.angleGain
;
629 *errorRate
= *currentPidSetpoint
- gyroRate
;
632 // reset iterm, since accumulated error before crash is now meaningless
633 // and iterm windup during crash recovery can be extreme, especially on yaw axis
634 pidData
[axis
].I
= 0.0f
;
635 if (cmpTimeUs(currentTimeUs
, pidRuntime
.crashDetectedAtUs
) > pidRuntime
.crashTimeLimitUs
636 || (getMotorMixRange() < 1.0f
637 && fabsf(gyro
.gyroADCf
[FD_ROLL
]) < pidRuntime
.crashRecoveryRate
638 && fabsf(gyro
.gyroADCf
[FD_PITCH
]) < pidRuntime
.crashRecoveryRate
639 && fabsf(gyro
.gyroADCf
[FD_YAW
]) < pidRuntime
.crashRecoveryRate
)) {
640 if (sensors(SENSOR_ACC
)) {
641 // check aircraft nearly level
642 if (abs(attitude
.raw
[FD_ROLL
] - angleTrim
->raw
[FD_ROLL
]) < pidRuntime
.crashRecoveryAngleDeciDegrees
643 && abs(attitude
.raw
[FD_PITCH
] - angleTrim
->raw
[FD_PITCH
]) < pidRuntime
.crashRecoveryAngleDeciDegrees
) {
644 pidRuntime
.inCrashRecoveryMode
= false;
648 pidRuntime
.inCrashRecoveryMode
= false;
655 static FAST_CODE_NOINLINE
void detectAndSetCrashRecovery(
656 const pidCrashRecovery_e crash_recovery
, const int axis
,
657 const timeUs_t currentTimeUs
, const float delta
, const float errorRate
)
659 // if crash recovery is on and accelerometer enabled and there is no gyro overflow, then check for a crash
660 // no point in trying to recover if the crash is so severe that the gyro overflows
661 if ((crash_recovery
|| FLIGHT_MODE(GPS_RESCUE_MODE
)) && !gyroOverflowDetected()) {
662 if (ARMING_FLAG(ARMED
)) {
663 if (getMotorMixRange() >= 1.0f
&& !pidRuntime
.inCrashRecoveryMode
664 && fabsf(delta
) > pidRuntime
.crashDtermThreshold
665 && fabsf(errorRate
) > pidRuntime
.crashGyroThreshold
666 && fabsf(getSetpointRate(axis
)) < pidRuntime
.crashSetpointThreshold
) {
667 if (crash_recovery
== PID_CRASH_RECOVERY_DISARM
) {
668 setArmingDisabled(ARMING_DISABLED_CRASH_DETECTED
);
669 disarm(DISARM_REASON_CRASH_PROTECTION
);
671 pidRuntime
.inCrashRecoveryMode
= true;
672 pidRuntime
.crashDetectedAtUs
= currentTimeUs
;
675 if (pidRuntime
.inCrashRecoveryMode
&& cmpTimeUs(currentTimeUs
, pidRuntime
.crashDetectedAtUs
) < pidRuntime
.crashTimeDelayUs
&& (fabsf(errorRate
) < pidRuntime
.crashGyroThreshold
676 || fabsf(getSetpointRate(axis
)) > pidRuntime
.crashSetpointThreshold
)) {
677 pidRuntime
.inCrashRecoveryMode
= false;
680 } else if (pidRuntime
.inCrashRecoveryMode
) {
681 pidRuntime
.inCrashRecoveryMode
= false;
688 #ifdef USE_ACRO_TRAINER
690 int acroTrainerSign(float x
)
692 return x
> 0 ? 1 : -1;
695 // Acro Trainer - Manipulate the setPoint to limit axis angle while in acro mode
696 // There are three states:
697 // 1. Current angle has exceeded limit
698 // Apply correction to return to limit (similar to pidLevel)
699 // 2. Future overflow has been projected based on current angle and gyro rate
700 // Manage the setPoint to control the gyro rate as the actual angle approaches the limit (try to prevent overshoot)
701 // 3. If no potential overflow is detected, then return the original setPoint
703 // Use the FAST_CODE_NOINLINE directive to avoid this code from being inlined into ITCM RAM. We accept the
704 // performance decrease when Acro Trainer mode is active under the assumption that user is unlikely to be
705 // expecting ultimate flight performance at very high loop rates when in this mode.
706 static FAST_CODE_NOINLINE
float applyAcroTrainer(int axis
, const rollAndPitchTrims_t
*angleTrim
, float setPoint
)
708 float ret
= setPoint
;
710 if (!FLIGHT_MODE(ANGLE_MODE
| HORIZON_MODE
| GPS_RESCUE_MODE
| ALT_HOLD_MODE
)) {
711 bool resetIterm
= false;
712 float projectedAngle
= 0;
713 const int setpointSign
= acroTrainerSign(setPoint
);
714 const float currentAngle
= (attitude
.raw
[axis
] - angleTrim
->raw
[axis
]) / 10.0f
;
715 const int angleSign
= acroTrainerSign(currentAngle
);
717 if ((pidRuntime
.acroTrainerAxisState
[axis
] != 0) && (pidRuntime
.acroTrainerAxisState
[axis
] != setpointSign
)) { // stick has reversed - stop limiting
718 pidRuntime
.acroTrainerAxisState
[axis
] = 0;
721 // Limit and correct the angle when it exceeds the limit
722 if ((fabsf(currentAngle
) > pidRuntime
.acroTrainerAngleLimit
) && (pidRuntime
.acroTrainerAxisState
[axis
] == 0)) {
723 if (angleSign
== setpointSign
) {
724 pidRuntime
.acroTrainerAxisState
[axis
] = angleSign
;
729 if (pidRuntime
.acroTrainerAxisState
[axis
] != 0) {
730 ret
= constrainf(((pidRuntime
.acroTrainerAngleLimit
* angleSign
) - currentAngle
) * pidRuntime
.acroTrainerGain
, -ACRO_TRAINER_SETPOINT_LIMIT
, ACRO_TRAINER_SETPOINT_LIMIT
);
733 // Not currently over the limit so project the angle based on current angle and
734 // gyro angular rate using a sliding window based on gyro rate (faster rotation means larger window.
735 // If the projected angle exceeds the limit then apply limiting to minimize overshoot.
736 // Calculate the lookahead window by scaling proportionally with gyro rate from 0-500dps
737 float checkInterval
= constrainf(fabsf(gyro
.gyroADCf
[axis
]) / ACRO_TRAINER_LOOKAHEAD_RATE_LIMIT
, 0.0f
, 1.0f
) * pidRuntime
.acroTrainerLookaheadTime
;
738 projectedAngle
= (gyro
.gyroADCf
[axis
] * checkInterval
) + currentAngle
;
739 const int projectedAngleSign
= acroTrainerSign(projectedAngle
);
740 if ((fabsf(projectedAngle
) > pidRuntime
.acroTrainerAngleLimit
) && (projectedAngleSign
== setpointSign
)) {
741 ret
= ((pidRuntime
.acroTrainerAngleLimit
* projectedAngleSign
) - projectedAngle
) * pidRuntime
.acroTrainerGain
;
750 if (axis
== pidRuntime
.acroTrainerDebugAxis
) {
751 DEBUG_SET(DEBUG_ACRO_TRAINER
, 0, lrintf(currentAngle
* 10.0f
));
752 DEBUG_SET(DEBUG_ACRO_TRAINER
, 1, pidRuntime
.acroTrainerAxisState
[axis
]);
753 DEBUG_SET(DEBUG_ACRO_TRAINER
, 2, lrintf(ret
));
754 DEBUG_SET(DEBUG_ACRO_TRAINER
, 3, lrintf(projectedAngle
* 10.0f
));
760 #endif // USE_ACRO_TRAINER
762 static float accelerationLimit(int axis
, float currentPidSetpoint
)
764 static float previousSetpoint
[XYZ_AXIS_COUNT
];
765 const float currentVelocity
= currentPidSetpoint
- previousSetpoint
[axis
];
767 if (fabsf(currentVelocity
) > pidRuntime
.maxVelocity
[axis
]) {
768 currentPidSetpoint
= (currentVelocity
> 0) ? previousSetpoint
[axis
] + pidRuntime
.maxVelocity
[axis
] : previousSetpoint
[axis
] - pidRuntime
.maxVelocity
[axis
];
771 previousSetpoint
[axis
] = currentPidSetpoint
;
772 return currentPidSetpoint
;
775 static void rotateVector(float v
[XYZ_AXIS_COUNT
], const float rotation
[XYZ_AXIS_COUNT
])
777 // rotate v around rotation vector rotation
778 // rotation in radians, all elements must be small
779 for (int i
= 0; i
< XYZ_AXIS_COUNT
; i
++) {
780 int i_1
= (i
+ 1) % 3;
781 int i_2
= (i
+ 2) % 3;
782 float newV
= v
[i_1
] + v
[i_2
] * rotation
[i
];
783 v
[i_2
] -= v
[i_1
] * rotation
[i
];
788 STATIC_UNIT_TESTED
void rotateItermAndAxisError(void)
790 if (pidRuntime
.itermRotation
791 #if defined(USE_ABSOLUTE_CONTROL)
792 || pidRuntime
.acGain
> 0 || debugMode
== DEBUG_AC_ERROR
795 const float gyroToAngle
= pidRuntime
.dT
* RAD
;
796 float rotationRads
[XYZ_AXIS_COUNT
];
797 for (int i
= FD_ROLL
; i
<= FD_YAW
; i
++) {
798 rotationRads
[i
] = gyro
.gyroADCf
[i
] * gyroToAngle
;
800 #if defined(USE_ABSOLUTE_CONTROL)
801 if (pidRuntime
.acGain
> 0 || debugMode
== DEBUG_AC_ERROR
) {
802 rotateVector(axisError
, rotationRads
);
805 if (pidRuntime
.itermRotation
) {
806 float v
[XYZ_AXIS_COUNT
];
807 for (int i
= 0; i
< XYZ_AXIS_COUNT
; i
++) {
810 rotateVector(v
, rotationRads
);
811 for (int i
= 0; i
< XYZ_AXIS_COUNT
; i
++) {
818 #if defined(USE_ITERM_RELAX)
819 #if defined(USE_ABSOLUTE_CONTROL)
820 STATIC_UNIT_TESTED
void applyAbsoluteControl(const int axis
, const float gyroRate
, float *currentPidSetpoint
, float *itermErrorRate
)
822 if (pidRuntime
.acGain
> 0 || debugMode
== DEBUG_AC_ERROR
) {
823 const float setpointLpf
= pt1FilterApply(&pidRuntime
.acLpf
[axis
], *currentPidSetpoint
);
824 const float setpointHpf
= fabsf(*currentPidSetpoint
- setpointLpf
);
825 float acErrorRate
= 0;
826 const float gmaxac
= setpointLpf
+ 2 * setpointHpf
;
827 const float gminac
= setpointLpf
- 2 * setpointHpf
;
828 if (gyroRate
>= gminac
&& gyroRate
<= gmaxac
) {
829 const float acErrorRate1
= gmaxac
- gyroRate
;
830 const float acErrorRate2
= gminac
- gyroRate
;
831 if (acErrorRate1
* axisError
[axis
] < 0) {
832 acErrorRate
= acErrorRate1
;
834 acErrorRate
= acErrorRate2
;
836 if (fabsf(acErrorRate
* pidRuntime
.dT
) > fabsf(axisError
[axis
]) ) {
837 acErrorRate
= -axisError
[axis
] * pidRuntime
.pidFrequency
;
840 acErrorRate
= (gyroRate
> gmaxac
? gmaxac
: gminac
) - gyroRate
;
843 if (wasThrottleRaised()) {
844 axisError
[axis
] = constrainf(axisError
[axis
] + acErrorRate
* pidRuntime
.dT
,
845 -pidRuntime
.acErrorLimit
, pidRuntime
.acErrorLimit
);
846 const float acCorrection
= constrainf(axisError
[axis
] * pidRuntime
.acGain
, -pidRuntime
.acLimit
, pidRuntime
.acLimit
);
847 *currentPidSetpoint
+= acCorrection
;
848 *itermErrorRate
+= acCorrection
;
849 DEBUG_SET(DEBUG_AC_CORRECTION
, axis
, lrintf(acCorrection
* 10));
850 if (axis
== FD_ROLL
) {
851 DEBUG_SET(DEBUG_ITERM_RELAX
, 3, lrintf(acCorrection
* 10));
854 DEBUG_SET(DEBUG_AC_ERROR
, axis
, lrintf(axisError
[axis
] * 10));
859 STATIC_UNIT_TESTED
void applyItermRelax(const int axis
, const float iterm
,
860 const float gyroRate
, float *itermErrorRate
, float *currentPidSetpoint
)
862 const float setpointLpf
= pt1FilterApply(&pidRuntime
.windupLpf
[axis
], *currentPidSetpoint
);
863 const float setpointHpf
= fabsf(*currentPidSetpoint
- setpointLpf
);
865 if (pidRuntime
.itermRelax
) {
866 if (axis
< FD_YAW
|| pidRuntime
.itermRelax
== ITERM_RELAX_RPY
|| pidRuntime
.itermRelax
== ITERM_RELAX_RPY_INC
) {
867 float itermRelaxThreshold
= ITERM_RELAX_SETPOINT_THRESHOLD
;
868 if (FLIGHT_MODE(ANGLE_MODE
)) {
869 itermRelaxThreshold
*= 0.2f
;
871 const float itermRelaxFactor
= MAX(0, 1 - setpointHpf
/ itermRelaxThreshold
);
872 const bool isDecreasingI
=
873 ((iterm
> 0) && (*itermErrorRate
< 0)) || ((iterm
< 0) && (*itermErrorRate
> 0));
874 if ((pidRuntime
.itermRelax
>= ITERM_RELAX_RP_INC
) && isDecreasingI
) {
875 // Do Nothing, use the precalculed itermErrorRate
876 } else if (pidRuntime
.itermRelaxType
== ITERM_RELAX_SETPOINT
) {
877 *itermErrorRate
*= itermRelaxFactor
;
878 } else if (pidRuntime
.itermRelaxType
== ITERM_RELAX_GYRO
) {
879 *itermErrorRate
= fapplyDeadband(setpointLpf
- gyroRate
, setpointHpf
);
881 *itermErrorRate
= 0.0f
;
884 if (axis
== FD_ROLL
) {
885 DEBUG_SET(DEBUG_ITERM_RELAX
, 0, lrintf(setpointHpf
));
886 DEBUG_SET(DEBUG_ITERM_RELAX
, 1, lrintf(itermRelaxFactor
* 100.0f
));
887 DEBUG_SET(DEBUG_ITERM_RELAX
, 2, lrintf(*itermErrorRate
));
891 #if defined(USE_ABSOLUTE_CONTROL)
892 applyAbsoluteControl(axis
, gyroRate
, currentPidSetpoint
, itermErrorRate
);
898 #ifdef USE_AIRMODE_LPF
899 void pidUpdateAirmodeLpf(float currentOffset
)
901 if (pidRuntime
.airmodeThrottleOffsetLimit
== 0.0f
) {
905 float offsetHpf
= currentOffset
* 2.5f
;
906 offsetHpf
= offsetHpf
- pt1FilterApply(&pidRuntime
.airmodeThrottleLpf2
, offsetHpf
);
908 // During high frequency oscillation 2 * currentOffset averages to the offset required to avoid mirroring of the waveform
909 pt1FilterApply(&pidRuntime
.airmodeThrottleLpf1
, offsetHpf
);
910 // Bring offset up immediately so the filter only applies to the decline
911 if (currentOffset
* pidRuntime
.airmodeThrottleLpf1
.state
>= 0 && fabsf(currentOffset
) > pidRuntime
.airmodeThrottleLpf1
.state
) {
912 pidRuntime
.airmodeThrottleLpf1
.state
= currentOffset
;
914 pidRuntime
.airmodeThrottleLpf1
.state
= constrainf(pidRuntime
.airmodeThrottleLpf1
.state
, -pidRuntime
.airmodeThrottleOffsetLimit
, pidRuntime
.airmodeThrottleOffsetLimit
);
917 float pidGetAirmodeThrottleOffset(void)
919 return pidRuntime
.airmodeThrottleLpf1
.state
;
923 static FAST_CODE_NOINLINE
void disarmOnImpact(void)
925 // if, being armed, and after takeoff...
926 if (wasThrottleRaised()
927 // and, either sticks are centred and throttle zeroed,
928 && ((getMaxRcDeflectionAbs() < 0.05f
&& mixerGetRcThrottle() < 0.05f
)
929 // we could test here for stage 2 failsafe (including both landing or GPS Rescue)
930 // this may permit removing the GPS Rescue disarm method altogether
931 #ifdef USE_ALT_HOLD_MODE
932 // or in altitude hold mode, including failsafe landing mode, indirectly
933 || FLIGHT_MODE(ALT_HOLD_MODE
)
936 // increase sensitivity by 50% when low and in altitude hold or failsafe landing
937 // for more reliable disarm with gentle controlled landings
938 float lowAltitudeSensitivity
= 1.0f
;
939 #ifdef USE_ALT_HOLD_MODE
940 lowAltitudeSensitivity
= (FLIGHT_MODE(ALT_HOLD_MODE
) && isBelowLandingAltitude()) ? 1.5f
: 1.0f
;
942 // and disarm if accelerometer jerk exceeds threshold...
943 if ((fabsf(acc
.accDelta
) * lowAltitudeSensitivity
) > pidRuntime
.landingDisarmThreshold
) {
945 setArmingDisabled(ARMING_DISABLED_ARM_SWITCH
); // NB: need a better message
946 disarm(DISARM_REASON_LANDING
);
947 // note: threshold should be high enough to avoid unwanted disarms in the air on throttle chops, eg around 10
950 DEBUG_SET(DEBUG_EZLANDING
, 6, lrintf(getMaxRcDeflectionAbs() * 100.0f
));
951 DEBUG_SET(DEBUG_EZLANDING
, 7, lrintf(acc
.accDelta
));
954 #ifdef USE_LAUNCH_CONTROL
955 #define LAUNCH_CONTROL_MAX_RATE 100.0f
956 #define LAUNCH_CONTROL_MIN_RATE 5.0f
957 #define LAUNCH_CONTROL_ANGLE_WINDOW 10.0f // The remaining angle degrees where rate dampening starts
959 // Use the FAST_CODE_NOINLINE directive to avoid this code from being inlined into ITCM RAM to avoid overflow.
960 // The impact is possibly slightly slower performance on F7/H7 but they have more than enough
961 // processing power that it should be a non-issue.
962 static FAST_CODE_NOINLINE
float applyLaunchControl(int axis
, const rollAndPitchTrims_t
*angleTrim
)
966 // Scale the rates based on stick deflection only. Fixed rates with a max of 100deg/sec
967 // reached at 50% stick deflection. This keeps the launch control positioning consistent
968 // regardless of the user's rates.
969 if ((axis
== FD_PITCH
) || (pidRuntime
.launchControlMode
!= LAUNCH_CONTROL_MODE_PITCHONLY
)) {
970 const float stickDeflection
= constrainf(getRcDeflection(axis
), -0.5f
, 0.5f
);
971 ret
= LAUNCH_CONTROL_MAX_RATE
* stickDeflection
* 2;
975 // If ACC is enabled and a limit angle is set, then try to limit forward tilt
976 // to that angle and slow down the rate as the limit is approached to reduce overshoot
977 if ((axis
== FD_PITCH
) && (pidRuntime
.launchControlAngleLimit
> 0) && (ret
> 0)) {
978 const float currentAngle
= (attitude
.raw
[axis
] - angleTrim
->raw
[axis
]) / 10.0f
;
979 if (currentAngle
>= pidRuntime
.launchControlAngleLimit
) {
982 //for the last 10 degrees scale the rate from the current input to 5 dps
983 const float angleDelta
= pidRuntime
.launchControlAngleLimit
- currentAngle
;
984 if (angleDelta
<= LAUNCH_CONTROL_ANGLE_WINDOW
) {
985 ret
= scaleRangef(angleDelta
, 0, LAUNCH_CONTROL_ANGLE_WINDOW
, LAUNCH_CONTROL_MIN_RATE
, ret
);
997 static float getTpaFactor(const pidProfile_t
*pidProfile
, int axis
, term_e term
)
999 float tpaFactor
= pidRuntime
.tpaFactor
;
1002 if (axis
== FD_YAW
) {
1003 tpaFactor
= pidRuntime
.tpaFactorYaw
;
1009 const bool tpaActive
= isTpaActive(pidProfile
->tpa_mode
, term
);
1012 return tpaActive
? tpaFactor
: 1.0f
;
1017 return tpaActive
? pidRuntime
.tpaFactorSterm
[axis
] : 1.0f
;
1024 static float getSterm(int axis
, const pidProfile_t
*pidProfile
, float setpoint
)
1027 float sTerm
= setpoint
/ getMaxRcRate(axis
) * 1000.0f
*
1028 (float)pidProfile
->pid
[axis
].S
* S_TERM_SCALE
;
1030 DEBUG_SET(DEBUG_S_TERM
, 2 * axis
, lrintf(sTerm
));
1031 sTerm
*= getTpaFactor(pidProfile
, axis
, TERM_S
);
1032 DEBUG_SET(DEBUG_S_TERM
, 2 * axis
+ 1, lrintf(sTerm
));
1043 NOINLINE
static void calculateSpaValues(const pidProfile_t
*pidProfile
)
1046 for (int axis
= 0; axis
< XYZ_AXIS_COUNT
; axis
++) {
1047 float currentRate
= getSetpointRate(axis
);
1048 pidRuntime
.spa
[axis
] = 1.0f
- smoothStepUpTransition(
1049 fabsf(currentRate
), pidProfile
->spa_center
[axis
], pidProfile
->spa_width
[axis
]);
1050 DEBUG_SET(DEBUG_SPA
, axis
, lrintf(pidRuntime
.spa
[axis
] * 1000));
1057 NOINLINE
static void applySpa(int axis
, const pidProfile_t
*pidProfile
)
1060 spaMode_e mode
= pidProfile
->spa_mode
[axis
];
1062 if (pidRuntime
.axisInAngleMode
[axis
]) {
1063 mode
= SPA_MODE_OFF
;
1068 pidData
[axis
].P
*= pidRuntime
.spa
[axis
];
1069 pidData
[axis
].D
*= pidRuntime
.spa
[axis
];
1070 pidData
[axis
].I
*= pidRuntime
.spa
[axis
];
1073 pidData
[axis
].I
*= pidRuntime
.spa
[axis
];
1075 case SPA_MODE_PD_I_FREEZE
:
1076 pidData
[axis
].P
*= pidRuntime
.spa
[axis
];
1077 pidData
[axis
].D
*= pidRuntime
.spa
[axis
];
1079 case SPA_MODE_I_FREEZE
:
1090 // Betaflight pid controller, which will be maintained in the future with additional features specialised for current (mini) multirotor usage.
1091 // Based on 2DOF reference design (matlab)
1092 void FAST_CODE
pidController(const pidProfile_t
*pidProfile
, timeUs_t currentTimeUs
)
1094 static float previousGyroRateDterm
[XYZ_AXIS_COUNT
];
1095 static float previousRawGyroRateDterm
[XYZ_AXIS_COUNT
];
1097 calculateSpaValues(pidProfile
);
1099 #ifdef USE_YAW_SPIN_RECOVERY
1100 const bool yawSpinActive
= gyroYawSpinDetected();
1103 const bool launchControlActive
= isLaunchControlActive();
1105 #if defined(USE_ACC)
1106 static timeUs_t levelModeStartTimeUs
= 0;
1107 static bool prevExternalAngleRequest
= false;
1108 const rollAndPitchTrims_t
*angleTrim
= &accelerometerConfig()->accelerometerTrims
;
1109 float horizonLevelStrength
= 0.0f
;
1111 const bool isExternalAngleModeRequest
= FLIGHT_MODE(GPS_RESCUE_MODE
)
1112 #ifdef USE_ALT_HOLD_MODE
1113 || FLIGHT_MODE(ALT_HOLD_MODE
)
1116 levelMode_e levelMode
;
1117 if (FLIGHT_MODE(ANGLE_MODE
| HORIZON_MODE
| GPS_RESCUE_MODE
)) {
1118 if (pidRuntime
.levelRaceMode
&& !isExternalAngleModeRequest
) {
1119 levelMode
= LEVEL_MODE_R
;
1121 levelMode
= LEVEL_MODE_RP
;
1124 // Keep track of when we entered a self-level mode so that we can
1125 // add a guard time before crash recovery can activate.
1126 // Also reset the guard time whenever GPS Rescue is activated.
1127 if ((levelModeStartTimeUs
== 0) || (isExternalAngleModeRequest
&& !prevExternalAngleRequest
)) {
1128 levelModeStartTimeUs
= currentTimeUs
;
1131 // Calc horizonLevelStrength if needed
1132 if (FLIGHT_MODE(HORIZON_MODE
)) {
1133 horizonLevelStrength
= calcHorizonLevelStrength();
1136 levelMode
= LEVEL_MODE_OFF
;
1137 levelModeStartTimeUs
= 0;
1140 prevExternalAngleRequest
= isExternalAngleModeRequest
;
1143 UNUSED(currentTimeUs
);
1147 if (pidRuntime
.antiGravityEnabled
) {
1148 pidRuntime
.antiGravityThrottleD
*= pidRuntime
.antiGravityGain
;
1149 // used later to increase pTerm
1150 pidRuntime
.itermAccelerator
= pidRuntime
.antiGravityThrottleD
* ANTIGRAVITY_KI
;
1152 pidRuntime
.antiGravityThrottleD
= 0.0f
;
1153 pidRuntime
.itermAccelerator
= 0.0f
;
1155 DEBUG_SET(DEBUG_ANTI_GRAVITY
, 2, lrintf((1 + (pidRuntime
.itermAccelerator
/ pidRuntime
.pidCoefficient
[FD_PITCH
].Ki
)) * 1000));
1156 // amount of antigravity added relative to user's pitch iTerm coefficient
1157 // used later to increase iTerm
1159 // Precalculate gyro delta for D-term here, this allows loop unrolling
1160 float gyroRateDterm
[XYZ_AXIS_COUNT
];
1161 for (int axis
= FD_ROLL
; axis
<= FD_YAW
; ++axis
) {
1162 gyroRateDterm
[axis
] = gyro
.gyroADCf
[axis
];
1164 // Log the unfiltered D for ROLL and PITCH
1165 if (debugMode
== DEBUG_D_LPF
&& axis
!= FD_YAW
) {
1166 const float delta
= (previousRawGyroRateDterm
[axis
] - gyroRateDterm
[axis
]) * pidRuntime
.pidFrequency
/ D_LPF_RAW_SCALE
;
1167 previousRawGyroRateDterm
[axis
] = gyroRateDterm
[axis
];
1168 DEBUG_SET(DEBUG_D_LPF
, axis
, lrintf(delta
)); // debug d_lpf 2 and 3 used for pre-TPA D
1171 gyroRateDterm
[axis
] = pidRuntime
.dtermNotchApplyFn((filter_t
*) &pidRuntime
.dtermNotch
[axis
], gyroRateDterm
[axis
]);
1172 gyroRateDterm
[axis
] = pidRuntime
.dtermLowpassApplyFn((filter_t
*) &pidRuntime
.dtermLowpass
[axis
], gyroRateDterm
[axis
]);
1173 gyroRateDterm
[axis
] = pidRuntime
.dtermLowpass2ApplyFn((filter_t
*) &pidRuntime
.dtermLowpass2
[axis
], gyroRateDterm
[axis
]);
1176 rotateItermAndAxisError();
1178 #ifdef USE_RPM_FILTER
1182 if (pidRuntime
.useEzDisarm
) {
1186 // ----------PID controller----------
1187 for (int axis
= FD_ROLL
; axis
<= FD_YAW
; ++axis
) {
1189 float currentPidSetpoint
= getSetpointRate(axis
);
1190 if (pidRuntime
.maxVelocity
[axis
]) {
1191 currentPidSetpoint
= accelerationLimit(axis
, currentPidSetpoint
);
1193 // Yaw control is GYRO based, direct sticks control is applied to rate PID
1194 // When Race Mode is active PITCH control is also GYRO based in level or horizon mode
1195 #if defined(USE_ACC)
1196 pidRuntime
.axisInAngleMode
[axis
] = false;
1197 if (axis
< FD_YAW
) {
1198 if (levelMode
== LEVEL_MODE_RP
|| (levelMode
== LEVEL_MODE_R
&& axis
== FD_ROLL
)) {
1199 pidRuntime
.axisInAngleMode
[axis
] = true;
1200 currentPidSetpoint
= pidLevel(axis
, pidProfile
, angleTrim
, currentPidSetpoint
, horizonLevelStrength
);
1202 } else { // yaw axis only
1203 if (levelMode
== LEVEL_MODE_RP
) {
1204 // if earth referencing is requested, attenuate yaw axis setpoint when pitched or rolled
1205 // and send yawSetpoint to Angle code to modulate pitch and roll
1206 // code cost is 107 cycles when earthRef enabled, 20 otherwise, nearly all in cos_approx
1207 const float earthRefGain
= FLIGHT_MODE(GPS_RESCUE_MODE
) ? 1.0f
: pidRuntime
.angleEarthRef
;
1209 pidRuntime
.angleYawSetpoint
= currentPidSetpoint
;
1210 float maxAngleTargetAbs
= earthRefGain
* fmaxf( fabsf(pidRuntime
.angleTarget
[FD_ROLL
]), fabsf(pidRuntime
.angleTarget
[FD_PITCH
]) );
1211 maxAngleTargetAbs
*= (FLIGHT_MODE(HORIZON_MODE
)) ? horizonLevelStrength
: 1.0f
;
1212 // reduce compensation whenever Horizon uses less levelling
1213 currentPidSetpoint
*= cos_approx(DEGREES_TO_RADIANS(maxAngleTargetAbs
));
1214 DEBUG_SET(DEBUG_ANGLE_TARGET
, 2, currentPidSetpoint
); // yaw setpoint after attenuation
1220 const float currentPidSetpointBeforeWingAdjust
= currentPidSetpoint
;
1221 currentPidSetpoint
= wingAdjustSetpoint(currentPidSetpoint
, axis
);
1223 #ifdef USE_ACRO_TRAINER
1224 if ((axis
!= FD_YAW
) && pidRuntime
.acroTrainerActive
&& !pidRuntime
.inCrashRecoveryMode
&& !launchControlActive
) {
1225 currentPidSetpoint
= applyAcroTrainer(axis
, angleTrim
, currentPidSetpoint
);
1227 #endif // USE_ACRO_TRAINER
1229 #ifdef USE_LAUNCH_CONTROL
1230 if (launchControlActive
) {
1231 #if defined(USE_ACC)
1232 currentPidSetpoint
= applyLaunchControl(axis
, angleTrim
);
1234 currentPidSetpoint
= applyLaunchControl(axis
, NULL
);
1239 // Handle yaw spin recovery - zero the setpoint on yaw to aid in recovery
1240 // It's not necessary to zero the set points for R/P because the PIDs will be zeroed below
1241 #ifdef USE_YAW_SPIN_RECOVERY
1242 if ((axis
== FD_YAW
) && yawSpinActive
) {
1243 currentPidSetpoint
= 0.0f
;
1245 #endif // USE_YAW_SPIN_RECOVERY
1247 // -----calculate error rate
1248 const float gyroRate
= gyro
.gyroADCf
[axis
]; // Process variable from gyro output in deg/sec
1249 float errorRate
= currentPidSetpoint
- gyroRate
; // r - y
1250 #if defined(USE_ACC)
1251 handleCrashRecovery(
1252 pidProfile
->crash_recovery
, angleTrim
, axis
, currentTimeUs
, gyroRate
,
1253 ¤tPidSetpoint
, &errorRate
);
1256 const float previousIterm
= pidData
[axis
].I
;
1257 float itermErrorRate
= errorRate
;
1259 #ifdef USE_ABSOLUTE_CONTROL
1260 const float uncorrectedSetpoint
= currentPidSetpoint
;
1263 #if defined(USE_ITERM_RELAX)
1264 if (!launchControlActive
&& !pidRuntime
.inCrashRecoveryMode
) {
1265 applyItermRelax(axis
, previousIterm
, gyroRate
, &itermErrorRate
, ¤tPidSetpoint
);
1266 errorRate
= currentPidSetpoint
- gyroRate
;
1269 #ifdef USE_ABSOLUTE_CONTROL
1270 const float setpointCorrection
= currentPidSetpoint
- uncorrectedSetpoint
;
1273 // --------low-level gyro-based PID based on 2DOF PID controller. ----------
1275 // -----calculate P component
1276 pidData
[axis
].P
= pidRuntime
.pidCoefficient
[axis
].Kp
* errorRate
* getTpaFactor(pidProfile
, axis
, TERM_P
);
1277 if (axis
== FD_YAW
) {
1278 pidData
[axis
].P
= pidRuntime
.ptermYawLowpassApplyFn((filter_t
*) &pidRuntime
.ptermYawLowpass
, pidData
[axis
].P
);
1281 // -----calculate I component
1282 float Ki
= pidRuntime
.pidCoefficient
[axis
].Ki
;
1283 float itermLimit
= pidRuntime
.itermLimit
; // windup fraction of pidSumLimit
1285 #ifdef USE_LAUNCH_CONTROL
1286 // if launch control is active override the iterm gains and apply iterm windup protection to all axes
1287 if (launchControlActive
) {
1288 Ki
= pidRuntime
.launchControlKi
;
1292 // yaw iTerm has it's own limit based on pidSumLimitYaw
1293 if (axis
== FD_YAW
) {
1294 itermLimit
= pidRuntime
.itermLimitYaw
; // windup fraction of pidSumLimitYaw
1295 // note that this is a stronger limit than previously
1296 pidRuntime
.itermAccelerator
= 0.0f
; // no antigravity on yaw iTerm
1300 float iTermChange
= (Ki
+ pidRuntime
.itermAccelerator
) * pidRuntime
.dT
* itermErrorRate
;
1302 if (pidProfile
->spa_mode
[axis
] != SPA_MODE_OFF
) {
1303 // slowing down I-term change, or even making it zero if setpoint is high enough
1304 iTermChange
*= pidRuntime
.spa
[axis
];
1308 pidData
[axis
].I
= constrainf(previousIterm
+ iTermChange
, -itermLimit
, itermLimit
);
1310 // -----calculate D component
1312 float pidSetpointDelta
= 0;
1314 #ifdef USE_FEEDFORWARD
1315 if (FLIGHT_MODE(ANGLE_MODE
) && pidRuntime
.axisInAngleMode
[axis
]) {
1316 // this axis is fully under self-levelling control
1317 // it will already have stick based feedforward applied in the input to their angle setpoint
1318 // a simple setpoint Delta can be used to for PID feedforward element for motor lag on these axes
1319 // however RC steps come in, via angle setpoint
1320 // and setpoint RC smoothing must have a cutoff half normal to remove those steps completely
1321 // the RC stepping does not come in via the feedforward, which is very well smoothed already
1322 // if uncommented, and the forcing to zero is removed, the two following lines will restore PID feedforward to angle mode axes
1323 // but for now let's see how we go without it (which was the case before 4.5 anyway)
1324 // pidSetpointDelta = currentPidSetpoint - pidRuntime.previousPidSetpoint[axis];
1325 // pidSetpointDelta *= pidRuntime.pidFrequency * pidRuntime.angleFeedforwardGain;
1326 pidSetpointDelta
= 0.0f
;
1328 // the axis is operating as a normal acro axis, so use normal feedforard from rc.c
1329 pidSetpointDelta
= getFeedforward(axis
);
1332 pidRuntime
.previousPidSetpoint
[axis
] = currentPidSetpoint
; // this is the value sent to blackbox, and used for D-max setpoint
1334 // disable D if launch control is active
1335 if ((pidRuntime
.pidCoefficient
[axis
].Kd
> 0) && !launchControlActive
) {
1336 // Divide rate change by dT to get differential (ie dr/dt).
1337 // dT is fixed and calculated from the target PID loop time
1338 // This is done to avoid DTerm spikes that occur with dynamically
1339 // calculated deltaT whenever another task causes the PID
1340 // loop execution to be delayed.
1341 const float delta
= - (gyroRateDterm
[axis
] - previousGyroRateDterm
[axis
]) * pidRuntime
.pidFrequency
;
1342 float preTpaD
= pidRuntime
.pidCoefficient
[axis
].Kd
* delta
;
1344 #if defined(USE_ACC)
1345 if (cmpTimeUs(currentTimeUs
, levelModeStartTimeUs
) > CRASH_RECOVERY_DETECTION_DELAY_US
) {
1346 detectAndSetCrashRecovery(pidProfile
->crash_recovery
, axis
, currentTimeUs
, delta
, errorRate
);
1351 float dMaxMultiplier
= 1.0f
;
1352 if (pidRuntime
.dMaxPercent
[axis
] > 1.0f
) {
1353 float dMaxGyroFactor
= pt2FilterApply(&pidRuntime
.dMaxRange
[axis
], delta
);
1354 dMaxGyroFactor
= fabsf(dMaxGyroFactor
) * pidRuntime
.dMaxGyroGain
;
1355 const float dMaxSetpointFactor
= fabsf(pidSetpointDelta
) * pidRuntime
.dMaxSetpointGain
;
1356 const float dMaxBoost
= fmaxf(dMaxGyroFactor
, dMaxSetpointFactor
);
1357 // dMaxBoost starts at zero, and by 1.0 we get Dmax, but it can exceed 1.
1358 dMaxMultiplier
+= (pidRuntime
.dMaxPercent
[axis
] - 1.0f
) * dMaxBoost
;
1359 dMaxMultiplier
= pt2FilterApply(&pidRuntime
.dMaxLowpass
[axis
], dMaxMultiplier
);
1360 // limit the gain to the fraction that DMax is greater than Min
1361 dMaxMultiplier
= MIN(dMaxMultiplier
, pidRuntime
.dMaxPercent
[axis
]);
1362 if (axis
== FD_ROLL
) {
1363 DEBUG_SET(DEBUG_D_MAX
, 0, lrintf(dMaxGyroFactor
* 100));
1364 DEBUG_SET(DEBUG_D_MAX
, 1, lrintf(dMaxSetpointFactor
* 100));
1365 DEBUG_SET(DEBUG_D_MAX
, 2, lrintf(pidRuntime
.pidCoefficient
[axis
].Kd
* dMaxMultiplier
* 10 / DTERM_SCALE
)); // actual D
1366 } else if (axis
== FD_PITCH
) {
1367 DEBUG_SET(DEBUG_D_MAX
, 3, lrintf(pidRuntime
.pidCoefficient
[axis
].Kd
* dMaxMultiplier
* 10 / DTERM_SCALE
));
1371 // Apply the gain that increases D towards Dmax
1372 preTpaD
*= dMaxMultiplier
;
1375 pidData
[axis
].D
= preTpaD
* getTpaFactor(pidProfile
, axis
, TERM_D
);
1377 // Log the value of D pre application of TPA
1378 if (axis
!= FD_YAW
) {
1379 DEBUG_SET(DEBUG_D_LPF
, axis
- FD_ROLL
+ 2, lrintf(preTpaD
* D_LPF_PRE_TPA_SCALE
));
1382 pidData
[axis
].D
= 0;
1383 if (axis
!= FD_YAW
) {
1384 DEBUG_SET(DEBUG_D_LPF
, axis
- FD_ROLL
+ 2, 0);
1388 previousGyroRateDterm
[axis
] = gyroRateDterm
[axis
];
1390 // -----calculate feedforward component
1392 #ifdef USE_ABSOLUTE_CONTROL
1393 // include abs control correction in feedforward
1394 pidSetpointDelta
+= setpointCorrection
- pidRuntime
.oldSetpointCorrection
[axis
];
1395 pidRuntime
.oldSetpointCorrection
[axis
] = setpointCorrection
;
1397 // no feedforward in launch control
1398 const float feedforwardGain
= launchControlActive
? 0.0f
: pidRuntime
.pidCoefficient
[axis
].Kf
;
1399 pidData
[axis
].F
= feedforwardGain
* pidSetpointDelta
;
1401 #ifdef USE_YAW_SPIN_RECOVERY
1402 if (yawSpinActive
) {
1403 pidData
[axis
].I
= 0; // in yaw spin always disable I
1404 if (axis
<= FD_PITCH
) {
1405 // zero PIDs on pitch and roll leaving yaw P to correct spin
1406 pidData
[axis
].P
= 0;
1407 pidData
[axis
].D
= 0;
1408 pidData
[axis
].F
= 0;
1409 pidData
[axis
].S
= 0;
1412 #endif // USE_YAW_SPIN_RECOVERY
1414 #ifdef USE_LAUNCH_CONTROL
1415 // Disable P/I appropriately based on the launch control mode
1416 if (launchControlActive
) {
1417 // if not using FULL mode then disable I accumulation on yaw as
1418 // yaw has a tendency to windup. Otherwise limit yaw iterm accumulation.
1419 const int launchControlYawItermLimit
= (pidRuntime
.launchControlMode
== LAUNCH_CONTROL_MODE_FULL
) ? LAUNCH_CONTROL_YAW_ITERM_LIMIT
: 0;
1420 pidData
[FD_YAW
].I
= constrainf(pidData
[FD_YAW
].I
, -launchControlYawItermLimit
, launchControlYawItermLimit
);
1422 // for pitch-only mode we disable everything except pitch P/I
1423 if (pidRuntime
.launchControlMode
== LAUNCH_CONTROL_MODE_PITCHONLY
) {
1424 pidData
[FD_ROLL
].P
= 0;
1425 pidData
[FD_ROLL
].I
= 0;
1426 pidData
[FD_YAW
].P
= 0;
1427 // don't let I go negative (pitch backwards) as front motors are limited in the mixer
1428 pidData
[FD_PITCH
].I
= MAX(0.0f
, pidData
[FD_PITCH
].I
);
1433 // Add P boost from antiGravity when sticks are close to zero
1434 if (axis
!= FD_YAW
) {
1435 float agSetpointAttenuator
= fabsf(currentPidSetpoint
) / 50.0f
;
1436 agSetpointAttenuator
= MAX(agSetpointAttenuator
, 1.0f
);
1437 // attenuate effect if turning more than 50 deg/s, half at 100 deg/s
1438 const float antiGravityPBoost
= 1.0f
+ (pidRuntime
.antiGravityThrottleD
/ agSetpointAttenuator
) * pidRuntime
.antiGravityPGain
;
1439 pidData
[axis
].P
*= antiGravityPBoost
;
1440 if (axis
== FD_PITCH
) {
1441 DEBUG_SET(DEBUG_ANTI_GRAVITY
, 3, lrintf(antiGravityPBoost
* 1000));
1445 pidData
[axis
].S
= getSterm(axis
, pidProfile
, currentPidSetpointBeforeWingAdjust
);
1446 applySpa(axis
, pidProfile
);
1448 // calculating the PID sum
1449 const float pidSum
= pidData
[axis
].P
+ pidData
[axis
].I
+ pidData
[axis
].D
+ pidData
[axis
].F
+ pidData
[axis
].S
;
1450 #ifdef USE_INTEGRATED_YAW_CONTROL
1451 if (axis
== FD_YAW
&& pidRuntime
.useIntegratedYaw
) {
1452 pidData
[axis
].Sum
+= pidSum
* pidRuntime
.dT
* 100.0f
;
1453 pidData
[axis
].Sum
-= pidData
[axis
].Sum
* pidRuntime
.integratedYawRelax
/ 100000.0f
* pidRuntime
.dT
/ 0.000125f
;
1457 pidData
[axis
].Sum
= pidSum
;
1461 // Disable PID control if at zero throttle or if gyro overflow detected
1462 // This may look very innefficient, but it is done on purpose to always show real CPU usage as in flight
1463 if (!pidRuntime
.pidStabilisationEnabled
|| gyroOverflowDetected()) {
1464 for (int axis
= FD_ROLL
; axis
<= FD_YAW
; ++axis
) {
1465 pidData
[axis
].P
= 0;
1466 pidData
[axis
].I
= 0;
1467 pidData
[axis
].D
= 0;
1468 pidData
[axis
].F
= 0;
1469 pidData
[axis
].S
= 0;
1471 pidData
[axis
].Sum
= 0;
1473 } else if (pidRuntime
.zeroThrottleItermReset
) {
1478 bool crashRecoveryModeActive(void)
1480 return pidRuntime
.inCrashRecoveryMode
;
1483 #ifdef USE_ACRO_TRAINER
1484 void pidSetAcroTrainerState(bool newState
)
1486 if (pidRuntime
.acroTrainerActive
!= newState
) {
1488 pidAcroTrainerInit();
1490 pidRuntime
.acroTrainerActive
= newState
;
1493 #endif // USE_ACRO_TRAINER
1495 void pidSetAntiGravityState(bool newState
)
1497 if (newState
!= pidRuntime
.antiGravityEnabled
) {
1498 // reset the accelerator on state changes
1499 pidRuntime
.itermAccelerator
= 0.0f
;
1501 pidRuntime
.antiGravityEnabled
= newState
;
1504 bool pidAntiGravityEnabled(void)
1506 return pidRuntime
.antiGravityEnabled
;
1510 void dynLpfDTermUpdate(float throttle
)
1512 if (pidRuntime
.dynLpfFilter
!= DYN_LPF_NONE
) {
1514 if (pidRuntime
.dynLpfCurveExpo
> 0) {
1515 cutoffFreq
= dynLpfCutoffFreq(throttle
, pidRuntime
.dynLpfMin
, pidRuntime
.dynLpfMax
, pidRuntime
.dynLpfCurveExpo
);
1517 cutoffFreq
= fmaxf(dynThrottle(throttle
) * pidRuntime
.dynLpfMax
, pidRuntime
.dynLpfMin
);
1520 switch (pidRuntime
.dynLpfFilter
) {
1522 for (int axis
= 0; axis
< XYZ_AXIS_COUNT
; axis
++) {
1523 pt1FilterUpdateCutoff(&pidRuntime
.dtermLowpass
[axis
].pt1Filter
, pt1FilterGain(cutoffFreq
, pidRuntime
.dT
));
1526 case DYN_LPF_BIQUAD
:
1527 for (int axis
= 0; axis
< XYZ_AXIS_COUNT
; axis
++) {
1528 biquadFilterUpdateLPF(&pidRuntime
.dtermLowpass
[axis
].biquadFilter
, cutoffFreq
, targetPidLooptime
);
1532 for (int axis
= 0; axis
< XYZ_AXIS_COUNT
; axis
++) {
1533 pt2FilterUpdateCutoff(&pidRuntime
.dtermLowpass
[axis
].pt2Filter
, pt2FilterGain(cutoffFreq
, pidRuntime
.dT
));
1537 for (int axis
= 0; axis
< XYZ_AXIS_COUNT
; axis
++) {
1538 pt3FilterUpdateCutoff(&pidRuntime
.dtermLowpass
[axis
].pt3Filter
, pt3FilterGain(cutoffFreq
, pidRuntime
.dT
));
1546 float dynLpfCutoffFreq(float throttle
, uint16_t dynLpfMin
, uint16_t dynLpfMax
, uint8_t expo
)
1548 const float expof
= expo
/ 10.0f
;
1549 const float curve
= throttle
* (1 - throttle
) * expof
+ throttle
;
1550 return (dynLpfMax
- dynLpfMin
) * curve
+ dynLpfMin
;
1553 void pidSetItermReset(bool enabled
)
1555 pidRuntime
.zeroThrottleItermReset
= enabled
;
1558 float pidGetPreviousSetpoint(int axis
)
1560 return pidRuntime
.previousPidSetpoint
[axis
];
1563 float pidGetDT(void)
1565 return pidRuntime
.dT
;
1568 float pidGetPidFrequency(void)
1570 return pidRuntime
.pidFrequency
;