pid slider support with changed defaults
[betaflight.git] / src / main / flight / pid.h
blob253b8772428e7c02f8c82ae59f2d7da065165054
1 /*
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)
8 * any later version.
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/>.
21 #pragma once
23 #include <stdbool.h>
24 #include "common/time.h"
25 #include "common/filter.h"
26 #include "common/axis.h"
28 #include "pg/pg.h"
30 #define MAX_PID_PROCESS_DENOM 16
31 #define PID_CONTROLLER_BETAFLIGHT 1
32 #define PID_MIXER_SCALING 1000.0f
33 #define PID_SERVO_MIXER_SCALING 0.7f
34 #define PIDSUM_LIMIT 500
35 #define PIDSUM_LIMIT_YAW 400
36 #define PIDSUM_LIMIT_MIN 100
37 #define PIDSUM_LIMIT_MAX 1000
39 #define PID_GAIN_MAX 250
40 #define F_GAIN_MAX 2000
41 #define D_MIN_GAIN_MAX 250
43 // Scaling factors for Pids for better tunable range in configurator for betaflight pid controller. The scaling is based on legacy pid controller or previous float
44 #define PTERM_SCALE 0.032029f
45 #define ITERM_SCALE 0.244381f
46 #define DTERM_SCALE 0.000529f
48 // The constant scale factor to replace the Kd component of the feedforward calculation.
49 // This value gives the same "feel" as the previous Kd default of 26 (26 * DTERM_SCALE)
50 #define FEEDFORWARD_SCALE 0.013754f
52 // Full iterm suppression in setpoint mode at high-passed setpoint rate > 40deg/sec
53 #define ITERM_RELAX_SETPOINT_THRESHOLD 40.0f
54 #define ITERM_RELAX_CUTOFF_DEFAULT 15
56 // Anti gravity I constant
57 #define AG_KI 21.586988f;
59 #define ITERM_ACCELERATOR_GAIN_OFF 0
60 #define ITERM_ACCELERATOR_GAIN_MAX 30000
61 #define PID_ROLL_DEFAULT { 45, 80, 40, 120 }
62 #define PID_PITCH_DEFAULT { 45, 80, 40, 120 }
63 #define PID_YAW_DEFAULT { 45, 80, 0, 120 }
64 #define D_MIN_DEFAULT { 30, 30, 0 }
66 #define DYN_LPF_DTERM_MIN_HZ_DEFAULT 75
67 #define DYN_LPF_DTERM_MAX_HZ_DEFAULT 150
68 #define DTERM_LOWPASS_2_HZ_DEFAULT 150
70 typedef enum {
71 PID_ROLL,
72 PID_PITCH,
73 PID_YAW,
74 PID_LEVEL,
75 PID_MAG,
76 PID_ITEM_COUNT
77 } pidIndex_e;
79 typedef enum {
80 SUPEREXPO_YAW_OFF = 0,
81 SUPEREXPO_YAW_ON,
82 SUPEREXPO_YAW_ALWAYS
83 } pidSuperExpoYaw_e;
85 typedef enum {
86 PID_STABILISATION_OFF = 0,
87 PID_STABILISATION_ON
88 } pidStabilisationState_e;
90 typedef enum {
91 PID_CRASH_RECOVERY_OFF = 0,
92 PID_CRASH_RECOVERY_ON,
93 PID_CRASH_RECOVERY_BEEP,
94 PID_CRASH_RECOVERY_DISARM,
95 } pidCrashRecovery_e;
97 typedef struct pidf_s {
98 uint8_t P;
99 uint8_t I;
100 uint8_t D;
101 uint16_t F;
102 } pidf_t;
104 typedef enum {
105 ANTI_GRAVITY_SMOOTH,
106 ANTI_GRAVITY_STEP
107 } antiGravityMode_e;
109 typedef enum {
110 ITERM_RELAX_OFF,
111 ITERM_RELAX_RP,
112 ITERM_RELAX_RPY,
113 ITERM_RELAX_RP_INC,
114 ITERM_RELAX_RPY_INC,
115 ITERM_RELAX_COUNT,
116 } itermRelax_e;
118 typedef enum {
119 ITERM_RELAX_GYRO,
120 ITERM_RELAX_SETPOINT,
121 ITERM_RELAX_TYPE_COUNT,
122 } itermRelaxType_e;
124 typedef enum feedforwardAveraging_e {
125 FEEDFORWARD_AVERAGING_OFF,
126 FEEDFORWARD_AVERAGING_2_POINT,
127 FEEDFORWARD_AVERAGING_3_POINT,
128 FEEDFORWARD_AVERAGING_4_POINT,
129 } feedforwardAveraging_t;
131 #define MAX_PROFILE_NAME_LENGTH 8u
133 typedef struct pidProfile_s {
134 uint16_t yaw_lowpass_hz; // Additional yaw filter when yaw axis too noisy
135 uint16_t dterm_lowpass_hz; // Delta Filter in hz
136 uint16_t dterm_notch_hz; // Biquad dterm notch hz
137 uint16_t dterm_notch_cutoff; // Biquad dterm notch low cutoff
139 pidf_t pid[PID_ITEM_COUNT];
141 uint8_t dterm_filter_type; // Filter selection for dterm
142 uint8_t itermWindupPointPercent; // iterm windup threshold, percent motor saturation
143 uint16_t pidSumLimit;
144 uint16_t pidSumLimitYaw;
145 uint8_t pidAtMinThrottle; // Disable/Enable pids on zero throttle. Normally even without airmode P and D would be active.
146 uint8_t levelAngleLimit; // Max angle in degrees in level mode
148 uint8_t horizon_tilt_effect; // inclination factor for Horizon mode
149 uint8_t horizon_tilt_expert_mode; // OFF or ON
151 // Betaflight PID controller parameters
152 uint8_t antiGravityMode; // type of anti gravity method
153 uint16_t itermThrottleThreshold; // max allowed throttle delta before iterm accelerated in ms
154 uint16_t itermAcceleratorGain; // Iterm Accelerator Gain when itermThrottlethreshold is hit
155 uint16_t yawRateAccelLimit; // yaw accel limiter for deg/sec/ms
156 uint16_t rateAccelLimit; // accel limiter roll/pitch deg/sec/ms
157 uint16_t crash_dthreshold; // dterm crash value
158 uint16_t crash_gthreshold; // gyro crash value
159 uint16_t crash_setpoint_threshold; // setpoint must be below this value to detect crash, so flips and rolls are not interpreted as crashes
160 uint16_t crash_time; // ms
161 uint16_t crash_delay; // ms
162 uint8_t crash_recovery_angle; // degrees
163 uint8_t crash_recovery_rate; // degree/second
164 uint16_t crash_limit_yaw; // limits yaw errorRate, so crashes don't cause huge throttle increase
165 uint16_t itermLimit;
166 uint16_t dterm_lowpass2_hz; // Extra PT1 Filter on D in hz
167 uint8_t crash_recovery; // off, on, on and beeps when it is in crash recovery mode
168 uint8_t throttle_boost; // how much should throttle be boosted during transient changes 0-100, 100 adds 10x hpf filtered throttle
169 uint8_t throttle_boost_cutoff; // Which cutoff frequency to use for throttle boost. higher cutoffs keep the boost on for shorter. Specified in hz.
170 uint8_t iterm_rotation; // rotates iterm to translate world errors to local coordinate system
171 uint8_t iterm_relax_type; // Specifies type of relax algorithm
172 uint8_t iterm_relax_cutoff; // This cutoff frequency specifies a low pass filter which predicts average response of the quad to setpoint
173 uint8_t iterm_relax; // Enable iterm suppression during stick input
174 uint8_t acro_trainer_angle_limit; // Acro trainer roll/pitch angle limit in degrees
175 uint8_t acro_trainer_debug_axis; // The axis for which record debugging values are captured 0=roll, 1=pitch
176 uint8_t acro_trainer_gain; // The strength of the limiting. Raising may reduce overshoot but also lead to oscillation around the angle limit
177 uint16_t acro_trainer_lookahead_ms; // The lookahead window in milliseconds used to reduce overshoot
178 uint8_t abs_control_gain; // How strongly should the absolute accumulated error be corrected for
179 uint8_t abs_control_limit; // Limit to the correction
180 uint8_t abs_control_error_limit; // Limit to the accumulated error
181 uint8_t abs_control_cutoff; // Cutoff frequency for path estimation in abs control
182 uint8_t dterm_filter2_type; // Filter selection for 2nd dterm
183 uint16_t dyn_lpf_dterm_min_hz;
184 uint16_t dyn_lpf_dterm_max_hz;
185 uint8_t launchControlMode; // Whether launch control is limited to pitch only (launch stand or top-mount) or all axes (on battery)
186 uint8_t launchControlThrottlePercent; // Throttle percentage to trigger launch for launch control
187 uint8_t launchControlAngleLimit; // Optional launch control angle limit (requires ACC)
188 uint8_t launchControlGain; // Iterm gain used while launch control is active
189 uint8_t launchControlAllowTriggerReset; // Controls trigger behavior and whether the trigger can be reset
190 uint8_t use_integrated_yaw; // Selects whether the yaw pidsum should integrated
191 uint8_t integrated_yaw_relax; // Specifies how much integrated yaw should be reduced to offset the drag based yaw component
192 uint8_t thrustLinearization; // Compensation factor for pid linearization
193 uint8_t d_min[XYZ_AXIS_COUNT]; // Minimum D value on each axis
194 uint8_t d_min_gain; // Gain factor for amount of gyro / setpoint activity required to boost D
195 uint8_t d_min_advance; // Percentage multiplier for setpoint input to boost algorithm
196 uint8_t motor_output_limit; // Upper limit of the motor output (percent)
197 int8_t auto_profile_cell_count; // Cell count for this profile to be used with if auto PID profile switching is used
198 uint8_t transient_throttle_limit; // Maximum DC component of throttle change to mix into throttle to prevent airmode mirroring noise
199 char profileName[MAX_PROFILE_NAME_LENGTH + 1]; // Descriptive name for profile
201 uint8_t dyn_idle_min_rpm; // minimum motor speed enforced by the dynamic idle controller
202 uint8_t dyn_idle_p_gain; // P gain during active control of rpm
203 uint8_t dyn_idle_i_gain; // I gain during active control of rpm
204 uint8_t dyn_idle_d_gain; // D gain for corrections around rapid changes in rpm
205 uint8_t dyn_idle_max_increase; // limit on maximum possible increase in motor idle drive during active control
207 uint8_t feedforward_transition; // Feedforward attenuation around centre sticks
208 uint8_t feedforward_averaging; // Number of packets to average when averaging is on
209 uint8_t feedforward_smooth_factor; // Amount of lowpass type smoothing for feedforward steps
210 uint8_t feedforward_jitter_factor; // Number of RC steps below which to attenuate feedforward
211 uint8_t feedforward_boost; // amount of setpoint acceleration to add to feedforward, 10 means 100% added
212 uint8_t feedforward_max_rate_limit; // Maximum setpoint rate percentage for feedforward
214 uint8_t dyn_lpf_curve_expo; // set the curve for dynamic dterm lowpass filter
215 uint8_t level_race_mode; // NFE race mode - when true pitch setpoint calculation is gyro based in level mode
216 uint8_t vbat_sag_compensation; // Reduce motor output by this percentage of the maximum compensation amount
218 uint8_t simplified_pids_mode;
219 uint8_t simplified_master_multiplier;
220 uint8_t simplified_roll_pitch_ratio;
221 uint8_t simplified_i_gain;
222 uint8_t simplified_d_gain;
223 uint8_t simplified_pi_gain;
224 uint8_t simplified_dmin_ratio;
225 uint8_t simplified_feedforward_gain;
226 uint8_t simplified_dterm_filter;
227 uint8_t simplified_dterm_filter_multiplier;
228 uint8_t simplified_pitch_pi_gain;
229 } pidProfile_t;
231 PG_DECLARE_ARRAY(pidProfile_t, PID_PROFILE_COUNT, pidProfiles);
233 typedef struct pidConfig_s {
234 uint8_t pid_process_denom; // Processing denominator for PID controller vs gyro sampling rate
235 uint8_t runaway_takeoff_prevention; // off, on - enables pidsum runaway disarm logic
236 uint16_t runaway_takeoff_deactivate_delay; // delay in ms for "in-flight" conditions before deactivation (successful flight)
237 uint8_t runaway_takeoff_deactivate_throttle; // minimum throttle percent required during deactivation phase
238 } pidConfig_t;
240 PG_DECLARE(pidConfig_t, pidConfig);
242 union rollAndPitchTrims_u;
243 void pidController(const pidProfile_t *pidProfile, timeUs_t currentTimeUs);
245 typedef struct pidAxisData_s {
246 float P;
247 float I;
248 float D;
249 float F;
251 float Sum;
252 } pidAxisData_t;
254 typedef union dtermLowpass_u {
255 pt1Filter_t pt1Filter;
256 biquadFilter_t biquadFilter;
257 pt2Filter_t pt2Filter;
258 pt3Filter_t pt3Filter;
259 } dtermLowpass_t;
261 typedef struct pidCoefficient_s {
262 float Kp;
263 float Ki;
264 float Kd;
265 float Kf;
266 } pidCoefficient_t;
268 typedef struct pidRuntime_s {
269 float dT;
270 float pidFrequency;
271 bool pidStabilisationEnabled;
272 float previousPidSetpoint[XYZ_AXIS_COUNT];
273 filterApplyFnPtr dtermNotchApplyFn;
274 biquadFilter_t dtermNotch[XYZ_AXIS_COUNT];
275 filterApplyFnPtr dtermLowpassApplyFn;
276 dtermLowpass_t dtermLowpass[XYZ_AXIS_COUNT];
277 filterApplyFnPtr dtermLowpass2ApplyFn;
278 dtermLowpass_t dtermLowpass2[XYZ_AXIS_COUNT];
279 filterApplyFnPtr ptermYawLowpassApplyFn;
280 pt1Filter_t ptermYawLowpass;
281 bool antiGravityEnabled;
282 uint8_t antiGravityMode;
283 pt1Filter_t antiGravityThrottleLpf;
284 pt1Filter_t antiGravitySmoothLpf;
285 float antiGravityOsdCutoff;
286 float antiGravityThrottleHpf;
287 float antiGravityPBoost;
288 float itermAccelerator;
289 uint16_t itermAcceleratorGain;
290 pidCoefficient_t pidCoefficient[XYZ_AXIS_COUNT];
291 float levelGain;
292 float horizonGain;
293 float horizonTransition;
294 float horizonCutoffDegrees;
295 float horizonFactorRatio;
296 uint8_t horizonTiltExpertMode;
297 float maxVelocity[XYZ_AXIS_COUNT];
298 float itermWindupPointInv;
299 bool inCrashRecoveryMode;
300 timeUs_t crashDetectedAtUs;
301 timeDelta_t crashTimeLimitUs;
302 timeDelta_t crashTimeDelayUs;
303 int32_t crashRecoveryAngleDeciDegrees;
304 float crashRecoveryRate;
305 float crashGyroThreshold;
306 float crashDtermThreshold;
307 float crashSetpointThreshold;
308 float crashLimitYaw;
309 float itermLimit;
310 bool itermRotation;
311 bool zeroThrottleItermReset;
312 bool levelRaceMode;
314 #ifdef USE_ITERM_RELAX
315 pt1Filter_t windupLpf[XYZ_AXIS_COUNT];
316 uint8_t itermRelax;
317 uint8_t itermRelaxType;
318 uint8_t itermRelaxCutoff;
319 #endif
321 #ifdef USE_ABSOLUTE_CONTROL
322 float acCutoff;
323 float acGain;
324 float acLimit;
325 float acErrorLimit;
326 pt1Filter_t acLpf[XYZ_AXIS_COUNT];
327 float oldSetpointCorrection[XYZ_AXIS_COUNT];
328 #endif
330 #ifdef USE_D_MIN
331 pt2Filter_t dMinRange[XYZ_AXIS_COUNT];
332 pt2Filter_t dMinLowpass[XYZ_AXIS_COUNT];
333 float dMinPercent[XYZ_AXIS_COUNT];
334 float dMinGyroGain;
335 float dMinSetpointGain;
336 #endif
338 #ifdef USE_AIRMODE_LPF
339 pt1Filter_t airmodeThrottleLpf1;
340 pt1Filter_t airmodeThrottleLpf2;
341 #endif
343 #ifdef USE_RC_SMOOTHING_FILTER
344 pt3Filter_t feedforwardPt3[XYZ_AXIS_COUNT];
345 bool feedforwardLpfInitialized;
346 uint8_t rcSmoothingDebugAxis;
347 uint8_t rcSmoothingFilterType;
348 #endif // USE_RC_SMOOTHING_FILTER
350 #ifdef USE_ACRO_TRAINER
351 float acroTrainerAngleLimit;
352 float acroTrainerLookaheadTime;
353 uint8_t acroTrainerDebugAxis;
354 float acroTrainerGain;
355 bool acroTrainerActive;
356 int acroTrainerAxisState[2]; // only need roll and pitch
357 #endif
359 #ifdef USE_DYN_LPF
360 uint8_t dynLpfFilter;
361 uint16_t dynLpfMin;
362 uint16_t dynLpfMax;
363 uint8_t dynLpfCurveExpo;
364 #endif
366 #ifdef USE_LAUNCH_CONTROL
367 uint8_t launchControlMode;
368 uint8_t launchControlAngleLimit;
369 float launchControlKi;
370 #endif
372 #ifdef USE_INTEGRATED_YAW_CONTROL
373 bool useIntegratedYaw;
374 uint8_t integratedYawRelax;
375 #endif
377 #ifdef USE_THRUST_LINEARIZATION
378 float thrustLinearization;
379 float throttleCompensateAmount;
380 #endif
382 #ifdef USE_AIRMODE_LPF
383 float airmodeThrottleOffsetLimit;
384 #endif
386 #ifdef USE_FEEDFORWARD
387 float feedforwardTransitionFactor;
388 feedforwardAveraging_t feedforwardAveraging;
389 float feedforwardSmoothFactor;
390 float feedforwardJitterFactor;
391 float feedforwardBoostFactor;
392 #endif
393 } pidRuntime_t;
395 extern pidRuntime_t pidRuntime;
397 extern const char pidNames[];
399 extern pidAxisData_t pidData[3];
401 extern uint32_t targetPidLooptime;
403 extern float throttleBoost;
404 extern pt1Filter_t throttleLpf;
406 void pidResetIterm(void);
407 void pidStabilisationState(pidStabilisationState_e pidControllerState);
408 void pidSetItermAccelerator(float newItermAccelerator);
409 bool crashRecoveryModeActive(void);
410 void pidAcroTrainerInit(void);
411 void pidSetAcroTrainerState(bool newState);
412 void pidUpdateAntiGravityThrottleFilter(float throttle);
413 bool pidOsdAntiGravityActive(void);
414 bool pidOsdAntiGravityMode(void);
415 void pidSetAntiGravityState(bool newState);
416 bool pidAntiGravityEnabled(void);
418 #ifdef USE_THRUST_LINEARIZATION
419 float pidApplyThrustLinearization(float motorValue);
420 float pidCompensateThrustLinearization(float throttle);
421 #endif
423 #ifdef USE_AIRMODE_LPF
424 void pidUpdateAirmodeLpf(float currentOffset);
425 float pidGetAirmodeThrottleOffset();
426 #endif
428 #ifdef UNIT_TEST
429 #include "sensors/acceleration.h"
430 extern float axisError[XYZ_AXIS_COUNT];
431 void applyItermRelax(const int axis, const float iterm,
432 const float gyroRate, float *itermErrorRate, float *currentPidSetpoint);
433 void applyAbsoluteControl(const int axis, const float gyroRate, float *currentPidSetpoint, float *itermErrorRate);
434 void rotateItermAndAxisError();
435 float pidLevel(int axis, const pidProfile_t *pidProfile,
436 const rollAndPitchTrims_t *angleTrim, float currentPidSetpoint);
437 float calcHorizonLevelStrength(void);
438 #endif
439 void dynLpfDTermUpdate(float throttle);
440 void pidSetItermReset(bool enabled);
441 float pidGetPreviousSetpoint(int axis);
442 float pidGetDT();
443 float pidGetPidFrequency();
444 float pidGetFeedforwardBoostFactor();
445 float pidGetFeedforwardSmoothFactor();
446 float pidGetFeedforwardJitterFactor();
447 float pidGetFeedforwardTransitionFactor();
448 float dynLpfCutoffFreq(float throttle, uint16_t dynLpfMin, uint16_t dynLpfMax, uint8_t expo);