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"
22 #include "common/time.h"
24 #define GYRO_SATURATION_LIMIT 1800 // 1800dps
25 #define PID_SUM_LIMIT_MIN 100
26 #define PID_SUM_LIMIT_MAX 1000
27 #define PID_SUM_LIMIT_DEFAULT 500
28 #define PID_SUM_LIMIT_YAW_DEFAULT 400
30 #define HEADING_HOLD_RATE_LIMIT_MIN 10
31 #define HEADING_HOLD_RATE_LIMIT_MAX 250
32 #define HEADING_HOLD_RATE_LIMIT_DEFAULT 90
34 #define AXIS_ACCEL_MIN_LIMIT 50
36 #define HEADING_HOLD_ERROR_LPF_FREQ 2
39 FP-PID has been rescaled to match LuxFloat (and MWRewrite) from Cleanflight 1.13
41 #define FP_PID_RATE_FF_MULTIPLIER 31.0f
42 #define FP_PID_RATE_P_MULTIPLIER 31.0f
43 #define FP_PID_RATE_I_MULTIPLIER 4.0f
44 #define FP_PID_RATE_D_MULTIPLIER 1905.0f
45 #define FP_PID_RATE_D_FF_MULTIPLIER 7270.0f
46 #define FP_PID_LEVEL_P_MULTIPLIER 1.0f / 6.56f // Level P gain units is [1/sec] and angle error is [deg] => [deg/s]
47 #define FP_PID_YAWHOLD_P_MULTIPLIER 80.0f
49 #define MC_ITERM_RELAX_SETPOINT_THRESHOLD 40.0f
50 #define MC_ITERM_RELAX_CUTOFF_DEFAULT 15
52 #define ANTI_GRAVITY_THROTTLE_FILTER_CUTOFF 15 // The anti gravity throttle highpass filter cutoff
54 #define FIXED_WING_LEVEL_TRIM_DEADBAND_DEFAULT 5
56 #define TASK_AUX_RATE_HZ 100 //In Hz
66 PID_SURFACE
, // n/a n/a
70 PID_POS_HEADING
,// n/a +
76 PID_TYPE_NONE
= 0, // Not used in the current platform/mixer/configuration
77 PID_TYPE_PID
, // Uses P, I and D terms
78 PID_TYPE_PIFF
, // Uses P, I, D and FF
79 PID_TYPE_AUTO
, // Autodetect
82 typedef struct pid8_s
{
89 typedef struct pidBank_s
{
90 pid8_t pid
[PID_ITEM_COUNT
];
99 typedef struct pidProfile_s
{
100 uint8_t pidControllerType
;
104 uint8_t dterm_lpf_type
; // Dterm LPF type: PT1, BIQUAD
105 uint16_t dterm_lpf_hz
;
109 uint8_t heading_hold_rate_limit
; // Maximum rotation rate HEADING_HOLD mode can feed to yaw rate PID controller
111 uint8_t itermWindupPointPercent
; // Experimental ITerm windup threshold, percent of motor saturation
113 uint32_t axisAccelerationLimitYaw
; // Max rate of change of yaw angular rate setpoint (deg/s^2 = dps/s)
114 uint32_t axisAccelerationLimitRollPitch
; // Max rate of change of roll/pitch angular rate setpoint (deg/s^2 = dps/s)
116 int16_t max_angle_inclination
[ANGLE_INDEX_COUNT
]; // Max possible inclination (roll and pitch axis separately
118 uint16_t pidItermLimitPercent
;
120 // Airplane-specific parameters
121 float fixedWingReferenceAirspeed
; // Reference tuning airspeed for the airplane - the speed for which PID gains are tuned
122 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.
123 float fixedWingCoordinatedPitchGain
; // This is the gain of the pitch rate to keep the pitch angle constant during coordinated turns.
124 uint16_t fixedWingYawItermBankFreeze
; // Freeze yaw Iterm when bank angle is more than this many degrees
126 float navVelXyDTermLpfHz
;
127 uint8_t navVelXyDtermAttenuation
; // VEL_XY dynamic Dterm scale: Dterm will be attenuatedby this value (in percent) when UAV is traveling with more than navVelXyDtermAttenuationStart percents of max velocity
128 uint8_t navVelXyDtermAttenuationStart
; // VEL_XY dynamic Dterm scale: Dterm attenuation will begin at this percent of max velocity
129 uint8_t navVelXyDtermAttenuationEnd
; // VEL_XY dynamic Dterm scale: Dterm will be fully attenuated at this percent of max velocity
130 uint8_t iterm_relax_cutoff
; // This cutoff frequency specifies a low pass filter which predicts average response of the quad to setpoint
131 uint8_t iterm_relax
; // Enable iterm suppression during stick input
136 float dBoostMaxAtAlleceleration
;
137 uint8_t dBoostGyroDeltaLpfHz
;
140 #ifdef USE_ANTIGRAVITY
141 float antigravityGain
;
142 float antigravityAccelerator
;
143 uint8_t antigravityCutoff
;
146 uint16_t navFwPosHdgPidsumLimit
;
147 uint8_t controlDerivativeLpfHz
;
149 float fixedWingLevelTrim
;
150 float fixedWingLevelTrimGain
;
152 uint8_t fwAltControlResponseFactor
;
153 #ifdef USE_SMITH_PREDICTOR
154 float smithPredictorStrength
;
155 float smithPredictorDelay
;
156 uint16_t smithPredictorFilterHz
;
160 uint16_t fwItermLockTimeMaxMs
;
161 uint8_t fwItermLockRateLimit
;
162 uint8_t fwItermLockEngageThreshold
;
166 typedef struct pidAutotuneConfig_s
{
167 uint16_t fw_detect_time
; // Time [ms] to detect sustained undershoot or overshoot
168 uint8_t fw_min_stick
; // Minimum stick input required to update rates and gains
169 uint8_t fw_ff_to_p_gain
; // FF to P gain (strength relationship) [%]
170 uint8_t fw_p_to_d_gain
; // P to D gain (strength relationship) [%]
171 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]
172 uint8_t fw_rate_adjustment
; // Adjust rate settings during autotune?
173 uint8_t fw_max_rate_deflection
; // Percentage of max mixer output used for calculating the rates
174 } pidAutotuneConfig_t
;
180 } fw_autotune_rate_adjustment_e
;
182 PG_DECLARE_PROFILE(pidProfile_t
, pidProfile
);
183 PG_DECLARE(pidAutotuneConfig_t
, pidAutotuneConfig
);
185 const pidBank_t
* pidBank(void);
186 pidBank_t
* pidBankMutable(void);
188 extern int16_t axisPID
[];
189 extern int32_t axisPID_P
[], axisPID_I
[], axisPID_D
[], axisPID_F
[], axisPID_Setpoint
[];
192 bool pidInitFilters(void);
193 void pidResetErrorAccumulators(void);
194 void pidReduceErrorAccumulators(int8_t delta
, uint8_t axis
);
195 float getAxisIterm(uint8_t axis
);
196 float getTotalRateTarget(void);
197 void pidResetTPAFilter(void);
199 struct controlRateConfig_s
;
200 struct motorConfig_s
;
203 void schedulePidGainsUpdate(void);
204 void updatePIDCoefficients(void);
205 void pidController(float dT
);
207 float pidRateToRcCommand(float rateDPS
, uint8_t rate
);
208 int16_t pidAngleToRcCommand(float angleDeciDegrees
, int16_t maxInclination
);
211 HEADING_HOLD_DISABLED
= 0,
212 HEADING_HOLD_UPDATE_HEADING
,
216 void updateHeadingHoldTarget(int16_t heading
);
217 void resetHeadingHoldTarget(int16_t heading
);
218 int16_t getHeadingHoldTarget(void);
220 void autotuneUpdateState(void);
221 void autotuneFixedWingUpdate(const flight_dynamics_index_t axis
, float desiredRateDps
, float reachedRateDps
, float pidOutput
);
223 pidType_e
pidIndexGetType(pidIndex_e pidIndex
);
225 bool isFixedWingLevelTrimActive(void);
226 void updateFixedWingLevelTrim(timeUs_t currentTimeUs
);
227 float getFixedWingLevelTrim(void);
228 bool isAngleHoldLevel(void);
229 uint16_t getPidSumLimit(const flight_dynamics_index_t axis
);