3.0.1 Defaults // Improve setpoint transition
[betaflight.git] / src / main / flight / pid.c
blobdee35d6af760ba24f43edeab4b04fc74a0269521
1 /*
2 * This file is part of Cleanflight.
4 * Cleanflight is free software: you can redistribute it and/or modify
5 * it under the terms of the GNU General Public License as published by
6 * the Free Software Foundation, either version 3 of the License, or
7 * (at your option) any later version.
9 * Cleanflight is distributed in the hope that it will be useful,
10 * but WITHOUT ANY WARRANTY; without even the implied warranty of
11 * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
12 * GNU General Public License for more details.
14 * You should have received a copy of the GNU General Public License
15 * along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
18 #include <stdbool.h>
19 #include <stdint.h>
20 #include <math.h>
22 #include <platform.h>
24 #include "build_config.h"
25 #include "debug.h"
27 #include "common/axis.h"
28 #include "common/maths.h"
29 #include "common/filter.h"
31 #include "drivers/sensor.h"
33 #include "drivers/accgyro.h"
34 #include "sensors/sensors.h"
35 #include "sensors/gyro.h"
36 #include "sensors/acceleration.h"
38 #include "rx/rx.h"
40 #include "io/rc_controls.h"
41 #include "io/gps.h"
43 #include "flight/pid.h"
44 #include "flight/imu.h"
45 #include "flight/navigation.h"
46 #include "flight/gtune.h"
48 #include "config/runtime_config.h"
50 extern uint8_t motorCount;
51 uint32_t targetPidLooptime;
52 extern float setpointRate[3];
53 extern float rcInput[3];
55 static bool pidStabilisationEnabled;
57 int16_t axisPID[3];
59 #ifdef BLACKBOX
60 int32_t axisPID_P[3], axisPID_I[3], axisPID_D[3];
61 #endif
63 // PIDweight is a scale factor for PIDs which is derived from the throttle and TPA setting, and 100 = 100% scale means no PID reduction
64 uint8_t PIDweight[3];
66 static int32_t errorGyroI[3];
67 static float errorGyroIf[3];
69 static void pidLegacy(const pidProfile_t *pidProfile, uint16_t max_angle_inclination,
70 const rollAndPitchTrims_t *angleTrim, const rxConfig_t *rxConfig);
71 #ifdef SKIP_PID_FLOAT
72 pidControllerFuncPtr pid_controller = pidLegacy; // which pid controller are we using
73 #else
74 static void pidBetaflight(const pidProfile_t *pidProfile, uint16_t max_angle_inclination,
75 const rollAndPitchTrims_t *angleTrim, const rxConfig_t *rxConfig);
76 pidControllerFuncPtr pid_controller = pidBetaflight; // which pid controller are we using
77 #endif
79 void setTargetPidLooptime(uint32_t pidLooptime)
81 targetPidLooptime = pidLooptime;
84 void pidResetErrorGyroState(void)
86 for (int axis = 0; axis < 3; axis++) {
87 errorGyroI[axis] = 0;
88 errorGyroIf[axis] = 0.0f;
92 void pidStabilisationState(pidStabilisationState_e pidControllerState)
94 pidStabilisationEnabled = (pidControllerState == PID_STABILISATION_ON) ? true : false;
97 float getdT (void)
99 static float dT;
100 if (!dT) dT = (float)targetPidLooptime * 0.000001f;
102 return dT;
105 const angle_index_t rcAliasToAngleIndexMap[] = { AI_ROLL, AI_PITCH };
107 static pt1Filter_t deltaFilter[3];
108 static pt1Filter_t yawFilter;
109 static biquadFilter_t dtermFilterLpf[3];
110 static biquadFilter_t dtermFilterNotch[3];
111 static firFilterState_t dtermDenoisingState[3];
112 static bool dtermNotchInitialised;
114 void initFilters(const pidProfile_t *pidProfile) {
115 int axis;
116 static uint8_t lowpassFilterType;
118 if (pidProfile->dterm_notch_hz && !dtermNotchInitialised) {
119 float notchQ = filterGetNotchQ(pidProfile->dterm_notch_hz, pidProfile->dterm_notch_cutoff);
120 for (axis = 0; axis < 3; axis++) biquadFilterInit(&dtermFilterNotch[axis], pidProfile->dterm_notch_hz, targetPidLooptime, notchQ, FILTER_NOTCH);
121 dtermNotchInitialised = true;
124 if ((pidProfile->dterm_filter_type != lowpassFilterType) && pidProfile->dterm_lpf_hz) {
125 if (pidProfile->dterm_filter_type == FILTER_BIQUAD) {
126 for (axis = 0; axis < 3; axis++) biquadFilterInitLPF(&dtermFilterLpf[axis], pidProfile->dterm_lpf_hz, targetPidLooptime);
129 if (pidProfile->dterm_filter_type == FILTER_FIR) {
130 for (axis = 0; axis < 3; axis++) initFirFilter(&dtermDenoisingState[axis], pidProfile->dterm_lpf_hz, targetPidLooptime);
132 lowpassFilterType = pidProfile->dterm_filter_type;
136 #ifndef SKIP_PID_FLOAT
137 // Betaflight pid controller, which will be maintained in the future with additional features specialised for current (mini) multirotor usage. Based on 2DOF reference design (matlab)
138 static void pidBetaflight(const pidProfile_t *pidProfile, uint16_t max_angle_inclination,
139 const rollAndPitchTrims_t *angleTrim, const rxConfig_t *rxConfig)
141 float errorRate = 0, rD = 0, PVRate = 0, dynC;
142 float ITerm,PTerm,DTerm;
143 static float lastRateError[2];
144 static float Kp[3], Ki[3], Kd[3], c[3], rollPitchMaxVelocity, yawMaxVelocity, previousSetpoint[3], relaxFactor[3];
145 float delta;
146 int axis;
147 float horizonLevelStrength = 1;
149 float tpaFactor = PIDweight[0] / 100.0f; // tpa is now float
151 initFilters(pidProfile);
153 if (FLIGHT_MODE(HORIZON_MODE)) {
154 // Figure out the raw stick positions
155 const int32_t stickPosAil = ABS(getRcStickDeflection(FD_ROLL, rxConfig->midrc));
156 const int32_t stickPosEle = ABS(getRcStickDeflection(FD_PITCH, rxConfig->midrc));
157 const int32_t mostDeflectedPos = MAX(stickPosAil, stickPosEle);
158 // Progressively turn off the horizon self level strength as the stick is banged over
159 horizonLevelStrength = (float)(500 - mostDeflectedPos) / 500; // 1 at centre stick, 0 = max stick deflection
160 if(pidProfile->D8[PIDLEVEL] == 0){
161 horizonLevelStrength = 0;
162 } else {
163 horizonLevelStrength = constrainf(((horizonLevelStrength - 1) * (100 / pidProfile->D8[PIDLEVEL])) + 1, 0, 1);
167 // Yet Highly experimental and under test and development
168 // Throttle coupled to Igain like inverted TPA // 50hz calculation (should cover all rx protocols)
169 static float kiThrottleGain = 1.0f;
170 if (pidProfile->itermThrottleGain) {
171 const uint16_t maxLoopCount = 20000 / targetPidLooptime;
172 const float throttleItermGain = (float)pidProfile->itermThrottleGain * 0.001f;
173 static int16_t previousThrottle;
174 static uint16_t loopIncrement;
176 if (loopIncrement >= maxLoopCount) {
177 kiThrottleGain = 1.0f + constrainf((float)(ABS(rcCommand[THROTTLE] - previousThrottle)) * throttleItermGain, 0.0f, 5.0f); // Limit to factor 5
178 previousThrottle = rcCommand[THROTTLE];
179 loopIncrement = 0;
180 } else {
181 loopIncrement++;
185 // ----------PID controller----------
186 for (axis = 0; axis < 3; axis++) {
188 static uint8_t configP[3], configI[3], configD[3];
190 // Prevent unnecessary computing and check for changed PIDs. No need for individual checks. Only pids is fine for now
191 // Prepare all parameters for PID controller
192 if ((pidProfile->P8[axis] != configP[axis]) || (pidProfile->I8[axis] != configI[axis]) || (pidProfile->D8[axis] != configD[axis])) {
193 Kp[axis] = PTERM_SCALE * pidProfile->P8[axis];
194 Ki[axis] = ITERM_SCALE * pidProfile->I8[axis];
195 Kd[axis] = DTERM_SCALE * pidProfile->D8[axis];
196 c[axis] = pidProfile->dtermSetpointWeight / 100.0f;
197 relaxFactor[axis] = 1.0f - (pidProfile->setpointRelaxRatio / 100.0f);
198 yawMaxVelocity = pidProfile->yawRateAccelLimit * 1000 * getdT();
199 rollPitchMaxVelocity = pidProfile->rateAccelLimit * 1000 * getdT();
201 configP[axis] = pidProfile->P8[axis];
202 configI[axis] = pidProfile->I8[axis];
203 configD[axis] = pidProfile->D8[axis];
206 // Limit abrupt yaw inputs / stops
207 float maxVelocity = (axis == YAW) ? yawMaxVelocity : rollPitchMaxVelocity;
208 if (maxVelocity) {
209 float currentVelocity = setpointRate[axis] - previousSetpoint[axis];
210 if (ABS(currentVelocity) > maxVelocity) {
211 setpointRate[axis] = (currentVelocity > 0) ? previousSetpoint[axis] + maxVelocity : previousSetpoint[axis] - maxVelocity;
213 previousSetpoint[axis] = setpointRate[axis];
216 // Yaw control is GYRO based, direct sticks control is applied to rate PID
217 if ((FLIGHT_MODE(ANGLE_MODE) || FLIGHT_MODE(HORIZON_MODE)) && axis != YAW) {
218 // calculate error angle and limit the angle to the max inclination
219 #ifdef GPS
220 const float errorAngle = (constrainf(pidProfile->levelSensitivity * rcCommand[axis] + GPS_angle[axis], -((int) max_angle_inclination),
221 +max_angle_inclination) - attitude.raw[axis] + angleTrim->raw[axis]) / 10.0f; // 16 bits is ok here
222 #else
223 const float errorAngle = (constrainf(pidProfile->levelSensitivity * rcCommand[axis], -((int) max_angle_inclination),
224 +max_angle_inclination) - attitude.raw[axis] + angleTrim->raw[axis]) / 10.0f; // 16 bits is ok here
225 #endif
226 if (FLIGHT_MODE(ANGLE_MODE)) {
227 // ANGLE mode - control is angle based, so control loop is needed
228 setpointRate[axis] = errorAngle * pidProfile->P8[PIDLEVEL] / 10.0f;
229 } else {
230 // HORIZON mode - direct sticks control is applied to rate PID
231 // mix up angle error to desired AngleRate to add a little auto-level feel
232 setpointRate[axis] = setpointRate[axis] + (errorAngle * pidProfile->I8[PIDLEVEL] * horizonLevelStrength / 10.0f);
236 PVRate = gyroADCf[axis] / 16.4f; // Process variable from gyro output in deg/sec
238 // --------low-level gyro-based PID based on 2DOF PID controller. ----------
239 // ---------- 2-DOF PID controller with optional filter on derivative term. b = 1 and only c can be tuned (amount derivative on measurement or error). ----------
240 // Used in stand-alone mode for ACRO, controlled by higher level regulators in other modes
241 // ----- calculate error / angle rates ----------
242 errorRate = setpointRate[axis] - PVRate; // r - y
244 // -----calculate P component and add Dynamic Part based on stick input
245 PTerm = Kp[axis] * errorRate * tpaFactor;
247 // -----calculate I component.
248 // Reduce strong Iterm accumulation during higher stick inputs
249 float accumulationThreshold = (axis == YAW) ? pidProfile->yawItermIgnoreRate : pidProfile->rollPitchItermIgnoreRate;
250 float setpointRateScaler = constrainf(1.0f - (ABS(setpointRate[axis]) / accumulationThreshold), 0.0f, 1.0f);
252 // Handle All windup Scenarios
253 // limit maximum integrator value to prevent WindUp
254 float itermScaler = setpointRateScaler * kiThrottleGain;
256 errorGyroIf[axis] = constrainf(errorGyroIf[axis] + Ki[axis] * errorRate * getdT() * itermScaler, -250.0f, 250.0f);
258 // I coefficient (I8) moved before integration to make limiting independent from PID settings
259 ITerm = errorGyroIf[axis];
261 //-----calculate D-term (Yaw D not yet supported)
262 if (axis != YAW) {
263 static float previousSetpoint[3];
264 dynC = c[axis];
265 if (pidProfile->setpointRelaxRatio < 100) {
266 dynC = c[axis];
267 if (setpointRate[axis] > 0) {
268 if ((setpointRate[axis] - previousSetpoint[axis]) < previousSetpoint[axis])
269 dynC = dynC * powerf(rcInput[axis], 2) * relaxFactor[axis] + dynC * (1-relaxFactor[axis]);
270 } else if (setpointRate[axis] < 0) {
271 if ((setpointRate[axis] - previousSetpoint[axis]) > previousSetpoint[axis])
272 dynC = dynC * powerf(rcInput[axis], 2) * relaxFactor[axis] + dynC * (1-relaxFactor[axis]);
275 previousSetpoint[axis] = setpointRate[axis];
276 rD = dynC * setpointRate[axis] - PVRate; // cr - y
277 delta = rD - lastRateError[axis];
278 lastRateError[axis] = rD;
280 // Divide delta by targetLooptime to get differential (ie dr/dt)
281 delta *= (1.0f / getdT());
283 if (debugMode == DEBUG_DTERM_FILTER) debug[axis] = Kd[axis] * delta * tpaFactor;
285 // Filter delta
286 if (dtermNotchInitialised) delta = biquadFilterApply(&dtermFilterNotch[axis], delta);
288 if (pidProfile->dterm_lpf_hz) {
289 if (pidProfile->dterm_filter_type == FILTER_BIQUAD)
290 delta = biquadFilterApply(&dtermFilterLpf[axis], delta);
291 else if (pidProfile->dterm_filter_type == FILTER_PT1)
292 delta = pt1FilterApply4(&deltaFilter[axis], delta, pidProfile->dterm_lpf_hz, getdT());
293 else
294 delta = firFilterUpdate(&dtermDenoisingState[axis], delta);
297 DTerm = Kd[axis] * delta * tpaFactor;
299 // -----calculate total PID output
300 axisPID[axis] = constrain(lrintf(PTerm + ITerm + DTerm), -pidProfile->pidSumLimit, pidProfile->pidSumLimit);
301 } else {
302 if (pidProfile->yaw_lpf_hz) PTerm = pt1FilterApply4(&yawFilter, PTerm, pidProfile->yaw_lpf_hz, getdT());
304 axisPID[axis] = lrintf(PTerm + ITerm);
306 DTerm = 0.0f; // needed for blackbox
309 // Disable PID control at zero throttle
310 if (!pidStabilisationEnabled) axisPID[axis] = 0;
312 #ifdef GTUNE
313 if (FLIGHT_MODE(GTUNE_MODE) && ARMING_FLAG(ARMED)) {
314 calculate_Gtune(axis);
316 #endif
318 #ifdef BLACKBOX
319 axisPID_P[axis] = PTerm;
320 axisPID_I[axis] = ITerm;
321 axisPID_D[axis] = DTerm;
322 #endif
325 #endif
327 // Legacy pid controller betaflight evolved pid rewrite based on 2.9 releae. Good for fastest cycletimes for those who believe in that. Don't expect much development in the future
328 static void pidLegacy(const pidProfile_t *pidProfile, uint16_t max_angle_inclination,
329 const rollAndPitchTrims_t *angleTrim, const rxConfig_t *rxConfig)
331 int axis;
332 int32_t PTerm, ITerm, DTerm, delta;
333 static int32_t lastRateError[3];
334 int32_t AngleRateTmp = 0, RateError = 0, gyroRate = 0;
336 int8_t horizonLevelStrength = 100;
338 initFilters(pidProfile);
340 if (FLIGHT_MODE(HORIZON_MODE)) {
341 // Figure out the raw stick positions
342 const int32_t stickPosAil = ABS(getRcStickDeflection(FD_ROLL, rxConfig->midrc));
343 const int32_t stickPosEle = ABS(getRcStickDeflection(FD_PITCH, rxConfig->midrc));
344 const int32_t mostDeflectedPos = MAX(stickPosAil, stickPosEle);
345 // Progressively turn off the horizon self level strength as the stick is banged over
346 horizonLevelStrength = (500 - mostDeflectedPos) / 5; // 100 at centre stick, 0 = max stick deflection
347 // Using Level D as a Sensitivity for Horizon. 0 more level to 255 more rate. Default value of 100 seems to work fine.
348 // For more rate mode increase D and slower flips and rolls will be possible
349 horizonLevelStrength = constrain((10 * (horizonLevelStrength - 100) * (10 * pidProfile->D8[PIDLEVEL] / 80) / 100) + 100, 0, 100);
352 // ----------PID controller----------
353 for (axis = 0; axis < 3; axis++) {
355 // -----Get the desired angle rate depending on flight mode
356 AngleRateTmp = (int32_t)setpointRate[axis];
358 if ((FLIGHT_MODE(ANGLE_MODE) || FLIGHT_MODE(HORIZON_MODE)) && axis != YAW) {
359 // calculate error angle and limit the angle to max configured inclination
360 #ifdef GPS
361 const int32_t errorAngle = constrain(2 * rcCommand[axis] + GPS_angle[axis], -((int) max_angle_inclination),
362 +max_angle_inclination) - attitude.raw[axis] + angleTrim->raw[axis];
363 #else
364 const int32_t errorAngle = constrain(2 * rcCommand[axis], -((int) max_angle_inclination),
365 +max_angle_inclination) - attitude.raw[axis] + angleTrim->raw[axis];
366 #endif
367 if (FLIGHT_MODE(ANGLE_MODE)) {
368 // ANGLE mode - control is angle based, so control loop is needed
369 AngleRateTmp = (errorAngle * pidProfile->P8[PIDLEVEL]) >> 4;
370 } else {
371 // HORIZON mode - mix up angle error to desired AngleRateTmp to add a little auto-level feel,
372 // horizonLevelStrength is scaled to the stick input
373 AngleRateTmp = AngleRateTmp + ((errorAngle * pidProfile->I8[PIDLEVEL] * horizonLevelStrength / 100) >> 4);
377 // --------low-level gyro-based PID. ----------
378 // Used in stand-alone mode for ACRO, controlled by higher level regulators in other modes
379 // -----calculate scaled error.AngleRates
380 // multiplication of rcCommand corresponds to changing the sticks scaling here
381 gyroRate = gyroADC[axis] / 4;
383 RateError = AngleRateTmp - gyroRate;
385 // -----calculate P component
386 PTerm = (RateError * pidProfile->P8[axis] * PIDweight[axis] / 100) >> 7;
388 // Constrain YAW by yaw_p_limit value if not servo driven in that case servolimits apply
389 if((motorCount >= 4 && pidProfile->yaw_p_limit) && axis == YAW) {
390 PTerm = constrain(PTerm, -pidProfile->yaw_p_limit, pidProfile->yaw_p_limit);
393 // -----calculate I component
394 // there should be no division before accumulating the error to integrator, because the precision would be reduced.
395 // Precision is critical, as I prevents from long-time drift. Thus, 32 bits integrator is used.
396 // Time correction (to avoid different I scaling for different builds based on average cycle time)
397 // is normalized to cycle time = 2048.
398 // Prevent Accumulation
399 uint16_t resetRate = (axis == YAW) ? pidProfile->yawItermIgnoreRate : pidProfile->rollPitchItermIgnoreRate;
400 uint16_t dynamicFactor = (1 << 8) - constrain(((ABS(AngleRateTmp) << 6) / resetRate), 0, 1 << 8);
401 uint16_t dynamicKi = (pidProfile->I8[axis] * dynamicFactor) >> 8;
403 errorGyroI[axis] = errorGyroI[axis] + ((RateError * (uint16_t)targetPidLooptime) >> 11) * dynamicKi;
405 // limit maximum integrator value to prevent WindUp - accumulating extreme values when system is saturated.
406 // I coefficient (I8) moved before integration to make limiting independent from PID settings
407 errorGyroI[axis] = constrain(errorGyroI[axis], (int32_t) - GYRO_I_MAX << 13, (int32_t) + GYRO_I_MAX << 13);
409 ITerm = errorGyroI[axis] >> 13;
411 //-----calculate D-term
412 if (axis != YAW) {
413 if (pidProfile->deltaMethod == DELTA_FROM_ERROR) {
414 delta = RateError - lastRateError[axis];
415 lastRateError[axis] = RateError;
416 } else {
417 delta = -(gyroRate - lastRateError[axis]);
418 lastRateError[axis] = gyroRate;
421 // Divide delta by targetLooptime to get differential (ie dr/dt)
422 delta = (delta * ((uint16_t) 0xFFFF / ((uint16_t)targetPidLooptime >> 4))) >> 5;
424 if (debugMode == DEBUG_DTERM_FILTER) debug[axis] = (delta * pidProfile->D8[axis] * PIDweight[axis] / 100) >> 8;
426 // Filter delta
427 if (pidProfile->dterm_lpf_hz) {
428 float deltaf = delta; // single conversion
429 if (pidProfile->dterm_filter_type == FILTER_BIQUAD)
430 delta = biquadFilterApply(&dtermFilterLpf[axis], delta);
431 else if (pidProfile->dterm_filter_type == FILTER_PT1)
432 delta = pt1FilterApply4(&deltaFilter[axis], delta, pidProfile->dterm_lpf_hz, getdT());
433 else
434 delta = firFilterUpdate(&dtermDenoisingState[axis], delta);
436 delta = lrintf(deltaf);
439 DTerm = (delta * pidProfile->D8[axis] * PIDweight[axis] / 100) >> 8;
441 // -----calculate total PID output
442 axisPID[axis] = PTerm + ITerm + DTerm;
443 } else {
444 if (pidProfile->yaw_lpf_hz) PTerm = pt1FilterApply4(&yawFilter, PTerm, pidProfile->yaw_lpf_hz, getdT());
446 axisPID[axis] = PTerm + ITerm;
448 if (motorCount >= 4) {
449 int16_t yaw_jump_prevention_limit = constrain(YAW_JUMP_PREVENTION_LIMIT_HIGH - (pidProfile->D8[axis] << 3), YAW_JUMP_PREVENTION_LIMIT_LOW, YAW_JUMP_PREVENTION_LIMIT_HIGH);
451 // prevent "yaw jump" during yaw correction
452 axisPID[YAW] = constrain(axisPID[YAW], -yaw_jump_prevention_limit - ABS(rcCommand[YAW]), yaw_jump_prevention_limit + ABS(rcCommand[YAW]));
455 DTerm = 0; // needed for blackbox
458 if (!pidStabilisationEnabled) axisPID[axis] = 0;
460 #ifdef GTUNE
461 if (FLIGHT_MODE(GTUNE_MODE) && ARMING_FLAG(ARMED)) {
462 calculate_Gtune(axis);
464 #endif
466 #ifdef BLACKBOX
467 axisPID_P[axis] = PTerm;
468 axisPID_I[axis] = ITerm;
469 axisPID_D[axis] = DTerm;
470 #endif
474 void pidSetController(pidControllerType_e type)
476 switch (type) {
477 default:
478 case PID_CONTROLLER_LEGACY:
479 pid_controller = pidLegacy;
480 break;
481 #ifndef SKIP_PID_FLOAT
482 case PID_CONTROLLER_BETAFLIGHT:
483 pid_controller = pidBetaflight;
484 #endif