APM:Libraries
AC_PID_2D.cpp
Go to the documentation of this file.
1 
4 #include <AP_Math/AP_Math.h>
5 #include "AC_PID_2D.h"
6 
7 #define AC_PID_2D_FILT_HZ_DEFAULT 20.0f // default input filter frequency
8 #define AC_PID_2D_FILT_HZ_MIN 0.01f // minimum input filter frequency
9 #define AC_PID_2D_FILT_D_HZ_DEFAULT 10.0f // default input filter frequency
10 #define AC_PID_2D_FILT_D_HZ_MIN 0.005f // minimum input filter frequency
11 
13  // @Param: P
14  // @DisplayName: PID Proportional Gain
15  // @Description: P Gain which produces an output value that is proportional to the current error value
16  AP_GROUPINFO("P", 0, AC_PID_2D, _kp, 0),
17 
18  // @Param: I
19  // @DisplayName: PID Integral Gain
20  // @Description: I Gain which produces an output that is proportional to both the magnitude and the duration of the error
21  AP_GROUPINFO("I", 1, AC_PID_2D, _ki, 0),
22 
23  // @Param: IMAX
24  // @DisplayName: PID Integral Maximum
25  // @Description: The maximum/minimum value that the I term can output
26  AP_GROUPINFO("IMAX", 2, AC_PID_2D, _imax, 0),
27 
28  // @Param: FILT
29  // @DisplayName: PID Input filter frequency in Hz
30  // @Description: Input filter frequency in Hz
31  // @Units: Hz
32  AP_GROUPINFO("FILT", 3, AC_PID_2D, _filt_hz, AC_PID_2D_FILT_HZ_DEFAULT),
33 
34  // @Param: D
35  // @DisplayName: PID Derivative Gain
36  // @Description: D Gain which produces an output that is proportional to the rate of change of the error
37  AP_GROUPINFO("D", 4, AC_PID_2D, _kd, 0),
38 
39  // @Param: D_FILT
40  // @DisplayName: D term filter frequency in Hz
41  // @Description: D term filter frequency in Hz
42  // @Units: Hz
43  AP_GROUPINFO("D_FILT", 5, AC_PID_2D, _filt_d_hz, AC_PID_2D_FILT_D_HZ_DEFAULT),
44 
46 };
47 
48 // Constructor
49 AC_PID_2D::AC_PID_2D(float initial_p, float initial_i, float initial_d, float initial_imax, float initial_filt_hz, float initial_filt_d_hz, float dt) :
50  _dt(dt)
51 {
52  // load parameter values from eeprom
54 
55  _kp = initial_p;
56  _ki = initial_i;
57  _kd = initial_d;
58  _imax = fabsf(initial_imax);
59  filt_hz(initial_filt_hz);
60  filt_d_hz(initial_filt_d_hz);
61 
62  // reset input filter to first value received
63  _flags._reset_filter = true;
64 }
65 
66 // set_dt - set time step in seconds
67 void AC_PID_2D::set_dt(float dt)
68 {
69  // set dt and calculate the input filter alpha
70  _dt = dt;
73 }
74 
75 // filt_hz - set input filter hz
76 void AC_PID_2D::filt_hz(float hz)
77 {
78  _filt_hz.set(fabsf(hz));
79 
80  // sanity check _filt_hz
82 
83  // calculate the input filter alpha
85 }
86 
87 // filt_d_hz - set input filter hz
88 void AC_PID_2D::filt_d_hz(float hz)
89 {
90  _filt_d_hz.set(fabsf(hz));
91 
92  // sanity check _filt_hz
94 
95  // calculate the input filter alpha
97 }
98 
99 // set_input - set input to PID controller
100 // input is filtered before the PID controllers are run
101 // this should be called before any other calls to get_p, get_i or get_d
102 void AC_PID_2D::set_input(const Vector2f &input)
103 {
104  // don't process inf or NaN
105  if (!isfinite(input.x) || !isfinite(input.y)) {
106  return;
107  }
108 
109  // reset input filter to value received
110  if (_flags._reset_filter) {
111  _flags._reset_filter = false;
112  _input = input;
113  }
114 
115  // update filter and calculate derivative
116  const Vector2f input_delta = (input - _input) * _filt_alpha;
117  _input += input_delta;
118 
119  set_input_filter_d(input_delta);
120 }
121 
122 // set_input_filter_d - set input to PID controller
123 // only input to the D portion of the controller is filtered
124 // this should be called before any other calls to get_p, get_i or get_d
125 void AC_PID_2D::set_input_filter_d(const Vector2f& input_delta)
126 {
127  // don't process inf or NaN
128  if (!isfinite(input_delta.x) && !isfinite(input_delta.y)) {
129  return;
130  }
131 
132  // reset input filter
133  if (_flags._reset_filter) {
134  _flags._reset_filter = false;
135  _derivative.x = 0.0f;
136  _derivative.y = 0.0f;
137  }
138 
139  // update filter and calculate derivative
140  if (is_positive(_dt)) {
141  const Vector2f derivative = input_delta / _dt;
142  const Vector2f delta_derivative = (derivative - _derivative) * _filt_alpha_d;
143  _derivative += delta_derivative;
144  }
145 }
146 
148 {
149  return (_input * _kp);
150 }
151 
153 {
154  if (!is_zero(_ki) && !is_zero(_dt)) {
155  _integrator += (_input * _ki) * _dt;
156  const float integrator_length = _integrator.length();
157  if ((integrator_length > _imax) && is_positive(integrator_length)) {
158  _integrator *= (_imax / integrator_length);
159  }
160  return _integrator;
161  }
162  return Vector2f();
163 }
164 
165 // get_i_shrink - get_i but do not allow integrator to grow in length (it may shrink)
167 {
168  if (!is_zero(_ki) && !is_zero(_dt)) {
169  const float integrator_length_orig = MIN(_integrator.length(), _imax);
170  _integrator += (_input * _ki) * _dt;
171  const float integrator_length_new = _integrator.length();
172  if ((integrator_length_new > integrator_length_orig) && is_positive(integrator_length_new)) {
173  _integrator *= (integrator_length_orig / integrator_length_new);
174  }
175  return _integrator;
176  }
177  return Vector2f();
178 }
179 
181 {
182  // derivative component
183  return Vector2f(_kd * _derivative.x, _kd * _derivative.y);
184 }
185 
187 {
188  return get_p() + get_i() + get_d();
189 }
190 
192 {
193  _integrator.zero();
194 }
195 
197 {
198  _kp.load();
199  _ki.load();
200  _kd.load();
201  _imax.load();
202  _imax = fabsf(_imax);
203  _filt_hz.load();
204  _filt_d_hz.load();
205 
206  // calculate the input filter alpha
207  calc_filt_alpha();
209 }
210 
211 // save_gains - save gains to eeprom
213 {
214  _kp.save();
215  _ki.save();
216  _kd.save();
217  _imax.save();
218  _filt_hz.save();
219  _filt_d_hz.save();
220 }
221 
222 // calc_filt_alpha - recalculate the input filter alpha
224 {
225  if (is_zero(_filt_hz)) {
226  _filt_alpha = 1.0f;
227  return;
228  }
229 
230  // calculate alpha
231  const float rc = 1/(M_2PI*_filt_hz);
232  _filt_alpha = _dt / (_dt + rc);
233 }
234 
235 // calc_filt_alpha - recalculate the input filter alpha
237 {
238  if (is_zero(_filt_d_hz)) {
239  _filt_alpha_d = 1.0f;
240  return;
241  }
242 
243  // calculate alpha
244  const float rc = 1/(M_2PI*_filt_d_hz);
245  _filt_alpha_d = _dt / (_dt + rc);
246 }
AP_Float _kp
Definition: AC_PID_2D.h:85
Vector2< float > Vector2f
Definition: vector2.h:239
Vector2f _derivative
Definition: AC_PID_2D.h:103
float filt_d_hz() const
Definition: AC_PID_2D.h:53
Vector2f get_p() const
Definition: AC_PID_2D.cpp:147
void set_input(const Vector2f &input)
Definition: AC_PID_2D.cpp:102
Vector2f _integrator
Definition: AC_PID_2D.h:101
#define AC_PID_2D_FILT_D_HZ_MIN
Definition: AC_PID_2D.cpp:10
#define AP_GROUPINFO(name, idx, clazz, element, def)
Definition: AP_Param.h:102
AP_Float _filt_d_hz
Definition: AC_PID_2D.h:90
bool is_positive(const T fVal1)
Definition: AP_Math.h:50
void calc_filt_alpha()
Definition: AC_PID_2D.cpp:223
static RC_Channel * rc
Definition: RC_Channel.cpp:17
AC_PID_2D(float initial_p, float initial_i, float initial_d, float initial_imax, float initial_filt_hz, float initial_filt_d_hz, float dt)
Definition: AC_PID_2D.cpp:49
float _filt_alpha
Definition: AC_PID_2D.h:99
Generic PID algorithm, with EEPROM-backed storage of constants.
#define MIN(a, b)
Definition: usb_conf.h:215
AP_Float _imax
Definition: AC_PID_2D.h:88
static auto MAX(const A &one, const B &two) -> decltype(one > two ? one :two)
Definition: AP_Math.h:202
Vector2f get_d()
Definition: AC_PID_2D.cpp:180
T y
Definition: vector2.h:37
Vector2f get_i_shrink()
Definition: AC_PID_2D.cpp:166
void set_dt(float dt)
Definition: AC_PID_2D.cpp:67
Vector2f _input
Definition: AC_PID_2D.h:102
static const struct AP_Param::GroupInfo var_info[]
Definition: AC_PID_2D.h:69
bool is_zero(const T fVal1)
Definition: AP_Math.h:40
float filt_hz() const
Definition: AC_PID_2D.h:51
void set_input_filter_d(const Vector2f &input_delta)
Definition: AC_PID_2D.cpp:125
AP_Float _kd
Definition: AC_PID_2D.h:87
void reset_I()
Definition: AC_PID_2D.cpp:191
void calc_filt_alpha_d()
Definition: AC_PID_2D.cpp:236
#define M_2PI
Definition: definitions.h:19
void load_gains()
Definition: AC_PID_2D.cpp:196
Vector2f get_pid()
Definition: AC_PID_2D.cpp:186
float _dt
Definition: AC_PID_2D.h:98
Vector2f get_i()
Definition: AC_PID_2D.cpp:152
float length(void) const
Definition: vector2.cpp:24
T x
Definition: vector2.h:37
Copter PID control class.
Definition: AC_PID_2D.h:13
AP_Float _ki
Definition: AC_PID_2D.h:86
AP_Float _filt_hz
Definition: AC_PID_2D.h:89
void zero()
Definition: vector2.h:125
void save_gains()
Definition: AC_PID_2D.cpp:212
float _filt_alpha_d
Definition: AC_PID_2D.h:100
struct AC_PID_2D::ac_pid_flags _flags
DerivativeFilter< float, 11 > derivative
Definition: Derivative.cpp:16
#define AC_PID_2D_FILT_D_HZ_DEFAULT
Definition: AC_PID_2D.cpp:9
#define AC_PID_2D_FILT_HZ_MIN
Definition: AC_PID_2D.cpp:8
#define AC_PID_2D_FILT_HZ_DEFAULT
Definition: AC_PID_2D.cpp:7
#define AP_GROUPEND
Definition: AP_Param.h:121
static void setup_object_defaults(const void *object_pointer, const struct GroupInfo *group_info)
Definition: AP_Param.cpp:1214