sr_plain_pid.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 /*
36  Author: Melonee Wise
37  Contributors: Dave Coleman, Jonathan Bohren, Bob Holmberg, Wim Meeussen
38  Desc: Implements a standard proportional-integral-derivative controller
39 */
40 
42 #include <tinyxml.h>
43 #include <string>
44 #include <tuple>
45 
46 #include <boost/algorithm/clamp.hpp>
47 #include <boost/algorithm/minmax.hpp>
48 
49 namespace controller
50 {
51 
52 PlainPid::PlainPid(double p, double i, double d, double i_max, double i_min, bool antiwindup)
53 {
54  setGains(p, i, d, i_max, i_min, antiwindup);
55 
56  reset();
57 }
58 
60 {
61 }
62 
63 void PlainPid::initPid(double p, double i, double d, double i_max, double i_min, bool antiwindup)
64 {
65  setGains(p, i, d, i_max, i_min, antiwindup);
66 
67  reset();
68 }
69 
70 bool PlainPid::initParam(const std::string& prefix, const bool quiet)
71 {
72  ros::NodeHandle nh(prefix);
73  return init(nh, quiet);
74 }
75 
76 bool PlainPid::init(const ros::NodeHandle &node, const bool quiet)
77 {
78  ros::NodeHandle nh(node);
79 
80  Gains gains;
81 
82  // Load PID gains from parameter server
83  if (!nh.getParam("p", gains.p_gain_))
84  {
85  if (!quiet)
86  {
87  ROS_ERROR("No p gain specified for pid. Namespace: %s", nh.getNamespace().c_str());
88  }
89  return false;
90  }
91  // Only the P gain is required, the I and D gains are optional and default to 0:
92  nh.param("i", gains.i_gain_, 0.0);
93  nh.param("d", gains.d_gain_, 0.0);
94 
95  // Load integral clamp from param server or default to 0
96  double i_clamp;
97  nh.param("i_clamp", i_clamp, 0.0);
98  gains.i_max_ = std::abs(i_clamp);
99  gains.i_min_ = -std::abs(i_clamp);
100  if (nh.hasParam("i_clamp_min"))
101  {
102  nh.param("i_clamp_min", gains.i_min_, gains.i_min_); // use i_clamp_min parameter, otherwise keep -i_clamp
103  gains.i_min_ = -std::abs(gains.i_min_); // make sure the value is <= 0
104  }
105  if (nh.hasParam("i_clamp_max"))
106  {
107  nh.param("i_clamp_max", gains.i_max_, gains.i_max_); // use i_clamp_max parameter, otherwise keep i_clamp
108  gains.i_max_ = std::abs(gains.i_max_); // make sure the value is >= 0
109  }
110  nh.param("antiwindup", gains.antiwindup_, false);
111 
112  setGains(gains.p_gain_, gains.i_gain_, gains.d_gain_, gains.i_max_, gains.i_min_, gains.antiwindup_);
113 
114  reset();
115 
116  return true;
117 }
118 
119 bool PlainPid::initXml(TiXmlElement *config)
120 {
121  double i_clamp;
122  i_clamp = config->Attribute("iClamp") ? atof(config->Attribute("iClamp")) : 0.0;
123 
124  setGains(
125  config->Attribute("p") ? atof(config->Attribute("p")) : 0.0,
126  config->Attribute("i") ? atof(config->Attribute("i")) : 0.0,
127  config->Attribute("d") ? atof(config->Attribute("d")) : 0.0,
128  std::abs(i_clamp),
129  -std::abs(i_clamp),
130  config->Attribute("antiwindup") ? atof(config->Attribute("antiwindup")) : false);
131 
132  reset();
133 
134  return true;
135 }
136 
138 {
139  p_error_last_ = 0.0;
140  p_error_ = 0.0;
141  i_error_ = 0.0;
142  d_error_ = 0.0;
143  cmd_ = 0.0;
144 }
145 
146 void PlainPid::getGains(double &p, double &i, double &d, double &i_max, double &i_min)
147 {
148  bool antiwindup;
149  getGains(p, i, d, i_max, i_min, antiwindup);
150 }
151 
152 void PlainPid::getGains(double &p, double &i, double &d, double &i_max, double &i_min, bool &antiwindup)
153 {
154  p = pid_gains.p_gain_;
155  i = pid_gains.i_gain_;
156  d = pid_gains.d_gain_;
157  i_max = pid_gains.i_max_;
158  i_min = pid_gains.i_min_;
159  antiwindup = pid_gains.antiwindup_;
160 }
161 
162 void PlainPid::setGains(double p, double i, double d, double i_max, double i_min, bool antiwindup)
163 {
164  pid_gains.p_gain_ = p;
165  pid_gains.i_gain_ = i;
166  pid_gains.d_gain_ = d;
167  pid_gains.i_max_ = i_max;
168  pid_gains.i_min_ = i_min;
169  pid_gains.antiwindup_ = antiwindup;
170 }
171 
172 double PlainPid::computeCommand(double error, ros::Duration dt)
173 {
174  if (dt == ros::Duration(0.0) || std::isnan(error) || std::isinf(error))
175  return 0.0;
176 
177  double error_dot = d_error_;
178 
179  // Calculate the derivative error
180  if (dt.toSec() > 0.0)
181  {
182  error_dot = (error - p_error_last_) / dt.toSec();
183  p_error_last_ = error;
184  }
185 
186  return computeCommand(error, error_dot, dt);
187 }
188 
189 double PlainPid::updatePid(double error, ros::Duration dt)
190 {
191  return -computeCommand(error, dt);
192 }
193 
194 double PlainPid::computeCommand(double error, double error_dot, ros::Duration dt)
195 {
196  double p_term, d_term, i_term;
197  p_error_ = error; // this is error = target - state
198  d_error_ = error_dot;
199 
200  if (dt == ros::Duration(0.0) ||
201  std::isnan(error) ||
202  std::isinf(error) ||
203  std::isnan(error_dot) ||
204  std::isinf(error_dot))
205  return 0.0;
206 
207  // Calculate proportional contribution to command
208  p_term = pid_gains.p_gain_ * p_error_;
209 
210  // Calculate the integral of the position error
211  i_error_ += dt.toSec() * p_error_;
212 
214  {
215  // Prevent i_error_ from climbing higher than permitted by i_max_/i_min_
216  boost::tuple<double, double> bounds = boost::minmax<double>(pid_gains.i_min_ / pid_gains.i_gain_,
218  i_error_ = boost::algorithm::clamp(i_error_, bounds.get<0>(), bounds.get<1>());
219  }
220 
221  // Calculate integral contribution to command
222  i_term = pid_gains.i_gain_ * i_error_;
223 
224  if (!pid_gains.antiwindup_)
225  {
226  // Limit i_term so that the limit is meaningful in the output
227  i_term = boost::algorithm::clamp(i_term, pid_gains.i_min_, pid_gains.i_max_);
228  }
229 
230  // Calculate derivative contribution to command
231  d_term = pid_gains.d_gain_ * d_error_;
232 
233  // Compute the command
234  cmd_ = p_term + i_term + d_term;
235 
236  return cmd_;
237 }
238 
239 double PlainPid::updatePid(double error, double error_dot, ros::Duration dt)
240 {
241  return -computeCommand(error, error_dot, dt);
242 }
243 
244 void PlainPid::setCurrentCmd(double cmd)
245 {
246  cmd_ = cmd;
247 }
248 
250 {
251  return cmd_;
252 }
253 
254 void PlainPid::getCurrentPIDErrors(double *pe, double *ie, double *de)
255 {
256  *pe = p_error_;
257  *ie = i_error_;
258  *de = d_error_;
259 }
260 
262 {
263  ROS_INFO_STREAM_NAMED("pid", "Current Values of PID Class:\n"
264  << " P Gain: " << pid_gains.p_gain_ << "\n"
265  << " I Gain: " << pid_gains.i_gain_ << "\n"
266  << " D Gain: " << pid_gains.d_gain_ << "\n"
267  << " I_Max: " << pid_gains.i_max_ << "\n"
268  << " I_Min: " << pid_gains.i_min_ << "\n"
269  << " Antiwindup: " << pid_gains.antiwindup_ << "\n"
270  << " P_Error_Last: " << p_error_last_ << "\n"
271  << " P_Error: " << p_error_ << "\n"
272  << " I_Error: " << i_error_ << "\n"
273  << " D_Error: " << d_error_ << "\n"
274  << " Command: " << cmd_);
275 }
276 } // namespace controller
void setGains(double p, double i, double d, double i_max, double i_min, bool antiwindup=false)
Set PID gains for the controller.
~PlainPid()
Destructor of Pid class.
double computeCommand(double error, ros::Duration dt)
Set PID gains for the controller.
Gains pid_gains
Get PID gains for the controller.
#define ROS_INFO_STREAM_NAMED(name, args)
double getCurrentCmd()
Return current command for this PID controller.
ROS_DEPRECATED double updatePid(double p_error, ros::Duration dt)
Update the Pid loop with nonuniform time step size.
bool init(const ros::NodeHandle &n, const bool quiet=false)
Initialize PID with the parameters in a NodeHandle namespace Initializes dynamic reconfigure for PID ...
void getGains(double &p, double &i, double &d, double &i_max, double &i_min)
Get PID gains for the controller.
void getCurrentPIDErrors(double *pe, double *ie, double *de)
Return PID error terms for the controller.
bool param(const std::string &param_name, T &param_val, const T &default_val) const
const std::string & getNamespace() const
void initPid(double p, double i, double d, double i_max, double i_min, bool antiwindup=false)
Zeros out Pid values and initialize Pid-gains and integral term limits Does not initialize dynamic re...
void setCurrentCmd(double cmd)
Set current command for this PID controller.
void printValues()
Print to console the current parameters.
bool getParam(const std::string &key, std::string &s) const
Store gains in a struct to allow easier realtime buffer usage.
void reset()
Reset the state of this PID controller.
bool hasParam(const std::string &key) const
PlainPid(double p=0.0, double i=0.0, double d=0.0, double i_max=0.0, double i_min=-0.0, bool antiwindup=false)
Constructor, zeros out Pid values when created and initialize Pid-gains and integral term limits...
bool initXml(TiXmlElement *config)
Initialize PID with the parameters in an XML element Initializes dynamic reconfigure for PID gains...
#define ROS_ERROR(...)
bool initParam(const std::string &prefix, const bool quiet=false)
Initialize PID with the parameters in a namespace Initializes dynamic reconfigure for PID gains...


sr_mechanism_controllers
Author(s): Ugo Cupcic
autogenerated on Tue Oct 13 2020 03:55:58