TPA revisited; removed some irrelevant and redundant code
[betaflight.git] / src / main / flight / pid.c
blob9235a2a9e1980904b2a5477551c2ee5086dd34e3
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"
32 #include "drivers/accgyro.h"
33 #include "drivers/gyro_sync.h"
35 #include "sensors/sensors.h"
36 #include "sensors/gyro.h"
37 #include "sensors/acceleration.h"
39 #include "rx/rx.h"
41 #include "io/rc_controls.h"
42 #include "io/gps.h"
44 #include "flight/pid.h"
45 #include "flight/imu.h"
46 #include "flight/navigation_rewrite.h"
48 #include "config/runtime_config.h"
50 extern uint16_t cycleTime;
51 extern uint8_t motorCount;
52 extern bool motorLimitReached;
53 extern float dT;
55 int16_t axisPID[3];
57 #ifdef BLACKBOX
58 int32_t axisPID_P[3], axisPID_I[3], axisPID_D[3], axisPID_Setpoint[3];
59 #endif
61 // PIDweight is a scale factor for PIDs which is derived from the throttle and TPA setting, and 1 = 100% scale means no PID reduction
62 float PIDweight[3];
64 static float errorGyroIf[3] = { 0.0f, 0.0f, 0.0f };
65 static float errorGyroIfLimit[3] = { 0.0f, 0.0f, 0.0f };
67 void pidResetErrorGyro(void)
69 errorGyroIf[ROLL] = 0.0f;
70 errorGyroIf[PITCH] = 0.0f;
71 errorGyroIf[YAW] = 0.0f;
74 const angle_index_t rcAliasToAngleIndexMap[] = { AI_ROLL, AI_PITCH };
76 static filterStatePt1_t angleFilterState[2]; // Only ROLL and PITCH
77 static biquad_t deltaBiQuadState[3];
78 static bool deltaFilterInit = false;
80 float pidRcCommandToAngle(int16_t stick)
82 return stick * 2.0f;
85 int16_t pidAngleToRcCommand(float angleDeciDegrees)
87 return angleDeciDegrees / 2.0f;
90 float pidRcCommandToRate(int16_t stick, uint8_t rate)
92 // Map stick position from 200dps to 1200dps
93 return (float)((rate + 20) * stick) / 50.0f;
96 #define FP_PID_RATE_P_MULTIPLIER 40.0f
97 #define FP_PID_RATE_I_MULTIPLIER 40.0f
98 #define FP_PID_RATE_D_MULTIPLIER 4000.0f
99 #define FP_PID_LEVEL_P_MULTIPLIER 40.0f
101 void pidController(pidProfile_t *pidProfile, controlRateConfig_t *controlRateConfig, rxConfig_t *rxConfig)
103 UNUSED(rxConfig);
105 float horizonLevelStrength = 1;
106 static float rateErrorBuf[3][5] = { { 0 } };
107 int axis, n;
109 if (FLIGHT_MODE(HORIZON_MODE)) {
110 // Figure out the raw stick positions
111 const int32_t stickPosAil = ABS(getRcStickDeflection(FD_ROLL, rxConfig->midrc));
112 const int32_t stickPosEle = ABS(getRcStickDeflection(FD_PITCH, rxConfig->midrc));
113 const int32_t mostDeflectedPos = MAX(stickPosAil, stickPosEle);
115 // Progressively turn off the horizon self level strength as the stick is banged over
116 horizonLevelStrength = (float)(500 - mostDeflectedPos) / 500; // 1 at centre stick, 0 = max stick deflection
117 if(pidProfile->D8[PIDLEVEL] == 0){
118 horizonLevelStrength = 0;
119 } else {
120 horizonLevelStrength = constrainf(((horizonLevelStrength - 1) * (100.0f / pidProfile->D8[PIDLEVEL])) + 1, 0, 1);
124 for (axis = 0; axis < 3; axis++) {
125 float kP = pidProfile->P8[axis] / FP_PID_RATE_P_MULTIPLIER * PIDweight[axis];
126 float kI = pidProfile->I8[axis] / FP_PID_RATE_I_MULTIPLIER;
127 float kD = pidProfile->D8[axis] / FP_PID_RATE_D_MULTIPLIER * PIDweight[axis];
129 bool useIntegralComponent = (pidProfile->P8[axis] != 0) && (pidProfile->I8[axis] != 0);
131 float rateTarget; // rotation rate target (dps)
133 // Rate setpoint for ACRO and HORIZON modes
134 rateTarget = pidRcCommandToRate(rcCommand[axis], controlRateConfig->rates[axis]);
136 // Outer PID loop (ANGLE/HORIZON)
137 if ((axis != FD_YAW) && (FLIGHT_MODE(ANGLE_MODE) || FLIGHT_MODE(HORIZON_MODE))) {
138 float angleTarget = pidRcCommandToAngle(rcCommand[axis]);
139 float angleError = (constrain(angleTarget, -pidProfile->max_angle_inclination, +pidProfile->max_angle_inclination) - attitude.raw[axis]) / 10.0f;
141 // P[LEVEL] defines self-leveling strength (both for ANGLE and HORIZON modes)
142 if (FLIGHT_MODE(HORIZON_MODE)) {
143 rateTarget += angleError * (pidProfile->P8[PIDLEVEL] / FP_PID_LEVEL_P_MULTIPLIER) * horizonLevelStrength;
145 else {
146 rateTarget = angleError * (pidProfile->P8[PIDLEVEL] / FP_PID_LEVEL_P_MULTIPLIER);
149 // Apply simple LPF to rateTarget to make response less jerky
150 // Ideas behind this:
151 // 1) Attitude is updated at gyro rate, rateTarget for ANGLE mode is calculated from attitude
152 // 2) If this rateTarget is passed directly into gyro-base PID controller this effectively doubles the rateError. D-term that is calculated from error
153 // tend to amplify this even more. Moreover, this tend to respond to every slightest change in attitude making self-leveling jittery
154 // 3) Lowering LEVEL P can make the effects of (2) less visible, but this also slows down self-leveling.
155 // 4) Human pilot response to attitude change in RATE mode is fairly slow and smooth, human pilot doesn't compensate for each slightest change
156 // 5) (2) and (4) lead to a simple idea of adding a low-pass filter on rateTarget for ANGLE mode damping response to rapid attitude changes and smoothing
157 // out self-leveling reaction
158 if (pidProfile->I8[PIDLEVEL]) {
159 // I8[PIDLEVEL] is filter cutoff frequency (Hz). Practical values of filtering frequency is 5-10 Hz
160 rateTarget = filterApplyPt1(rateTarget, &angleFilterState[axis], pidProfile->I8[PIDLEVEL], dT);
164 // Limit desired rate to something gyro can measure reliably
165 rateTarget = constrainf(rateTarget, -GYRO_SATURATION_LIMIT, +GYRO_SATURATION_LIMIT);
167 // Inner PID loop - gyro-based control to reach rateTarget
168 float gyroRate = gyroADC[axis] * gyro.scale; // gyro output scaled to dps
169 float rateError = rateTarget - gyroRate;
171 // Calculate new P-term
172 float newPTerm = rateError * kP;
174 if((motorCount >= 4 && pidProfile->yaw_p_limit) && axis == YAW) {
175 newPTerm = constrain(newPTerm, -pidProfile->yaw_p_limit, pidProfile->yaw_p_limit);
178 // Calculate new D-term
179 // Shift old error values
180 for (n = 4; n > 0; n--) {
181 rateErrorBuf[axis][n] = rateErrorBuf[axis][n-1];
184 // Store new error value
185 rateErrorBuf[axis][0] = rateError;
187 // Calculate derivative using 5-point noise-robust differentiator by Pavel Holoborodko
188 float newDTerm = ((2 * (rateErrorBuf[axis][1] - rateErrorBuf[axis][3]) + (rateErrorBuf[axis][0] - rateErrorBuf[axis][4])) / (8 * dT)) * kD;
190 // Apply additional lowpass
191 if (pidProfile->dterm_lpf_hz) {
192 if (!deltaFilterInit) {
193 for (n = 0; n < 3; n++)
194 filterInitBiQuad(pidProfile->dterm_lpf_hz, &deltaBiQuadState[n], 0);
195 deltaFilterInit = true;
198 newDTerm = filterApplyBiQuad(newDTerm, &deltaBiQuadState[axis]);
201 // TODO: Get feedback from mixer on available correction range for each axis
202 float newOutput = newPTerm + errorGyroIf[axis] + newDTerm;
203 float newOutputLimited = constrainf(newOutput, -PID_MAX_OUTPUT, +PID_MAX_OUTPUT);
205 // Integrate only if we can do backtracking
206 if (useIntegralComponent) {
207 float kT = 2.0f / ((kP / kI) + (kD / kP));
208 errorGyroIf[axis] += (rateError * kI * dT) + ((newOutputLimited - newOutput) * kT * dT);
210 // Don't grow I-term if motors are at their limit
211 if (STATE(ANTI_WINDUP) || motorLimitReached) {
212 errorGyroIf[axis] = constrainf(errorGyroIf[axis], -errorGyroIfLimit[axis], errorGyroIfLimit[axis]);
213 } else {
214 errorGyroIfLimit[axis] = ABS(errorGyroIf[axis]);
216 } else {
217 errorGyroIf[axis] = 0;
220 axisPID[axis] = newOutputLimited;
222 debug[axis] = rateTarget;
224 #ifdef BLACKBOX
225 axisPID_P[axis] = newPTerm;
226 axisPID_I[axis] = errorGyroIf[axis];
227 axisPID_D[axis] = newDTerm;
228 axisPID_Setpoint[axis] = rateTarget;
229 #endif