Book a Demo!
CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutPoliciesSign UpSign In
Ardupilot
GitHub Repository: Ardupilot/ardupilot
Path: blob/master/libraries/AC_PID/AC_PID.cpp
9460 views
1
/// @file AC_PID.cpp
2
/// @brief General-purpose PID controller with input, error, and derivative filtering, plus slew rate limiting and EEPROM gain storage.
3
4
#include <AP_Math/AP_Math.h>
5
#include "AC_PID.h"
6
7
#define AC_PID_DEFAULT_NOTCH_ATTENUATION 40
8
9
const AP_Param::GroupInfo AC_PID::var_info[] = {
10
// @Param: P
11
// @DisplayName: PID Proportional Gain
12
// @Description: P Gain which produces an output value that is proportional to the current error value
13
AP_GROUPINFO_FLAGS_DEFAULT_POINTER("P", 0, AC_PID, _kp, default_kp),
14
15
// @Param: I
16
// @DisplayName: PID Integral Gain
17
// @Description: I Gain which produces an output that is proportional to both the magnitude and the duration of the error
18
AP_GROUPINFO_FLAGS_DEFAULT_POINTER("I", 1, AC_PID, _ki, default_ki),
19
20
// @Param: D
21
// @DisplayName: PID Derivative Gain
22
// @Description: D Gain which produces an output that is proportional to the rate of change of the error
23
AP_GROUPINFO_FLAGS_DEFAULT_POINTER("D", 2, AC_PID, _kd, default_kd),
24
25
// 3 was for uint16 IMAX
26
27
// @Param: FF
28
// @DisplayName: FF FeedForward Gain
29
// @Description: FF Gain which produces an output value that is proportional to the demanded input
30
AP_GROUPINFO_FLAGS_DEFAULT_POINTER("FF", 4, AC_PID, _kff, default_kff),
31
32
// @Param: IMAX
33
// @DisplayName: PID Integral Maximum
34
// @Description: The maximum/minimum value that the I term can output
35
AP_GROUPINFO_FLAGS_DEFAULT_POINTER("IMAX", 5, AC_PID, _kimax, default_kimax),
36
37
// 6 was for float FILT
38
39
// 7 is for float ILMI and FF
40
41
// index 8 was for AFF
42
43
// @Param: FLTT
44
// @DisplayName: PID Target filter frequency in Hz
45
// @Description: Low-pass filter frequency applied to the target input (Hz)
46
// @Units: Hz
47
AP_GROUPINFO_FLAGS_DEFAULT_POINTER("FLTT", 9, AC_PID, _filt_T_hz, default_filt_T_hz),
48
49
// @Param: FLTE
50
// @DisplayName: PID Error filter frequency in Hz
51
// @Description: Low-pass filter frequency applied to the error (Hz)
52
// @Units: Hz
53
AP_GROUPINFO_FLAGS_DEFAULT_POINTER("FLTE", 10, AC_PID, _filt_E_hz, default_filt_E_hz),
54
55
// @Param: FLTD
56
// @DisplayName: PID Derivative term filter frequency in Hz
57
// @Description: Low-pass filter frequency applied to the derivative (Hz)
58
// @Units: Hz
59
AP_GROUPINFO_FLAGS_DEFAULT_POINTER("FLTD", 11, AC_PID, _filt_D_hz, default_filt_D_hz),
60
61
// @Param: SMAX
62
// @DisplayName: Slew rate limit
63
// @Description: Sets an upper limit on the slew rate produced by the combined P and D gains. If the amplitude of the control action produced by the rate feedback exceeds this value, then the D+P gain is reduced to respect the limit. This limits the amplitude of high frequency oscillations caused by an excessive gain. The limit should be set to no more than 25% of the actuators maximum slew rate to allow for load effects. Note: The gain will not be reduced to less than 10% of the nominal value. A value of zero will disable this feature.
64
// @Range: 0 200
65
// @Increment: 0.5
66
// @User: Advanced
67
AP_GROUPINFO_FLAGS_DEFAULT_POINTER("SMAX", 12, AC_PID, _slew_rate_max, default_slew_rate_max),
68
69
// @Param: PDMX
70
// @DisplayName: PD sum maximum
71
// @Description: The maximum/minimum value that the sum of the P and D term can output
72
// @User: Advanced
73
AP_GROUPINFO("PDMX", 13, AC_PID, _kpdmax, 0),
74
75
// @Param: D_FF
76
// @DisplayName: PID Derivative FeedForward Gain
77
// @Description: FF D Gain which produces an output that is proportional to the rate of change of the target
78
// @Range: 0 0.02
79
// @Increment: 0.0001
80
// @User: Advanced
81
AP_GROUPINFO_FLAGS_DEFAULT_POINTER("D_FF", 14, AC_PID, _kdff, default_kdff),
82
83
#if AP_FILTER_ENABLED
84
// @Param: NTF
85
// @DisplayName: PID Target notch filter index
86
// @Description: PID Target notch filter index
87
// @Range: 1 8
88
// @User: Advanced
89
AP_GROUPINFO("NTF", 15, AC_PID, _notch_T_filter, 0),
90
91
// @Param: NEF
92
// @DisplayName: PID Error notch filter index
93
// @Description: PID Error notch filter index
94
// @Range: 1 8
95
// @User: Advanced
96
AP_GROUPINFO("NEF", 16, AC_PID, _notch_E_filter, 0),
97
#endif
98
99
AP_GROUPEND
100
};
101
102
// Constructor
103
AC_PID::AC_PID(float initial_p, float initial_i, float initial_d, float initial_ff, float initial_imax, float initial_filt_T_hz, float initial_filt_E_hz, float initial_filt_D_hz,
104
float initial_srmax, float initial_srtau, float initial_dff) :
105
default_kp(initial_p),
106
default_ki(initial_i),
107
default_kd(initial_d),
108
default_kff(initial_ff),
109
default_kdff(initial_dff),
110
default_kimax(initial_imax),
111
default_filt_T_hz(initial_filt_T_hz),
112
default_filt_E_hz(initial_filt_E_hz),
113
default_filt_D_hz(initial_filt_D_hz),
114
default_slew_rate_max(initial_srmax)
115
{
116
// load parameter values from eeprom
117
AP_Param::setup_object_defaults(this, var_info);
118
119
// this param is not in the table, so its default is no loaded in the call above
120
_slew_rate_tau.set(initial_srtau);
121
122
// reset input filter to first value received
123
_flags._reset_filter = true;
124
125
memset(&_pid_info, 0, sizeof(_pid_info));
126
127
// slew limit scaler allows for plane to use degrees/sec slew
128
// limit
129
_slew_limit_scale = 1;
130
}
131
132
// Sets the target low-pass filter frequency (Hz)
133
void AC_PID::set_filt_T_hz(float hz)
134
{
135
_filt_T_hz.set(fabsf(hz));
136
}
137
138
// Sets the error low-pass filter frequency (Hz)
139
void AC_PID::set_filt_E_hz(float hz)
140
{
141
_filt_E_hz.set(fabsf(hz));
142
}
143
144
// Sets the derivative low-pass filter frequency (Hz)
145
void AC_PID::set_filt_D_hz(float hz)
146
{
147
_filt_D_hz.set(fabsf(hz));
148
}
149
150
// slew_limit - set slew limit
151
void AC_PID::set_slew_limit(float smax)
152
{
153
_slew_rate_max.set(fabsf(smax));
154
}
155
156
// Configures optional notch filters for target and error signals using the given sample rate.
157
// Filters are dynamically allocated and validated via the AP_Filter API.
158
void AC_PID::set_notch_sample_rate(float sample_rate)
159
{
160
#if AP_FILTER_ENABLED
161
if (_notch_T_filter == 0 && _notch_E_filter == 0) {
162
return;
163
}
164
165
if (_notch_T_filter != 0) {
166
if (_target_notch == nullptr) {
167
_target_notch = NEW_NOTHROW NotchFilterFloat();
168
}
169
// Lookup filter definition and initialize if valid
170
AP_Filter* filter = AP::filters().get_filter(_notch_T_filter);
171
if (filter != nullptr && !filter->setup_notch_filter(*_target_notch, sample_rate)) {
172
delete _target_notch;
173
_target_notch = nullptr;
174
_notch_T_filter.set(0); // disable filter if setup fails
175
}
176
}
177
178
if (_notch_E_filter != 0) {
179
if (_error_notch == nullptr) {
180
_error_notch = NEW_NOTHROW NotchFilterFloat();
181
}
182
// Lookup filter definition and initialize if valid
183
AP_Filter* filter = AP::filters().get_filter(_notch_E_filter);
184
if (filter != nullptr && !filter->setup_notch_filter(*_error_notch, sample_rate)) {
185
delete _error_notch;
186
_error_notch = nullptr;
187
_notch_E_filter.set(0); // disable filter if setup fails
188
}
189
}
190
#endif
191
}
192
193
// Computes the PID output using a target and measurement input.
194
// Applies filters to the target and error, calculates the derivative and updates the integrator.
195
// If `limit` is true, the integrator is allowed to shrink but not grow.
196
float AC_PID::update_all(float target, float measurement, float dt, bool limit, float pd_scale, float i_scale)
197
{
198
// Return zero if input is invalid (NaN or infinite)
199
if (!isfinite(target) || !isfinite(measurement)) {
200
return 0.0f;
201
}
202
203
// Flag used for logging to indicate a filter reset occurred
204
_pid_info.reset = _flags._reset_filter;
205
// Reset filters to match the current input (first sample or after reset)
206
if (_flags._reset_filter) {
207
// Reset filters to match the current inputs
208
_flags._reset_filter = false;
209
210
// Reset target filter
211
_target = target;
212
#if AP_FILTER_ENABLED
213
if (_target_notch != nullptr) {
214
_target_notch->reset();
215
_target = _target_notch->apply(_target);
216
}
217
#endif
218
219
// Calculate error and reset error filter
220
_error = _target - measurement;
221
#if AP_FILTER_ENABLED
222
if (_error_notch != nullptr) {
223
_error_notch->reset();
224
_error = _error_notch->apply(_error);
225
}
226
#endif
227
// Clear derivative history to avoid spikes after reset
228
_derivative = 0.0f;
229
_target_derivative = 0.0f;
230
231
} else {
232
233
// Apply target filters
234
const float target_last = _target;
235
#if AP_FILTER_ENABLED
236
if (_target_notch != nullptr) {
237
// Allocate and set up target notch filter
238
target = _target_notch->apply(target);
239
}
240
#endif
241
// Apply first-order low-pass filter to target value
242
_target += get_filt_T_alpha(dt) * (target - _target);
243
244
// Calculate error and apply error filter
245
const float error_last = _error;
246
float error = _target - measurement;
247
#if AP_FILTER_ENABLED
248
if (_error_notch != nullptr) {
249
// Allocate and set up error notch filter
250
error = _error_notch->apply(error);
251
}
252
#endif
253
// apply notch filters before FTLD/FLTE to minimize shot noise
254
_error += get_filt_E_alpha(dt) * (error - _error);
255
256
if (is_positive(dt)) {
257
// Compute and low-pass filter the error derivative (D term)
258
float derivative = (_error - error_last) / dt;
259
_derivative += get_filt_D_alpha(dt) * (derivative - _derivative);
260
// Calculate target derivative for D_FF contribution
261
_target_derivative = (_target - target_last) / dt;
262
}
263
}
264
265
// Integrate error (with wind-up protection if limit is active)
266
// If limit is active, allow I-term to shrink but not grow
267
update_i(dt, limit, i_scale);
268
269
float P_out = (_error * _kp);
270
float D_out = (_derivative * _kd);
271
float I_out = _integrator;
272
273
// Calculate dynamic modifier to reduce P+D output based on slew rate limiter
274
_pid_info.Dmod = _slew_limiter.modifier((_pid_info.P + _pid_info.D) * _slew_limit_scale, dt);
275
_pid_info.slew_rate = _slew_limiter.get_slew_rate();
276
277
// This modifier is used to reduce control effort under fast transients
278
P_out *= _pid_info.Dmod;
279
D_out *= _pid_info.Dmod;
280
281
// scale pd output if required
282
P_out *= pd_scale;
283
D_out *= pd_scale;
284
285
_pid_info.PD_limit = false;
286
// Apply PD sum limit if enabled
287
if (is_positive(_kpdmax)) {
288
const float PD_sum_abs = fabsf(P_out + D_out);
289
if (PD_sum_abs > _kpdmax) {
290
const float pd_limit_scale = _kpdmax / PD_sum_abs;
291
P_out *= pd_limit_scale;
292
D_out *= pd_limit_scale;
293
_pid_info.PD_limit = true;
294
}
295
}
296
297
_pid_info.target = _target;
298
_pid_info.actual = measurement;
299
_pid_info.error = _error;
300
_pid_info.P = P_out;
301
_pid_info.D = D_out;
302
_pid_info.I = I_out;
303
_pid_info.limit = limit;
304
// Set I set flag for logging and clear
305
_pid_info.I_term_set = _flags._I_set;
306
_flags._I_set = false;
307
_pid_info.FF = _target * _kff;
308
_pid_info.DFF = _target_derivative * _kdff;
309
310
return P_out + D_out + I_out;
311
}
312
313
// Computes the PID output from an error input only (target assumed to be zero).
314
// Applies error filtering and updates the derivative and integrator.
315
// Target and measurement must be set separately for logging.
316
// todo: remove function when it is no longer used.
317
float AC_PID::update_error(float error, float dt, bool limit)
318
{
319
// don't process inf or NaN
320
if (!isfinite(error)) {
321
return 0.0f;
322
}
323
324
// Reuse update all code path, zero target and pass negative error as measurement
325
// Pass negative error as "measurement" so that error = target - measurement evaluates correctly
326
// Bypasses target filtering for legacy compatibility
327
_target = 0.0;
328
const float output = update_all(0.0, -error, dt, limit);
329
330
// Make sure logged target and actual are still 0 to maintain behaviour
331
_pid_info.target = 0.0;
332
_pid_info.actual = 0.0;
333
334
return output;
335
}
336
337
// Updates the integrator based on current error and dt.
338
// If `limit` is true, the integrator is only allowed to shrink to avoid wind-up.
339
// i_scale can be used to temporarily scale the updated I-term, by default is 1 - should not be set to 0
340
void AC_PID::update_i(float dt, bool limit, float i_scale)
341
{
342
if (!is_zero(_ki) && is_positive(dt)) {
343
// Allow integrator growth only if not limited, or if error opposes the integrator direction
344
if (!limit || ((is_positive(_integrator) && is_negative(_error)) || (is_negative(_integrator) && is_positive(_error)))) {
345
_integrator += ((float)_error * _ki) * i_scale * dt;
346
_integrator = constrain_float(_integrator, -_kimax, _kimax);
347
}
348
} else {
349
_integrator = 0.0f;
350
}
351
}
352
353
float AC_PID::get_p() const
354
{
355
return _pid_info.P;
356
}
357
358
float AC_PID::get_i() const
359
{
360
return _integrator;
361
}
362
363
float AC_PID::get_d() const
364
{
365
return _pid_info.D;
366
}
367
368
float AC_PID::get_ff() const
369
{
370
return _pid_info.FF + _pid_info.DFF;
371
}
372
373
float AC_PID::get_ff_component() const
374
{
375
return _pid_info.FF;
376
}
377
378
float AC_PID::get_dff_component() const
379
{
380
return _pid_info.DFF;
381
}
382
383
// Used to fully zero the I term between mode changes or initialization
384
void AC_PID::reset_I()
385
{
386
_flags._I_set = true;
387
_integrator = 0.0;
388
}
389
390
// Loads controller configuration from EEPROM, including gains and filter frequencies. (not used)
391
void AC_PID::load_gains()
392
{
393
_kp.load();
394
_ki.load();
395
_kd.load();
396
_kff.load();
397
_filt_T_hz.load();
398
_filt_E_hz.load();
399
_filt_D_hz.load();
400
}
401
402
// Saves controller configuration from EEPROM, including gains and filter frequencies. Used by autotune to save gains before tuning.
403
void AC_PID::save_gains()
404
{
405
_kp.save();
406
_ki.save();
407
_kd.save();
408
_kff.save();
409
_filt_T_hz.save();
410
_filt_E_hz.save();
411
_filt_D_hz.save();
412
}
413
414
// Returns alpha value for the target low-pass filter (based on filter frequency and dt)
415
float AC_PID::get_filt_T_alpha(float dt) const
416
{
417
return calc_lowpass_alpha_dt(dt, _filt_T_hz);
418
}
419
420
// Returns alpha value for the error low-pass filter (based on filter frequency and dt)
421
float AC_PID::get_filt_E_alpha(float dt) const
422
{
423
return calc_lowpass_alpha_dt(dt, _filt_E_hz);
424
}
425
426
// Returns alpha value for the derivative low-pass filter (based on filter frequency and dt)
427
float AC_PID::get_filt_D_alpha(float dt) const
428
{
429
return calc_lowpass_alpha_dt(dt, _filt_D_hz);
430
}
431
432
// Sets the integrator directly, clamped to the IMAX bounds. Also flags I-term as externally set.
433
void AC_PID::set_integrator(float integrator)
434
{
435
_flags._I_set = true;
436
_integrator = constrain_float(integrator, -_kimax, _kimax);
437
}
438
439
// Gradually adjust the integrator toward a desired value using a time constant.
440
// Typically used to "relax" the I-term in dynamic conditions.
441
void AC_PID::relax_integrator(float integrator, float dt, float time_constant)
442
{
443
integrator = constrain_float(integrator, -_kimax, _kimax);
444
if (is_positive(dt)) {
445
_flags._I_set = true;
446
_integrator = _integrator + (integrator - _integrator) * (dt / (dt + time_constant));
447
}
448
}
449
450