CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutSign UpSign In
Ardupilot

Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.

GitHub Repository: Ardupilot/ardupilot
Path: blob/master/libraries/AC_PID/AC_PID.cpp
Views: 1798
1
/// @file AC_PID.cpp
2
/// @brief Generic PID algorithm
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: Target filter frequency in 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: Error filter frequency in 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: Derivative filter frequency in 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
// filt_T_hz - set target filter hz
133
void AC_PID::set_filt_T_hz(float hz)
134
{
135
_filt_T_hz.set(fabsf(hz));
136
}
137
138
// filt_E_hz - set error filter hz
139
void AC_PID::set_filt_E_hz(float hz)
140
{
141
_filt_E_hz.set(fabsf(hz));
142
}
143
144
// filt_D_hz - set derivative filter 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
void AC_PID::set_notch_sample_rate(float sample_rate)
157
{
158
#if AP_FILTER_ENABLED
159
if (_notch_T_filter == 0 && _notch_E_filter == 0) {
160
return;
161
}
162
163
if (_notch_T_filter != 0) {
164
if (_target_notch == nullptr) {
165
_target_notch = NEW_NOTHROW NotchFilterFloat();
166
}
167
AP_Filter* filter = AP::filters().get_filter(_notch_T_filter);
168
if (filter != nullptr && !filter->setup_notch_filter(*_target_notch, sample_rate)) {
169
delete _target_notch;
170
_target_notch = nullptr;
171
_notch_T_filter.set(0);
172
}
173
}
174
175
if (_notch_E_filter != 0) {
176
if (_error_notch == nullptr) {
177
_error_notch = NEW_NOTHROW NotchFilterFloat();
178
}
179
AP_Filter* filter = AP::filters().get_filter(_notch_E_filter);
180
if (filter != nullptr && !filter->setup_notch_filter(*_error_notch, sample_rate)) {
181
delete _error_notch;
182
_error_notch = nullptr;
183
_notch_E_filter.set(0);
184
}
185
}
186
#endif
187
}
188
189
// update_all - set target and measured inputs to PID controller and calculate outputs
190
// target and error are filtered
191
// the derivative is then calculated and filtered
192
// the integral is then updated based on the setting of the limit flag
193
float AC_PID::update_all(float target, float measurement, float dt, bool limit, float boost)
194
{
195
// don't process inf or NaN
196
if (!isfinite(target) || !isfinite(measurement)) {
197
return 0.0f;
198
}
199
200
// reset input filter to value received
201
_pid_info.reset = _flags._reset_filter;
202
if (_flags._reset_filter) {
203
_flags._reset_filter = false;
204
205
// Reset target filter
206
_target = target;
207
#if AP_FILTER_ENABLED
208
if (_target_notch != nullptr) {
209
_target_notch->reset();
210
_target = _target_notch->apply(_target);
211
}
212
#endif
213
214
// Calculate error and reset error filter
215
_error = _target - measurement;
216
#if AP_FILTER_ENABLED
217
if (_error_notch != nullptr) {
218
_error_notch->reset();
219
_error = _error_notch->apply(_error);
220
}
221
#endif
222
// Zero derivatives
223
_derivative = 0.0f;
224
_target_derivative = 0.0f;
225
226
} else {
227
228
// Apply target filters
229
const float target_last = _target;
230
#if AP_FILTER_ENABLED
231
// apply notch filters before FTLD/FLTE to avoid shot noise
232
if (_target_notch != nullptr) {
233
target = _target_notch->apply(target);
234
}
235
#endif
236
_target += get_filt_T_alpha(dt) * (target - _target);
237
238
// Calculate error and apply error filter
239
const float error_last = _error;
240
float error = _target - measurement;
241
#if AP_FILTER_ENABLED
242
if (_error_notch != nullptr) {
243
error = _error_notch->apply(error);
244
}
245
#endif
246
_error += get_filt_E_alpha(dt) * (error - _error);
247
248
// calculate and filter derivative
249
if (is_positive(dt)) {
250
float derivative = (_error - error_last) / dt;
251
_derivative += get_filt_D_alpha(dt) * (derivative - _derivative);
252
_target_derivative = (_target - target_last) / dt;
253
}
254
}
255
256
// update I term
257
update_i(dt, limit);
258
259
float P_out = (_error * _kp);
260
float D_out = (_derivative * _kd);
261
262
// calculate slew limit modifier for P+D
263
_pid_info.Dmod = _slew_limiter.modifier((_pid_info.P + _pid_info.D) * _slew_limit_scale, dt);
264
_pid_info.slew_rate = _slew_limiter.get_slew_rate();
265
266
P_out *= _pid_info.Dmod;
267
D_out *= _pid_info.Dmod;
268
269
// boost output if required
270
P_out *= boost;
271
D_out *= boost;
272
273
_pid_info.PD_limit = false;
274
// Apply PD sum limit if enabled
275
if (is_positive(_kpdmax)) {
276
const float PD_sum_abs = fabsf(P_out + D_out);
277
if (PD_sum_abs > _kpdmax) {
278
const float PD_scale = _kpdmax / PD_sum_abs;
279
P_out *= PD_scale;
280
D_out *= PD_scale;
281
_pid_info.PD_limit = true;
282
}
283
}
284
285
_pid_info.target = _target;
286
_pid_info.actual = measurement;
287
_pid_info.error = _error;
288
_pid_info.P = P_out;
289
_pid_info.D = D_out;
290
_pid_info.FF = _target * _kff;
291
_pid_info.DFF = _target_derivative * _kdff;
292
293
return P_out + D_out + _integrator;
294
}
295
296
// update_error - set error input to PID controller and calculate outputs
297
// target is set to zero and error is set and filtered
298
// the derivative then is calculated and filtered
299
// the integral is then updated based on the setting of the limit flag
300
// Target and Measured must be set manually for logging purposes.
301
// todo: remove function when it is no longer used.
302
float AC_PID::update_error(float error, float dt, bool limit)
303
{
304
// don't process inf or NaN
305
if (!isfinite(error)) {
306
return 0.0f;
307
}
308
309
// Reuse update all code path, zero target and pass negative error as measurement
310
// Passing as measurement bypasses any target filtering to maintain behaviour
311
// Negate as update all calculates error as target - measurement
312
_target = 0.0;
313
const float output = update_all(0.0, -error, dt, limit);
314
315
// Make sure logged target and actual are still 0 to maintain behaviour
316
_pid_info.target = 0.0;
317
_pid_info.actual = 0.0;
318
319
return output;
320
}
321
322
// update_i - update the integral
323
// If the limit flag is set the integral is only allowed to shrink
324
void AC_PID::update_i(float dt, bool limit)
325
{
326
if (!is_zero(_ki) && is_positive(dt)) {
327
// Ensure that integrator can only be reduced if the output is saturated
328
if (!limit || ((is_positive(_integrator) && is_negative(_error)) || (is_negative(_integrator) && is_positive(_error)))) {
329
_integrator += ((float)_error * _ki) * dt;
330
_integrator = constrain_float(_integrator, -_kimax, _kimax);
331
}
332
} else {
333
_integrator = 0.0f;
334
}
335
_pid_info.I = _integrator;
336
_pid_info.limit = limit;
337
338
// Set I set flag for logging and clear
339
_pid_info.I_term_set = _flags._I_set;
340
_flags._I_set = false;
341
}
342
343
float AC_PID::get_p() const
344
{
345
return _pid_info.P;
346
}
347
348
float AC_PID::get_i() const
349
{
350
return _integrator;
351
}
352
353
float AC_PID::get_d() const
354
{
355
return _pid_info.D;
356
}
357
358
float AC_PID::get_ff() const
359
{
360
return _pid_info.FF + _pid_info.DFF;
361
}
362
363
void AC_PID::reset_I()
364
{
365
_flags._I_set = true;
366
_integrator = 0.0;
367
}
368
369
// load original gains from eeprom, used by autotune to restore gains after tuning
370
void AC_PID::load_gains()
371
{
372
_kp.load();
373
_ki.load();
374
_kd.load();
375
_kff.load();
376
_filt_T_hz.load();
377
_filt_E_hz.load();
378
_filt_D_hz.load();
379
}
380
381
// save original gains to eeprom, used by autotune to save gains before tuning
382
void AC_PID::save_gains()
383
{
384
_kp.save();
385
_ki.save();
386
_kd.save();
387
_kff.save();
388
_filt_T_hz.save();
389
_filt_E_hz.save();
390
_filt_D_hz.save();
391
}
392
393
// get_filt_T_alpha - get the target filter alpha
394
float AC_PID::get_filt_T_alpha(float dt) const
395
{
396
return calc_lowpass_alpha_dt(dt, _filt_T_hz);
397
}
398
399
// get_filt_E_alpha - get the error filter alpha
400
float AC_PID::get_filt_E_alpha(float dt) const
401
{
402
return calc_lowpass_alpha_dt(dt, _filt_E_hz);
403
}
404
405
// get_filt_D_alpha - get the derivative filter alpha
406
float AC_PID::get_filt_D_alpha(float dt) const
407
{
408
return calc_lowpass_alpha_dt(dt, _filt_D_hz);
409
}
410
411
void AC_PID::set_integrator(float integrator)
412
{
413
_flags._I_set = true;
414
_integrator = constrain_float(integrator, -_kimax, _kimax);
415
}
416
417
void AC_PID::relax_integrator(float integrator, float dt, float time_constant)
418
{
419
integrator = constrain_float(integrator, -_kimax, _kimax);
420
if (is_positive(dt)) {
421
_flags._I_set = true;
422
_integrator = _integrator + (integrator - _integrator) * (dt / (dt + time_constant));
423
}
424
}
425
426