Update video-tutorials.md
[u360gts.git] / src / main / flight / pid.c
blobc34adb515b081611c2afbe62460f7b753b6995cb
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"
26 #include "common/axis.h"
27 #include "common/maths.h"
28 #include "common/filter.h"
30 #include "drivers/sensor.h"
31 #include "drivers/accgyro.h"
33 #include "sensors/sensors.h"
34 #include "sensors/gyro.h"
35 #include "sensors/acceleration.h"
37 #include "rx/rx.h"
39 #include "io/rc_controls.h"
40 #include "io/gps.h"
42 #include "flight/pid.h"
43 #include "flight/imu.h"
44 #include "flight/navigation.h"
45 #include "flight/gtune.h"
47 #include "config/runtime_config.h"
49 extern uint16_t cycleTime;
50 extern uint8_t motorCount;
51 extern float dT;
53 int16_t heading;
54 int16_t axisPID[3];
56 #ifdef BLACKBOX
57 int32_t axisPID_P[3], axisPID_I[3], axisPID_D[3];
58 #endif
60 // PIDweight is a scale factor for PIDs which is derived from the throttle and TPA setting, and 100 = 100% scale means no PID reduction
61 uint8_t dynP8[3], dynI8[3], dynD8[3], PIDweight[3];
63 static int32_t errorGyroI[3] = { 0, 0, 0 };
64 static float errorGyroIf[3] = { 0.0f, 0.0f, 0.0f };
65 static int32_t errorAngleI[2] = { 0, 0 };
66 static float errorAngleIf[2] = { 0.0f, 0.0f };
68 static void pidMultiWiiRewrite(pidProfile_t *pidProfile, controlRateConfig_t *controlRateConfig,
69 uint16_t max_angle_inclination, rollAndPitchTrims_t *angleTrim, rxConfig_t *rxConfig);
71 typedef void (*pidControllerFuncPtr)(pidProfile_t *pidProfile, controlRateConfig_t *controlRateConfig,
72 uint16_t max_angle_inclination, rollAndPitchTrims_t *angleTrim, rxConfig_t *rxConfig); // pid controller function prototype
74 pidControllerFuncPtr pid_controller = pidMultiWiiRewrite; // which pid controller are we using
76 void pidResetErrorAngle(void)
78 errorAngleI[ROLL] = 0;
79 errorAngleI[PITCH] = 0;
81 errorAngleIf[ROLL] = 0.0f;
82 errorAngleIf[PITCH] = 0.0f;
85 void pidResetErrorGyro(void)
87 errorGyroI[ROLL] = 0;
88 errorGyroI[PITCH] = 0;
89 errorGyroI[YAW] = 0;
91 errorGyroIf[ROLL] = 0.0f;
92 errorGyroIf[PITCH] = 0.0f;
93 errorGyroIf[YAW] = 0.0f;
96 const angle_index_t rcAliasToAngleIndexMap[] = { AI_ROLL, AI_PITCH };
98 static filterStatePt1_t PTermState[3], DTermState[3];
100 static void pidLuxFloat(pidProfile_t *pidProfile, controlRateConfig_t *controlRateConfig,
101 uint16_t max_angle_inclination, rollAndPitchTrims_t *angleTrim, rxConfig_t *rxConfig)
103 float RateError, errorAngle, AngleRate, gyroRate;
104 float ITerm,PTerm,DTerm;
105 int32_t stickPosAil, stickPosEle, mostDeflectedPos;
106 static float lastError[3];
107 static float delta1[3], delta2[3];
108 float delta, deltaSum;
109 int axis;
110 float horizonLevelStrength = 1;
112 if (FLIGHT_MODE(HORIZON_MODE)) {
114 // Figure out the raw stick positions
115 stickPosAil = getRcStickDeflection(FD_ROLL, rxConfig->midrc);
116 stickPosEle = getRcStickDeflection(FD_PITCH, rxConfig->midrc);
118 if(ABS(stickPosAil) > ABS(stickPosEle)){
119 mostDeflectedPos = ABS(stickPosAil);
121 else {
122 mostDeflectedPos = ABS(stickPosEle);
125 // Progressively turn off the horizon self level strength as the stick is banged over
126 horizonLevelStrength = (float)(500 - mostDeflectedPos) / 500; // 1 at centre stick, 0 = max stick deflection
127 if(pidProfile->H_sensitivity == 0){
128 horizonLevelStrength = 0;
129 } else {
130 horizonLevelStrength = constrainf(((horizonLevelStrength - 1) * (100 / pidProfile->H_sensitivity)) + 1, 0, 1);
134 // ----------PID controller----------
135 for (axis = 0; axis < 3; axis++) {
136 // -----Get the desired angle rate depending on flight mode
137 uint8_t rate = controlRateConfig->rates[axis];
139 if (axis == FD_YAW) {
140 // YAW is always gyro-controlled (MAG correction is applied to rcCommand) 100dps to 1100dps max yaw rate
141 AngleRate = (float)((rate + 10) * rcCommand[YAW]) / 50.0f;
142 } else {
143 // calculate error and limit the angle to the max inclination
144 #ifdef GPS
145 errorAngle = (constrain(rcCommand[axis] + GPS_angle[axis], -((int) max_angle_inclination),
146 +max_angle_inclination) - inclination.raw[axis] + angleTrim->raw[axis]) / 10.0f; // 16 bits is ok here
147 #else
148 errorAngle = (constrain(rcCommand[axis], -((int) max_angle_inclination),
149 +max_angle_inclination) - inclination.raw[axis] + angleTrim->raw[axis]) / 10.0f; // 16 bits is ok here
150 #endif
152 if (FLIGHT_MODE(ANGLE_MODE)) {
153 // it's the ANGLE mode - control is angle based, so control loop is needed
154 AngleRate = errorAngle * pidProfile->A_level;
155 } else {
156 //control is GYRO based (ACRO and HORIZON - direct sticks control is applied to rate PID
157 AngleRate = (float)((rate + 20) * rcCommand[axis]) / 50.0f; // 200dps to 1200dps max roll/pitch rate
158 if (FLIGHT_MODE(HORIZON_MODE)) {
159 // mix up angle error to desired AngleRate to add a little auto-level feel
160 AngleRate += errorAngle * pidProfile->H_level * horizonLevelStrength;
165 gyroRate = gyroADC[axis] * gyro.scale; // gyro output scaled to dps
167 // --------low-level gyro-based PID. ----------
168 // Used in stand-alone mode for ACRO, controlled by higher level regulators in other modes
169 // -----calculate scaled error.AngleRates
170 // multiplication of rcCommand corresponds to changing the sticks scaling here
171 RateError = AngleRate - gyroRate;
173 // -----calculate P component
174 PTerm = RateError * pidProfile->P_f[axis] * PIDweight[axis] / 100;
176 // Pterm low pass
177 if (pidProfile->pterm_cut_hz) {
178 PTerm = filterApplyPt1(PTerm, &PTermState[axis], pidProfile->pterm_cut_hz, dT);
181 // -----calculate I component.
182 errorGyroIf[axis] = constrainf(errorGyroIf[axis] + RateError * dT * pidProfile->I_f[axis] * 10, -250.0f, 250.0f);
184 // limit maximum integrator value to prevent WindUp - accumulating extreme values when system is saturated.
185 // I coefficient (I8) moved before integration to make limiting independent from PID settings
186 ITerm = errorGyroIf[axis];
188 //-----calculate D-term
189 delta = RateError - lastError[axis];
190 lastError[axis] = RateError;
192 // Correct difference by cycle time. Cycle time is jittery (can be different 2 times), so calculated difference
193 // would be scaled by different dt each time. Division by dT fixes that.
194 delta *= (1.0f / dT);
195 // add moving average here to reduce noise
196 deltaSum = delta1[axis] + delta2[axis] + delta;
197 delta2[axis] = delta1[axis];
198 delta1[axis] = delta;
200 // Dterm low pass
201 if (pidProfile->dterm_cut_hz) {
202 deltaSum = filterApplyPt1(deltaSum, &DTermState[axis], pidProfile->dterm_cut_hz, dT);
205 DTerm = constrainf((deltaSum / 3.0f) * pidProfile->D_f[axis] * PIDweight[axis] / 100, -300.0f, 300.0f);
207 // -----calculate total PID output
208 axisPID[axis] = constrain(lrintf(PTerm + ITerm + DTerm), -1000, 1000);
210 #ifdef GTUNE
211 if (FLIGHT_MODE(GTUNE_MODE) && ARMING_FLAG(ARMED)) {
212 calculate_Gtune(axis);
214 #endif
216 #ifdef BLACKBOX
217 axisPID_P[axis] = PTerm;
218 axisPID_I[axis] = ITerm;
219 axisPID_D[axis] = DTerm;
220 #endif
224 static void pidMultiWii23(pidProfile_t *pidProfile, controlRateConfig_t *controlRateConfig, uint16_t max_angle_inclination,
225 rollAndPitchTrims_t *angleTrim, rxConfig_t *rxConfig)
227 UNUSED(rxConfig);
229 int axis, prop = 0;
230 int32_t rc, error, errorAngle;
231 int32_t PTerm, ITerm, PTermACC, ITermACC, DTerm;
232 static int16_t lastGyro[2] = { 0, 0 };
233 static int32_t delta1[2] = { 0, 0 }, delta2[2] = { 0, 0 };
234 int32_t delta;
236 if (FLIGHT_MODE(HORIZON_MODE)) {
237 prop = MIN(MAX(ABS(rcCommand[PITCH]), ABS(rcCommand[ROLL])), 512);
240 // PITCH & ROLL
241 for (axis = 0; axis < 2; axis++) {
243 rc = rcCommand[axis] << 1;
245 error = rc - (gyroADC[axis] / 4);
246 errorGyroI[axis] = constrain(errorGyroI[axis] + error, -16000, +16000); // WindUp 16 bits is ok here
248 if (ABS(gyroADC[axis]) > (640 * 4)) {
249 errorGyroI[axis] = 0;
252 ITerm = (errorGyroI[axis] >> 7) * pidProfile->I8[axis] >> 6; // 16 bits is ok here 16000/125 = 128 ; 128*250 = 32000
254 PTerm = (int32_t)rc * pidProfile->P8[axis] >> 6;
256 if (FLIGHT_MODE(ANGLE_MODE) || FLIGHT_MODE(HORIZON_MODE)) { // axis relying on ACC
257 // 50 degrees max inclination
258 #ifdef GPS
259 errorAngle = constrain(2 * rcCommand[axis] + GPS_angle[axis], -((int) max_angle_inclination),
260 +max_angle_inclination) - inclination.raw[axis] + angleTrim->raw[axis];
261 #else
262 errorAngle = constrain(2 * rcCommand[axis], -((int) max_angle_inclination),
263 +max_angle_inclination) - inclination.raw[axis] + angleTrim->raw[axis];
264 #endif
266 errorAngleI[axis] = constrain(errorAngleI[axis] + errorAngle, -10000, +10000); // WindUp //16 bits is ok here
268 PTermACC = ((int32_t)errorAngle * pidProfile->P8[PIDLEVEL]) >> 7; // 32 bits is needed for calculation: errorAngle*P8 could exceed 32768 16 bits is ok for result
270 int16_t limit = pidProfile->D8[PIDLEVEL] * 5;
271 PTermACC = constrain(PTermACC, -limit, +limit);
273 ITermACC = ((int32_t)errorAngleI[axis] * pidProfile->I8[PIDLEVEL]) >> 12; // 32 bits is needed for calculation:10000*I8 could exceed 32768 16 bits is ok for result
275 ITerm = ITermACC + ((ITerm - ITermACC) * prop >> 9);
276 PTerm = PTermACC + ((PTerm - PTermACC) * prop >> 9);
279 PTerm -= ((int32_t)(gyroADC[axis] / 4) * dynP8[axis]) >> 6; // 32 bits is needed for calculation
281 // Pterm low pass
282 if (pidProfile->pterm_cut_hz) {
283 PTerm = filterApplyPt1(PTerm, &PTermState[axis], pidProfile->pterm_cut_hz, dT);
286 delta = (gyroADC[axis] - lastGyro[axis]) / 4; // 16 bits is ok here, the dif between 2 consecutive gyro reads is limited to 800
287 lastGyro[axis] = gyroADC[axis];
288 DTerm = delta1[axis] + delta2[axis] + delta;
289 delta2[axis] = delta1[axis];
290 delta1[axis] = delta;
292 // Dterm low pass
293 if (pidProfile->dterm_cut_hz) {
294 DTerm = filterApplyPt1(DTerm, &DTermState[axis], pidProfile->dterm_cut_hz, dT);
297 DTerm = ((int32_t)DTerm * dynD8[axis]) >> 5; // 32 bits is needed for calculation
299 axisPID[axis] = PTerm + ITerm - DTerm;
301 #ifdef GTUNE
302 if (FLIGHT_MODE(GTUNE_MODE) && ARMING_FLAG(ARMED)) {
303 calculate_Gtune(axis);
305 #endif
307 #ifdef BLACKBOX
308 axisPID_P[axis] = PTerm;
309 axisPID_I[axis] = ITerm;
310 axisPID_D[axis] = -DTerm;
311 #endif
314 //YAW
315 rc = (int32_t)rcCommand[FD_YAW] * (2 * controlRateConfig->rates[FD_YAW] + 30) >> 5;
316 #ifdef ALIENWII32
317 error = rc - gyroADC[FD_YAW];
318 #else
319 error = rc - (gyroADC[FD_YAW] / 4);
320 #endif
321 errorGyroI[FD_YAW] += (int32_t)error * pidProfile->I8[FD_YAW];
322 errorGyroI[FD_YAW] = constrain(errorGyroI[FD_YAW], 2 - ((int32_t)1 << 28), -2 + ((int32_t)1 << 28));
323 if (ABS(rc) > 50) errorGyroI[FD_YAW] = 0;
325 PTerm = (int32_t)error * pidProfile->P8[FD_YAW] >> 6; // TODO: Bitwise shift on a signed integer is not recommended
327 // Constrain YAW by D value if not servo driven in that case servolimits apply
328 if(motorCount >= 4 && pidProfile->yaw_p_limit < YAW_P_LIMIT_MAX) {
329 PTerm = constrain(PTerm, -pidProfile->yaw_p_limit, pidProfile->yaw_p_limit);
332 ITerm = constrain((int16_t)(errorGyroI[FD_YAW] >> 13), -GYRO_I_MAX, +GYRO_I_MAX);
334 axisPID[FD_YAW] = PTerm + ITerm;
336 #ifdef GTUNE
337 if (FLIGHT_MODE(GTUNE_MODE) && ARMING_FLAG(ARMED)) {
338 calculate_Gtune(FD_YAW);
340 #endif
342 #ifdef BLACKBOX
343 axisPID_P[FD_YAW] = PTerm;
344 axisPID_I[FD_YAW] = ITerm;
345 axisPID_D[FD_YAW] = 0;
346 #endif
349 static void pidMultiWiiRewrite(pidProfile_t *pidProfile, controlRateConfig_t *controlRateConfig, uint16_t max_angle_inclination,
350 rollAndPitchTrims_t *angleTrim, rxConfig_t *rxConfig)
352 UNUSED(rxConfig);
354 int32_t errorAngle;
355 int axis;
356 int32_t delta, deltaSum;
357 static int32_t delta1[3], delta2[3];
358 int32_t PTerm, ITerm, DTerm;
359 static int32_t lastError[3] = { 0, 0, 0 };
360 int32_t AngleRateTmp, RateError;
362 int8_t horizonLevelStrength = 100;
363 int32_t stickPosAil, stickPosEle, mostDeflectedPos;
365 if (FLIGHT_MODE(HORIZON_MODE)) {
367 // Figure out the raw stick positions
368 stickPosAil = getRcStickDeflection(FD_ROLL, rxConfig->midrc);
369 stickPosEle = getRcStickDeflection(FD_PITCH, rxConfig->midrc);
371 if(ABS(stickPosAil) > ABS(stickPosEle)){
372 mostDeflectedPos = ABS(stickPosAil);
374 else {
375 mostDeflectedPos = ABS(stickPosEle);
378 // Progressively turn off the horizon self level strength as the stick is banged over
379 horizonLevelStrength = (500 - mostDeflectedPos) / 5; // 100 at centre stick, 0 = max stick deflection
381 // Using Level D as a Sensitivity for Horizon. 0 more level to 255 more rate. Default value of 100 seems to work fine.
382 // For more rate mode increase D and slower flips and rolls will be possible
383 horizonLevelStrength = constrain((10 * (horizonLevelStrength - 100) * (10 * pidProfile->D8[PIDLEVEL] / 80) / 100) + 100, 0, 100);
386 // ----------PID controller----------
387 for (axis = 0; axis < 3; axis++) {
388 uint8_t rate = controlRateConfig->rates[axis];
390 // -----Get the desired angle rate depending on flight mode
391 if (axis == FD_YAW) { // YAW is always gyro-controlled (MAG correction is applied to rcCommand)
392 AngleRateTmp = (((int32_t)(rate + 27) * rcCommand[YAW]) >> 5);
393 } else {
394 // calculate error and limit the angle to max configured inclination
395 #ifdef GPS
396 errorAngle = constrain(2 * rcCommand[axis] + GPS_angle[axis], -((int) max_angle_inclination),
397 +max_angle_inclination) - inclination.raw[axis] + angleTrim->raw[axis]; // 16 bits is ok here
398 #else
399 errorAngle = constrain(2 * rcCommand[axis], -((int) max_angle_inclination),
400 +max_angle_inclination) - inclination.raw[axis] + angleTrim->raw[axis]; // 16 bits is ok here
401 #endif
403 if (!FLIGHT_MODE(ANGLE_MODE)) { //control is GYRO based (ACRO and HORIZON - direct sticks control is applied to rate PID
404 AngleRateTmp = ((int32_t)(rate + 27) * rcCommand[axis]) >> 4;
405 if (FLIGHT_MODE(HORIZON_MODE)) {
406 // mix up angle error to desired AngleRateTmp to add a little auto-level feel. horizonLevelStrength is scaled to the stick input
407 AngleRateTmp += (errorAngle * pidProfile->I8[PIDLEVEL] * horizonLevelStrength / 100) >> 4;
409 } else { // it's the ANGLE mode - control is angle based, so control loop is needed
410 AngleRateTmp = (errorAngle * pidProfile->P8[PIDLEVEL]) >> 4;
414 // --------low-level gyro-based PID. ----------
415 // Used in stand-alone mode for ACRO, controlled by higher level regulators in other modes
416 // -----calculate scaled error.AngleRates
417 // multiplication of rcCommand corresponds to changing the sticks scaling here
418 RateError = AngleRateTmp - (gyroADC[axis] / 4);
420 // -----calculate P component
421 PTerm = (RateError * pidProfile->P8[axis] * PIDweight[axis] / 100) >> 7;
423 // Pterm low pass
424 if (pidProfile->pterm_cut_hz) {
425 PTerm = filterApplyPt1(PTerm, &PTermState[axis], pidProfile->pterm_cut_hz, dT);
428 // -----calculate I component
429 // there should be no division before accumulating the error to integrator, because the precision would be reduced.
430 // Precision is critical, as I prevents from long-time drift. Thus, 32 bits integrator is used.
431 // Time correction (to avoid different I scaling for different builds based on average cycle time)
432 // is normalized to cycle time = 2048.
433 errorGyroI[axis] = errorGyroI[axis] + ((RateError * cycleTime) >> 11) * pidProfile->I8[axis];
435 // limit maximum integrator value to prevent WindUp - accumulating extreme values when system is saturated.
436 // I coefficient (I8) moved before integration to make limiting independent from PID settings
437 errorGyroI[axis] = constrain(errorGyroI[axis], (int32_t) - GYRO_I_MAX << 13, (int32_t) + GYRO_I_MAX << 13);
438 ITerm = errorGyroI[axis] >> 13;
440 //-----calculate D-term
441 delta = RateError - lastError[axis]; // 16 bits is ok here, the dif between 2 consecutive gyro reads is limited to 800
442 lastError[axis] = RateError;
444 // Correct difference by cycle time. Cycle time is jittery (can be different 2 times), so calculated difference
445 // would be scaled by different dt each time. Division by dT fixes that.
446 delta = (delta * ((uint16_t) 0xFFFF / (cycleTime >> 4))) >> 6;
447 // add moving average here to reduce noise
448 deltaSum = delta1[axis] + delta2[axis] + delta;
449 delta2[axis] = delta1[axis];
450 delta1[axis] = delta;
452 // Dterm delta low pass
453 if (pidProfile->dterm_cut_hz) {
454 deltaSum = filterApplyPt1(deltaSum, &DTermState[axis], pidProfile->dterm_cut_hz, dT);
457 DTerm = (deltaSum * pidProfile->D8[axis] * PIDweight[axis] / 100) >> 8;
459 // -----calculate total PID output
460 axisPID[axis] = PTerm + ITerm + DTerm;
462 #ifdef GTUNE
463 if (FLIGHT_MODE(GTUNE_MODE) && ARMING_FLAG(ARMED)) {
464 calculate_Gtune(axis);
466 #endif
468 #ifdef BLACKBOX
469 axisPID_P[axis] = PTerm;
470 axisPID_I[axis] = ITerm;
471 axisPID_D[axis] = DTerm;
472 #endif
476 void pidSetController(pidControllerType_e type)
478 switch (type) {
479 default:
480 case PID_CONTROLLER_MWREWRITE:
481 pid_controller = pidMultiWiiRewrite;
482 break;
483 case PID_CONTROLLER_LUX_FLOAT:
484 pid_controller = pidLuxFloat;
485 break;
486 case PID_CONTROLLER_MW23:
487 pid_controller = pidMultiWii23;