PidController.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2008, Willow Garage, Inc.
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of the Willow Garage nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
35 // Original version: Melonee Wise <mwise@willowgarage.com>
36 #include <cstdio>
38 #include <boost/math/special_functions/fpclassify.hpp>
39 
40 namespace youbot {
41 
42 PidController::PidController(double P, double I, double D, double I1, double I2) :
43  p_gain_(P), i_gain_(I), d_gain_(D), i_max_(I1), i_min_(I2)
44 {
45  p_error_last_ = 0.0;
46  p_error_ = 0.0;
47  d_error_ = 0.0;
48  i_error_ = 0.0;
49  cmd_ = 0.0;
50  last_i_error = 0.0;
51 }
52 
54 {
55 }
56 
57 void PidController::initPid(double P, double I, double D, double I1, double I2)
58 {
59  p_gain_ = P;
60  i_gain_ = I;
61  d_gain_ = D;
62  i_max_ = I1;
63  i_min_ = I2;
64 
65  reset();
66 }
67 
69 {
70  p_error_last_ = 0.0;
71  p_error_ = 0.0;
72  d_error_ = 0.0;
73  i_error_ = 0.0;
74  cmd_ = 0.0;
75 }
76 
77 void PidController::getGains(double &p, double &i, double &d, double &i_max, double &i_min)
78 {
79  p = p_gain_;
80  i = i_gain_;
81  d = d_gain_;
82  i_max = i_max_;
83  i_min = i_min_;
84 }
85 
86 void PidController::setGains(double P, double I, double D, double I1, double I2)
87 {
88  p_gain_ = P;
89  i_gain_ = I;
90  d_gain_ = D;
91  i_max_ = I1;
92  i_min_ = I2;
93 }
94 
95 
96 double PidController::updatePid(double error, boost::posix_time::time_duration dt)
97 {
98  double p_term, d_term, i_term;
99  p_error_ = error; //this is pError = pState-pTarget
100  double deltatime = (double)dt.total_microseconds()/1000.0; //in milli seconds
101 
102 
103  if (deltatime == 0.0 || boost::math::isnan(error) || boost::math::isinf(error))
104  return 0.0;
105 
106  // Calculate proportional contribution to command
107  p_term = p_gain_ * p_error_;
108 
109  // Calculate the integral error
110 
111  i_error_ = last_i_error + deltatime * p_error_;
112  last_i_error = deltatime * p_error_;
113 
114  //Calculate integral contribution to command
115  i_term = i_gain_ * i_error_;
116 
117  // Limit i_term so that the limit is meaningful in the output
118  if (i_term > i_max_)
119  {
120  i_term = i_max_;
121  i_error_=i_term/i_gain_;
122  }
123  else if (i_term < i_min_)
124  {
125  i_term = i_min_;
126  i_error_=i_term/i_gain_;
127  }
128 
129  // Calculate the derivative error
130  if (deltatime != 0)
131  {
132  d_error_ = (p_error_ - p_error_last_) / deltatime;
134  }
135  // Calculate derivative contribution to command
136  d_term = d_gain_ * d_error_;
137  cmd_ = -p_term - i_term - d_term;
138 
139  // printf(" p_error_ %lf i_error_ %lf p_term %lf i_term %lf dt %lf out %lf\n", p_error_, i_error_, p_term, i_term, deltatime, cmd_);
140 
141  return cmd_;
142 }
143 
144 
145 double PidController::updatePid(double error, double error_dot, boost::posix_time::time_duration dt)
146 {
147  double p_term, d_term, i_term;
148  p_error_ = error; //this is pError = pState-pTarget
149  d_error_ = error_dot;
150  double deltatime = (double)dt.total_microseconds()/1000.0; //in milli seconds
151 
152  if (deltatime == 0.0 || boost::math::isnan(error) || boost::math::isinf(error) || boost::math::isnan(error_dot) || boost::math::isinf(error_dot))
153  return 0.0;
154 
155 
156  // Calculate proportional contribution to command
157  p_term = p_gain_ * p_error_;
158 
159  // Calculate the integral error
160  i_error_ = last_i_error + deltatime * p_error_;
161  last_i_error = deltatime * p_error_;
162 
163  // i_error_ = i_error_ + deltatime * p_error_;
164  // printf("i_error_ %lf dt.fractional_seconds() %lf\n", i_error_, deltatime);
165 
166  //Calculate integral contribution to command
167  i_term = i_gain_ * i_error_;
168 
169  // Limit i_term so that the limit is meaningful in the output
170  if (i_term > i_max_)
171  {
172  i_term = i_max_;
173  i_error_=i_term/i_gain_;
174  }
175  else if (i_term < i_min_)
176  {
177  i_term = i_min_;
178  i_error_=i_term/i_gain_;
179  }
180 
181  // Calculate derivative contribution to command
182  d_term = d_gain_ * d_error_;
183  cmd_ = -p_term - i_term - d_term;
184 
185  return cmd_;
186 }
187 
188 
189 
191 {
192  cmd_ = cmd;
193 }
194 
196 {
197  return cmd_;
198 }
199 
200 void PidController::getCurrentPIDErrors(double& pe, double& ie, double& de)
201 {
202  pe = p_error_;
203  ie = i_error_;
204  de = d_error_;
205 }
206 
207 }
void setGains(double P, double I, double D, double i_max, double i_min)
Set PID gains for the controller.
void setCurrentCmd(double cmd)
Set current command for this PID controller.
double getCurrentCmd()
Return current command for this PID controller.
double updatePid(double p_error, boost::posix_time::time_duration dt)
Update the Pid loop with nonuniform time step size.
void getCurrentPIDErrors(double &pe, double &ie, double &de)
Return PID error terms for the controller.
~PidController()
Destructor of Pid class.
PidController(double P=0.0, double I=0.0, double D=0.0, double I1=0.0, double I2=-0.0)
Constructor, zeros out Pid values when created and initialize Pid-gains and integral term limits:[iMa...
void getGains(double &p, double &i, double &d, double &i_max, double &i_min)
Get PID gains for the controller.
void reset()
Reset the state of this PID controller.
void initPid(double P, double I, double D, double I1, double I2)
Initialize PID-gains and integral term limits:[iMax:iMin]-[I1:I2].


youbot_driver
Author(s): Jan Paulus
autogenerated on Mon Jun 10 2019 15:46:25