sr_plain_pid.hpp
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 #ifndef SR_MECHANISM_CONTROLLERS_SR_PLAIN_PID_HPP
36 #define SR_MECHANISM_CONTROLLERS_SR_PLAIN_PID_HPP
37 
38 
39 #include <string>
40 #include <ros/ros.h>
41 #include <control_msgs/PidState.h>
42 
43 class TiXmlElement;
44 
45 namespace controller
46 {
47 
48 /***************************************************/
108 /***************************************************/
109 
110 class PlainPid
111 {
112 public:
116  struct Gains
117  {
118  // Optional constructor for passing in values without antiwindup
119  Gains(double p, double i, double d, double i_max, double i_min)
120  : p_gain_(p),
121  i_gain_(i),
122  d_gain_(d),
123  i_max_(i_max),
124  i_min_(i_min),
125  antiwindup_(false)
126  {}
127  // Optional constructor for passing in values
128  Gains(double p, double i, double d, double i_max, double i_min, bool antiwindup)
129  : p_gain_(p),
130  i_gain_(i),
131  d_gain_(d),
132  i_max_(i_max),
133  i_min_(i_min),
134  antiwindup_(antiwindup)
135  {}
136  // Default constructor
138  : p_gain_(0.0),
139  i_gain_(0.0),
140  d_gain_(0.0),
141  i_max_(0.0),
142  i_min_(0.0),
143  antiwindup_(false)
144  {}
145  double p_gain_;
146  double i_gain_;
147  double d_gain_;
148  double i_max_;
149  double i_min_;
150  bool antiwindup_;
151  };
152 
164  PlainPid(double p = 0.0,
165  double i = 0.0,
166  double d = 0.0,
167  double i_max = 0.0,
168  double i_min = -0.0,
169  bool antiwindup = false);
170 
174  ~PlainPid();
175 
186  void initPid(double p, double i, double d, double i_max, double i_min, bool antiwindup = false);
187 
195  bool initParam(const std::string& prefix, const bool quiet = false);
196 
204  bool init(const ros::NodeHandle &n, const bool quiet = false);
205 
212  bool initXml(TiXmlElement *config);
213 
217  void reset();
218 
227  void getGains(double &p, double &i, double &d, double &i_max, double &i_min);
228  void getGains(double &p, double &i, double &d, double &i_max, double &i_min, bool &antiwindup);
229 
235 
244  void setGains(double p, double i, double d, double i_max, double i_min, bool antiwindup = false);
245 
250 // void setGains(const Gains &gains);
251 
262  double computeCommand(double error, ros::Duration dt);
263 
275  double computeCommand(double error, double error_dot, ros::Duration dt);
276 
289  ROS_DEPRECATED double updatePid(double p_error, ros::Duration dt);
290 
305  ROS_DEPRECATED double updatePid(double error, double error_dot, ros::Duration dt);
306 
310  void setCurrentCmd(double cmd);
311 
315  double getCurrentCmd();
316 
323  void getCurrentPIDErrors(double *pe, double *ie, double *de);
324 
325 
329  void printValues();
330 
331 private:
332  double p_error_last_;
333  double p_error_;
334  double i_error_;
335  double d_error_;
336  double cmd_;
337 };
338 } // namespace controller
339 #endif
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.
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.
Gains(double p, double i, double d, double i_max, double i_min, bool antiwindup)
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...
Gains(double p, double i, double d, double i_max, double i_min)
void setCurrentCmd(double cmd)
Set current command for this PID controller.
#define ROS_DEPRECATED
void printValues()
Print to console the current parameters.
Store gains in a struct to allow easier realtime buffer usage.
void reset()
Reset the state of this PID controller.
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...
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