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/>.
20 #include "config/parameter_group.h"
21 #include "fc/runtime_config.h"
23 #define GYRO_SATURATION_LIMIT 1800 // 1800dps
24 #define PID_SUM_LIMIT_MIN 100
25 #define PID_SUM_LIMIT_MAX 1000
26 #define PID_SUM_LIMIT_DEFAULT 500
27 #define PID_SUM_LIMIT_YAW_DEFAULT 350
29 #define HEADING_HOLD_RATE_LIMIT_MIN 10
30 #define HEADING_HOLD_RATE_LIMIT_MAX 250
31 #define HEADING_HOLD_RATE_LIMIT_DEFAULT 90
33 #define FW_ITERM_THROW_LIMIT_DEFAULT 165
34 #define FW_ITERM_THROW_LIMIT_MIN 0
35 #define FW_ITERM_THROW_LIMIT_MAX 500
37 #define AXIS_ACCEL_MIN_LIMIT 50
39 #define HEADING_HOLD_ERROR_LPF_FREQ 2
42 FP-PID has been rescaled to match LuxFloat (and MWRewrite) from Cleanflight 1.13
44 #define FP_PID_RATE_FF_MULTIPLIER 31.0f
45 #define FP_PID_RATE_P_MULTIPLIER 31.0f
46 #define FP_PID_RATE_I_MULTIPLIER 4.0f
47 #define FP_PID_RATE_D_MULTIPLIER 1905.0f
48 #define FP_PID_RATE_D_FF_MULTIPLIER 7270.0f
49 #define FP_PID_LEVEL_P_MULTIPLIER 6.56f // Level P gain units is [1/sec] and angle error is [deg] => [deg/s]
50 #define FP_PID_YAWHOLD_P_MULTIPLIER 80.0f
52 #define MC_ITERM_RELAX_SETPOINT_THRESHOLD 40.0f
53 #define MC_ITERM_RELAX_CUTOFF_DEFAULT 15
55 #define ANTI_GRAVITY_THROTTLE_FILTER_CUTOFF 15 // The anti gravity throttle highpass filter cutoff
65 PID_SURFACE
, // n/a n/a
69 PID_POS_HEADING
,// n/a +
75 PID_TYPE_NONE
= 0, // Not used in the current platform/mixer/configuration
76 PID_TYPE_PID
, // Uses P, I and D terms
77 PID_TYPE_PIFF
, // Uses P, I and FF, ignoring D
78 PID_TYPE_AUTO
, // Autodetect
81 typedef struct pid8_s
{
88 typedef struct pidBank_s
{
89 pid8_t pid
[PID_ITEM_COUNT
];
103 typedef struct pidProfile_s
{
104 uint8_t pidControllerType
;
108 uint8_t dterm_lpf_type
; // Dterm LPF type: PT1, BIQUAD
109 uint16_t dterm_lpf_hz
;
111 uint8_t dterm_lpf2_type
; // Dterm LPF type: PT1, BIQUAD
112 uint16_t dterm_lpf2_hz
;
116 uint8_t heading_hold_rate_limit
; // Maximum rotation rate HEADING_HOLD mode can feed to yaw rate PID controller
118 uint8_t itermWindupPointPercent
; // Experimental ITerm windup threshold, percent of motor saturation
120 uint32_t axisAccelerationLimitYaw
; // Max rate of change of yaw angular rate setpoint (deg/s^2 = dps/s)
121 uint32_t axisAccelerationLimitRollPitch
; // Max rate of change of roll/pitch angular rate setpoint (deg/s^2 = dps/s)
123 int16_t max_angle_inclination
[ANGLE_INDEX_COUNT
]; // Max possible inclination (roll and pitch axis separately
125 uint16_t pidSumLimit
;
126 uint16_t pidSumLimitYaw
;
128 // Airplane-specific parameters
129 uint16_t fixedWingItermThrowLimit
;
130 float fixedWingReferenceAirspeed
; // Reference tuning airspeed for the airplane - the speed for which PID gains are tuned
131 float fixedWingCoordinatedYawGain
; // This is the gain of the yaw rate required to keep the yaw rate consistent with the turn rate for a coordinated turn.
132 float fixedWingItermLimitOnStickPosition
; //Do not allow Iterm to grow when stick position is above this point
134 uint8_t loiter_direction
; // Direction of loitering center point on right wing (clockwise - as before), or center point on left wing (counterclockwise)
135 float navVelXyDTermLpfHz
;
137 uint8_t iterm_relax_type
; // Specifies type of relax algorithm
138 uint8_t iterm_relax_cutoff
; // This cutoff frequency specifies a low pass filter which predicts average response of the quad to setpoint
139 uint8_t iterm_relax
; // Enable iterm suppression during stick input
142 float dBoostMaxAtAlleceleration
;
143 uint8_t dBoostGyroDeltaLpfHz
;
144 float antigravityGain
;
145 float antigravityAccelerator
;
146 uint8_t antigravityCutoff
;
148 uint16_t navFwPosHdgPidsumLimit
;
149 uint8_t controlDerivativeLpfHz
;
152 typedef struct pidAutotuneConfig_s
{
153 uint16_t fw_overshoot_time
; // Time [ms] to detect sustained overshoot
154 uint16_t fw_undershoot_time
; // Time [ms] to detect sustained undershoot
155 uint8_t fw_max_rate_threshold
; // Threshold [%] of max rate to consider autotune detection
156 uint8_t fw_ff_to_p_gain
; // FF to P gain (strength relationship) [%]
157 uint16_t fw_ff_to_i_time_constant
; // FF to I time (defines time for I to reach the same level of response as FF) [ms]
158 } pidAutotuneConfig_t
;
160 PG_DECLARE_PROFILE(pidProfile_t
, pidProfile
);
161 PG_DECLARE(pidAutotuneConfig_t
, pidAutotuneConfig
);
163 const pidBank_t
* pidBank(void);
164 pidBank_t
* pidBankMutable(void);
166 extern int16_t axisPID
[];
167 extern int32_t axisPID_P
[], axisPID_I
[], axisPID_D
[], axisPID_Setpoint
[];
170 bool pidInitFilters(void);
171 void pidResetErrorAccumulators(void);
172 void pidResetTPAFilter(void);
174 struct controlRateConfig_s
;
175 struct motorConfig_s
;
178 void schedulePidGainsUpdate(void);
179 void updatePIDCoefficients(float dT
);
180 void pidController(float dT
);
182 float pidRateToRcCommand(float rateDPS
, uint8_t rate
);
183 int16_t pidAngleToRcCommand(float angleDeciDegrees
, int16_t maxInclination
);
186 HEADING_HOLD_DISABLED
= 0,
187 HEADING_HOLD_UPDATE_HEADING
,
191 void updateHeadingHoldTarget(int16_t heading
);
192 void resetHeadingHoldTarget(int16_t heading
);
193 int16_t getHeadingHoldTarget(void);
195 void autotuneUpdateState(void);
196 void autotuneFixedWingUpdate(const flight_dynamics_index_t axis
, float desiredRateDps
, float reachedRateDps
, float pidOutput
);
198 pidType_e
pidIndexGetType(pidIndex_e pidIndex
);