APM:Libraries
AC_PID.cpp
Go to the documentation of this file.
1 
4 #include <AP_Math/AP_Math.h>
5 #include "AC_PID.h"
6 
8  // @Param: P
9  // @DisplayName: PID Proportional Gain
10  // @Description: P Gain which produces an output value that is proportional to the current error value
11  AP_GROUPINFO("P", 0, AC_PID, _kp, 0),
12 
13  // @Param: I
14  // @DisplayName: PID Integral Gain
15  // @Description: I Gain which produces an output that is proportional to both the magnitude and the duration of the error
16  AP_GROUPINFO("I", 1, AC_PID, _ki, 0),
17 
18  // @Param: D
19  // @DisplayName: PID Derivative Gain
20  // @Description: D Gain which produces an output that is proportional to the rate of change of the error
21  AP_GROUPINFO("D", 2, AC_PID, _kd, 0),
22 
23  // 3 was for uint16 IMAX
24  // 4 is used by TradHeli for FF
25 
26  // @Param: IMAX
27  // @DisplayName: PID Integral Maximum
28  // @Description: The maximum/minimum value that the I term can output
29  AP_GROUPINFO("IMAX", 5, AC_PID, _imax, 0),
30 
31  // @Param: FILT
32  // @DisplayName: PID Input filter frequency in Hz
33  // @Description: Input filter frequency in Hz
34  // @Units: Hz
35  AP_GROUPINFO("FILT", 6, AC_PID, _filt_hz, AC_PID_FILT_HZ_DEFAULT),
36 
37  // @Param: FF
38  // @DisplayName: FF FeedForward Gain
39  // @Description: FF Gain which produces an output value that is proportional to the demanded input
40  AP_GROUPINFO("FF", 7, AC_PID, _ff, 0),
41 
43 };
44 
45 // Constructor
46 AC_PID::AC_PID(float initial_p, float initial_i, float initial_d, float initial_imax, float initial_filt_hz, float dt, float initial_ff) :
47  _dt(dt),
48  _integrator(0.0f),
49  _input(0.0f),
50  _derivative(0.0f)
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  _ff = initial_ff;
61 
62  // reset input filter to first value received
63  _flags._reset_filter = true;
64 
65  memset(&_pid_info, 0, sizeof(_pid_info));
66 }
67 
68 // set_dt - set time step in seconds
69 void AC_PID::set_dt(float dt)
70 {
71  // set dt and calculate the input filter alpha
72  _dt = dt;
73 }
74 
75 // filt_hz - set input filter hz
76 void AC_PID::filt_hz(float hz)
77 {
78  _filt_hz.set(fabsf(hz));
79 
80  // sanity check _filt_hz
82 }
83 
84 // set_input_filter_all - set input to PID controller
85 // input is filtered before the PID controllers are run
86 // this should be called before any other calls to get_p, get_i or get_d
88 {
89  // don't process inf or NaN
90  if (!isfinite(input)) {
91  return;
92  }
93 
94  // reset input filter to value received
95  if (_flags._reset_filter) {
96  _flags._reset_filter = false;
97  _input = input;
98  _derivative = 0.0f;
99  }
100 
101  // update filter and calculate derivative
102  float input_filt_change = get_filt_alpha() * (input - _input);
103  _input = _input + input_filt_change;
104  if (_dt > 0.0f) {
105  _derivative = input_filt_change / _dt;
106  }
107 }
108 
109 // set_input_filter_d - set input to PID controller
110 // only input to the D portion of the controller is filtered
111 // this should be called before any other calls to get_p, get_i or get_d
112 void AC_PID::set_input_filter_d(float input)
113 {
114  // don't process inf or NaN
115  if (!isfinite(input)) {
116  return;
117  }
118 
119  // reset input filter to value received
120  if (_flags._reset_filter) {
121  _flags._reset_filter = false;
122  _derivative = 0.0f;
123  }
124 
125  // update filter and calculate derivative
126  if (_dt > 0.0f) {
127  float derivative = (input - _input) / _dt;
128  _derivative = _derivative + get_filt_alpha() * (derivative-_derivative);
129  }
130 
131  _input = input;
132 }
133 
135 {
136  _pid_info.P = (_input * _kp);
137  return _pid_info.P;
138 }
139 
141 {
142  if(!is_zero(_ki) && !is_zero(_dt)) {
143  _integrator += ((float)_input * _ki) * _dt;
144  if (_integrator < -_imax) {
145  _integrator = -_imax;
146  } else if (_integrator > _imax) {
147  _integrator = _imax;
148  }
150  return _integrator;
151  }
152  return 0;
153 }
154 
156 {
157  // derivative component
158  _pid_info.D = (_kd * _derivative);
159  return _pid_info.D;
160 }
161 
162 float AC_PID::get_ff(float requested_rate)
163 {
164  _pid_info.FF = (float)requested_rate * _ff;
165  return _pid_info.FF;
166 }
167 
168 
170 {
171  return get_p() + get_i();
172 }
173 
175 {
176  return get_p() + get_i() + get_d();
177 }
178 
180 {
181  _integrator = 0;
182 }
183 
185 {
186  _kp.load();
187  _ki.load();
188  _kd.load();
189  _imax.load();
190  _imax = fabsf(_imax);
191  _filt_hz.load();
192 }
193 
194 // save_gains - save gains to eeprom
196 {
197  _kp.save();
198  _ki.save();
199  _kd.save();
200  _imax.save();
201  _filt_hz.save();
202 }
203 
205 void AC_PID::operator() (float p, float i, float d, float imaxval, float input_filt_hz, float dt, float ffval)
206 {
207  _kp = p;
208  _ki = i;
209  _kd = d;
210  _imax = fabsf(imaxval);
211  _filt_hz = input_filt_hz;
212  _dt = dt;
213  _ff = ffval;
214 }
215 
216 // calc_filt_alpha - recalculate the input filter alpha
218 {
219  if (is_zero(_filt_hz)) {
220  return 1.0f;
221  }
222 
223  // calculate alpha
224  float rc = 1/(M_2PI*_filt_hz);
225  return _dt / (_dt + rc);
226 }
AP_Float _imax
Definition: AC_PID.h:93
void save_gains()
Definition: AC_PID.cpp:195
float _integrator
Definition: AC_PID.h:104
struct AC_PID::ac_pid_flags _flags
AP_Float & filt_hz()
Definition: AC_PID.h:63
AC_PID(float initial_p, float initial_i, float initial_d, float initial_imax, float initial_filt_hz, float dt, float initial_ff=0)
Definition: AC_PID.cpp:46
Generic PID algorithm, with EEPROM-backed storage of constants.
AP_Float _kp
Definition: AC_PID.h:90
float _derivative
Definition: AC_PID.h:106
#define AP_GROUPINFO(name, idx, clazz, element, def)
Definition: AP_Param.h:102
float get_d()
Definition: AC_PID.cpp:155
AP_Float _kd
Definition: AC_PID.h:92
float get_pi()
Definition: AC_PID.cpp:169
void reset_I()
Definition: AC_PID.cpp:179
static RC_Channel * rc
Definition: RC_Channel.cpp:17
float _dt
Definition: AC_PID.h:103
static auto MAX(const A &one, const B &two) -> decltype(one > two ? one :two)
Definition: AP_Math.h:202
float get_filt_alpha() const
Definition: AC_PID.cpp:217
#define AC_PID_FILT_HZ_MIN
Definition: AC_PID.h:13
void set_input_filter_d(float input)
Definition: AC_PID.cpp:112
float _input
Definition: AC_PID.h:105
bool is_zero(const T fVal1)
Definition: AP_Math.h:40
#define f(i)
static const struct AP_Param::GroupInfo var_info[]
Definition: AC_PID.h:85
AP_Float _ki
Definition: AC_PID.h:91
#define M_2PI
Definition: definitions.h:19
float get_ff(float requested_rate)
Definition: AC_PID.cpp:162
AP_Float _ff
Definition: AC_PID.h:95
#define AC_PID_FILT_HZ_DEFAULT
Definition: AC_PID.h:12
void operator()(float p, float i, float d, float imaxval, float input_filt_hz, float dt, float ffval=0)
operator function call for easy initialisation
Definition: AC_PID.cpp:205
float get_pid()
Definition: AC_PID.cpp:174
void load_gains()
Definition: AC_PID.cpp:184
void set_dt(float dt)
Definition: AC_PID.cpp:69
void set_input_filter_all(float input)
Definition: AC_PID.cpp:87
AP_Float _filt_hz
Definition: AC_PID.h:94
DerivativeFilter< float, 11 > derivative
Definition: Derivative.cpp:16
float get_i()
Definition: AC_PID.cpp:140
Copter PID control class.
Definition: AC_PID.h:17
float get_p()
Definition: AC_PID.cpp:134
#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
DataFlash_Class::PID_Info _pid_info
Definition: AC_PID.h:108