APM:Libraries
PID.cpp
Go to the documentation of this file.
1 
4 #include <cmath>
5 
6 #include "PID.h"
7 #include <AP_HAL/AP_HAL.h>
8 #include <AP_Math/AP_Math.h>
9 
10 extern const AP_HAL::HAL& hal;
11 
13 
14  // @Param: P
15  // @DisplayName: PID Proportional Gain
16  // @Description: P Gain which produces an output value that is proportional to the current error value
17  AP_GROUPINFO("P", 0, PID, _kp, 0),
18 
19  // @Param: I
20  // @DisplayName: PID Integral Gain
21  // @Description: I Gain which produces an output that is proportional to both the magnitude and the duration of the error
22  AP_GROUPINFO("I", 1, PID, _ki, 0),
23 
24  // @Param: D
25  // @DisplayName: PID Derivative Gain
26  // @Description: D Gain which produces an output that is proportional to the rate of change of the error
27  AP_GROUPINFO("D", 2, PID, _kd, 0),
28 
29  // @Param: IMAX
30  // @DisplayName: PID Integral Maximum
31  // @Description: The maximum/minimum value that the I term can output
32  AP_GROUPINFO("IMAX", 3, PID, _imax, 0),
33 
35 };
36 
37 float PID::get_pid(float error, float scaler)
38 {
39  uint32_t tnow = AP_HAL::millis();
40  uint32_t dt = tnow - _last_t;
41  float output = 0;
42  float delta_time;
43 
44  if (_last_t == 0 || dt > 1000) {
45  dt = 0;
46 
47  // if this PID hasn't been used for a full second then zero
48  // the intergator term. This prevents I buildup from a
49  // previous fight mode from causing a massive return before
50  // the integrator gets a chance to correct itself
51  reset_I();
52  }
53  _last_t = tnow;
54 
55  delta_time = (float)dt / 1000.0f;
56 
57  // Compute proportional component
58  _pid_info.P = error * _kp;
59  output += _pid_info.P;
60 
61  // Compute derivative component if time has elapsed
62  if ((fabsf(_kd) > 0) && (dt > 0)) {
63  float derivative;
64 
65  if (isnan(_last_derivative)) {
66  // we've just done a reset, suppress the first derivative
67  // term as we don't want a sudden change in input to cause
68  // a large D output change
69  derivative = 0;
70  _last_derivative = 0;
71  } else {
72  derivative = (error - _last_error) / delta_time;
73  }
74 
75  // discrete low pass filter, cuts out the
76  // high frequency noise that can drive the controller crazy
77  float RC = 1/(2*M_PI*_fCut);
78  derivative = _last_derivative +
79  ((delta_time / (RC + delta_time)) *
80  (derivative - _last_derivative));
81 
82  // update state
85 
86  // add in derivative component
88  output += _pid_info.D;
89  }
90 
91  // scale the P and D components
92  output *= scaler;
93  _pid_info.D *= scaler;
94  _pid_info.P *= scaler;
95 
96  // Compute integral component if time has elapsed
97  if ((fabsf(_ki) > 0) && (dt > 0)) {
98  _integrator += (error * _ki) * scaler * delta_time;
99  if (_integrator < -_imax) {
100  _integrator = -_imax;
101  } else if (_integrator > _imax) {
102  _integrator = _imax;
103  }
105  output += _integrator;
106  }
107 
108  _pid_info.desired = output;
109  return output;
110 }
111 
112 void
114 {
115  _integrator = 0;
116  // we use NAN (Not A Number) to indicate that the last
117  // derivative value is not valid
118  _last_derivative = NAN;
119  _pid_info.I = 0;
120 }
121 
122 void PID::reset() {
123  memset(&_pid_info, 0, sizeof(_pid_info));
124  reset_I();
125 }
126 
127 void
129 {
130  _kp.load();
131  _ki.load();
132  _kd.load();
133  _imax.load();
134 }
135 
136 void
138 {
139  _kp.save();
140  _ki.save();
141  _kd.save();
142  _imax.save();
143 }
void load_gains()
Definition: PID.cpp:128
Generic PID algorithm, with EEPROM-backed storage of constants.
#define AP_GROUPINFO(name, idx, clazz, element, def)
Definition: AP_Param.h:102
AP_Float _kp
Definition: PID.h:104
float _integrator
integrator value
Definition: PID.h:109
static const uint8_t _fCut
Definition: PID.h:123
void save_gains()
Definition: PID.cpp:137
#define f(i)
Object managing one PID control.
Definition: PID.h:13
uint32_t millis()
Definition: system.cpp:157
void reset()
Reset the whole PID state.
Definition: PID.cpp:122
float _last_error
last error for derivative
Definition: PID.h:110
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Definition: AC_PID_test.cpp:14
DataFlash_Class::PID_Info _pid_info
Definition: PID.h:116
float _last_derivative
last derivative for low-pass filter
Definition: PID.h:111
void reset_I()
Definition: PID.cpp:113
AP_Int16 _imax
Definition: PID.h:107
float get_pid(float error, float scaler=1.0)
Definition: PID.cpp:37
AP_Float _kd
Definition: PID.h:106
#define error(fmt, args ...)
uint32_t _last_t
last time get_pid() was called in millis
Definition: PID.h:112
DerivativeFilter< float, 11 > derivative
Definition: Derivative.cpp:16
#define M_PI
Definition: definitions.h:10
static const struct AP_Param::GroupInfo var_info[]
Definition: PID.h:99
AP_Float _ki
Definition: PID.h:105
#define AP_GROUPEND
Definition: AP_Param.h:121