Classes |
| struct | Gains |
| | Store gains in a struct to allow easier realtime buffer usage. More...
|
Public Member Functions |
| double | computeCommand (double error, ros::Duration dt) |
| | Set the PID error and compute the PID command with nonuniform time step size. The derivative error is computed from the change in the error and the timestep dt.
|
| double | computeCommand (double error, double error_dot, ros::Duration dt) |
| | Set the PID error and compute the PID command with nonuniform time step size. This also allows the user to pass in a precomputed derivative error.
|
| void | dynamicReconfigCallback (control_toolbox::ParametersConfig &config, uint32_t) |
| | Update the PID parameters from dynamics reconfigure.
|
| double | getCurrentCmd () |
| | Return current command for this PID controller.
|
| void | getCurrentPIDErrors (double *pe, double *ie, double *de) |
| | Return PID error terms for the controller.
|
| void | getGains (double &p, double &i, double &d, double &i_max, double &i_min) |
| | Get PID gains for the controller.
|
| Gains | getGains () |
| | Get PID gains for the controller.
|
| bool | init (const ros::NodeHandle &n, const bool quiet=false) |
| | Initialize PID with the parameters in a NodeHandle namespace Initializes dynamic reconfigure for PID gains.
|
| void | initDynamicReconfig (ros::NodeHandle &node) |
| | Start the dynamic reconfigure node and load the default values.
|
| bool | initParam (const std::string &prefix, const bool quiet=false) |
| | Initialize PID with the parameters in a namespace Initializes dynamic reconfigure for PID gains.
|
| void | initPid (double p, double i, double d, double i_max, double i_min) |
| | Zeros out Pid values and initialize Pid-gains and integral term limits Does not initialize dynamic reconfigure for PID gains.
|
| void | initPid (double p, double i, double d, double i_max, double i_min, const ros::NodeHandle &) |
| | Zeros out Pid values and initialize Pid-gains and integral term limits Initializes dynamic reconfigure for PID gains.
|
| bool | initXml (TiXmlElement *config) |
| | Initialize PID with the parameters in an XML element Initializes dynamic reconfigure for PID gains.
|
| Pid & | operator= (const Pid &source) |
| | Custom assignment operator Does not initialize dynamic reconfigure for PID gains.
|
| | Pid (double p=0.0, double i=0.0, double d=0.0, double i_max=0.0, double i_min=-0.0) |
| | Constructor, zeros out Pid values when created and initialize Pid-gains and integral term limits. Does not initialize dynamic reconfigure for PID gains.
|
| | Pid (const Pid &source) |
| | Copy constructor required for preventing mutexes from being copied.
|
| void | printValues () |
| | Print to console the current parameters.
|
| void | reset () |
| | Reset the state of this PID controller.
|
| void | setCurrentCmd (double cmd) |
| | Set current command for this PID controller.
|
| void | setGains (double p, double i, double d, double i_max, double i_min) |
| | Set PID gains for the controller.
|
| void | setGains (const Gains &gains) |
| | Set PID gains for the controller.
|
| void | updateDynamicReconfig () |
| | Set Dynamic Reconfigure's gains to Pid's values.
|
| void | updateDynamicReconfig (Gains gains_config) |
| void | updateDynamicReconfig (control_toolbox::ParametersConfig config) |
| ROS_DEPRECATED double | updatePid (double p_error, ros::Duration dt) |
| | Update the Pid loop with nonuniform time step size.
|
| ROS_DEPRECATED double | updatePid (double error, double error_dot, ros::Duration dt) |
| | Update the Pid loop with nonuniform time step size. This update call allows the user to pass in a precomputed derivative error.
|
| | ~Pid () |
| | Destructor of Pid class.
|
Private Types |
typedef
dynamic_reconfigure::Server
< control_toolbox::ParametersConfig > | DynamicReconfigServer |
Private Attributes |
| double | cmd_ |
| double | d_error_ |
| bool | dynamic_reconfig_initialized_ |
realtime_tools::RealtimeBuffer
< Gains > | gains_buffer_ |
| double | i_error_ |
| double | p_error_ |
| double | p_error_last_ |
| DynamicReconfigServer::CallbackType | param_reconfig_callback_ |
| boost::recursive_mutex | param_reconfig_mutex_ |
boost::shared_ptr
< DynamicReconfigServer > | param_reconfig_server_ |
A basic pid class.
This class implements a generic structure that can be used to create a wide range of pid controllers. It can function independently or be subclassed to provide more specific controls based on a particular control loop.
In particular, this class implements the standard pid equation:

where:
given:
-
.
ROS interface
- Parameters:
-
| p | Proportional gain |
| d | Derivative gain |
| i | Integral gain |
| i_clamp | Min/max bounds for the integral windup, the clamp is applied to the  |
Usage
To use the Pid class, you should first call some version of init() (in non-realtime) and then call updatePid() at every update step. For example:
control_toolbox::Pid pid;
pid.initPid(6.0, 1.0, 2.0, 0.3, -0.3);
double position_desi_ = 0.5;
...
ros::Time last_time = ros::Time::now();
while (true) {
ros::Time time = ros::Time::now();
double effort = pid.updatePid(currentPosition() - position_desi_, time - last_time);
last_time = time;
}
Definition at line 113 of file pid.h.