simple_pid.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2017 Robert Leishman, BYU MAGICC Lab.
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * Redistributions of source code must retain the above copyright notice, this
9  * list of conditions and the following disclaimer.
10  *
11  * * Redistributions in binary form must reproduce the above copyright notice,
12  * this list of conditions and the following disclaimer in the documentation
13  * and/or other materials provided with the distribution.
14  *
15  * * Neither the name of the copyright holder nor the names of its
16  * contributors may be used to endorse or promote products derived from
17  * this software without specific prior written permission.
18  *
19  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
20  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
21  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
22  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
23  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
24  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
25  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
26  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
27  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
28  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
29  * POSSIBILITY OF SUCH DAMAGE.
30  */
31 
33 
34 namespace rosflight_utils
35 {
36 //
37 // Basic initialization
38 //
40 {
41  kp_ = 0.0;
42  ki_ = 0.0;
43  kd_ = 0.0;
44  integrator_ = 0.0;
45  differentiator_ = 0.0;
46  last_error_ = 0.0;
47  last_state_ = 0.0;
48  tau_ = 0.0;
49 }
50 
51 //
52 // Initialize the controller
53 //
54 SimplePID::SimplePID(double p, double i, double d, double max, double min, double tau) :
55  kp_(p), ki_(i), kd_(d), max_(max), min_(min), tau_(tau)
56 {
57  integrator_ = 0.0;
58  differentiator_ = 0.0;
59  last_error_ = 0.0;
60  last_state_ = 0.0;
61 }
62 
63 //
64 // Compute the control;
65 //
66 double SimplePID::computePID(double desired, double current, double dt, double x_dot)
67 {
68  double error = desired - current;
69 
70  // Don't do stupid things (like divide by nearly zero, gigantic control jumps)
71  if (dt < 0.00001 || std::abs(error) > 9999999)
72  {
73  return 0.0;
74  }
75 
76  if (dt > 1.0)
77  {
78  // This means that this is a ''stale'' controller and needs to be reset.
79  // This would happen if we have been operating in a different mode for a while
80  // and will result in some enormous integrator.
81  // Or, it means we are disarmed and shouldn't integrate
82  // Setting dt for this loop will mean that the integrator and dirty derivative
83  // doesn't do anything this time but will keep it from exploding.
84  dt = 0.0;
85  differentiator_ = 0.0;
86  }
87 
88  double p_term = error*kp_;
89  double i_term = 0.0;
90  double d_term = 0.0;
91 
92 
93  // Calculate Derivative Term
94  if (kd_ > 0.0)
95  {
96  if (std::isfinite(x_dot))
97  {
98  d_term = kd_ * x_dot;
99  }
100  else if (dt > 0.0)
101  {
102  // Noise reduction (See "Small Unmanned Aircraft". Chapter 6. Slide 31/33)
103  // d/dx w.r.t. error:: differentiator_ = (2*tau_ - dt)/(2*tau_ + dt)*differentiator_ + 2/(2*tau_ + dt)*(error -
104  // last_error_);
106  (2 * tau_ - dt) / (2 * tau_ + dt) * differentiator_ + 2 / (2 * tau_ + dt) * (current - last_state_);
107  d_term = kd_* differentiator_;
108  }
109  }
110 
111  // Calculate Integrator Term
112  if (ki_ > 0.0)
113  {
114  integrator_ += dt / 2 * (error + last_error_); // (trapezoidal rule)
115  i_term = ki_ * integrator_;
116  }
117 
118  // Save off this state for next loop
119  last_error_ = error;
120  last_state_ = current;
121 
122  // Sum three terms
123  double u = p_term + i_term - d_term;
124 
125  return u;
126 
127  // Integrator anti-windup
128 // double u_sat = saturate(u, min_, max_);
129 // if (u != u_sat && std::fabs(i_term) > fabs(u - p_term + d_term))
130 // {
131 // // If we are at the saturation limits, then make sure the integrator doesn't get
132 // // bigger if it won't do anything (except take longer to unwind). Just set it to the
133 // // largest value it could be to max out the control
134 // integrator_ = (u_sat - p_term + d_term) / ki_;
135 // }
136 
137 // return u_sat;
138 }
139 
140 
141 //
142 // Late initialization or redo
143 //
144 void SimplePID::setGains(double p, double i, double d, double tau)
145 {
147  kp_ = p;
148  ki_ = i;
149  kd_ = d;
150  tau_ = tau;
151 }
152 
153 } // namespace relative_nav
double ki_
the integral gain (zero if you don&#39;t want integral control)
Definition: simple_pid.h:109
double last_error_
the last p_error, for computing the derivative;
Definition: simple_pid.h:113
double differentiator_
used for noise reduced differentiation
Definition: simple_pid.h:112
This file defines a simple PID controller to be used by other classes to implement a PID control loop...
Definition: simple_pid.h:44
double tau_
the noise reduction term for the derivative
Definition: simple_pid.h:115
double last_state_
the last state, for computing the derivative;
Definition: simple_pid.h:114
SimplePID()
SimplePID is the basic initializer;.
Definition: simple_pid.cpp:39
double kd_
the derivative gain (zero if you don&#39;t want derivative control)
Definition: simple_pid.h:110
double max_
Maximum Output.
Definition: simple_pid.h:116
double kp_
the proportional gain
Definition: simple_pid.h:108
double integrator_
the integral of p_error
Definition: simple_pid.h:111
double min_
Minimum Output.
Definition: simple_pid.h:117
void setGains(double p, double i=0.0, double d=0.0, double tau=0.15)
setgains is used to set the gains for a controller after it&#39;s been initialized. It will rewrite whate...
Definition: simple_pid.cpp:144
double computePID(double desired, double current, double dt, double x_dot=INFINITY)
computePID computes the PID control for the given error and timestep (since the last control was comp...
Definition: simple_pid.cpp:66


rosflight_utils
Author(s):
autogenerated on Wed Jul 3 2019 20:00:31