Classes | Public Member Functions | Private Types | Private Attributes
control_toolbox::Pid Class Reference

A basic pid class. More...

#include <pid.h>

List of all members.

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 level)
 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)
 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)
 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 &node)
 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.
Pidoperator= (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_term_
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_

Detailed Description

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:

$command = -p_{term} - i_{term} - d_{term} $

where:

given:

ROS interface

Parameters:
pProportional gain
dDerivative gain
iIntegral gain
i_clampMin/max bounds for the integral windup, the clamp is applied to the $i_{term}$

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.


Member Typedef Documentation

typedef dynamic_reconfigure::Server<control_toolbox::ParametersConfig> control_toolbox::Pid::DynamicReconfigServer [private]

Definition at line 377 of file pid.h.


Constructor & Destructor Documentation

control_toolbox::Pid::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.

Parameters:
pThe proportional gain.
iThe integral gain.
dThe derivative gain.
i_maxThe max integral windup.
i_minThe min integral windup.

Definition at line 48 of file pid.cpp.

control_toolbox::Pid::Pid ( const Pid source)

Copy constructor required for preventing mutexes from being copied.

Parameters:
source- Pid to copy

Definition at line 56 of file pid.cpp.

Destructor of Pid class.

Definition at line 66 of file pid.cpp.


Member Function Documentation

double control_toolbox::Pid::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.

Parameters:
errorError since last call (error = target - state)
dtChange in time since last call
Returns:
PID command

Definition at line 254 of file pid.cpp.

double control_toolbox::Pid::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.

Parameters:
errorError since last call (error = target - state)
error_dotd(Error)/dt since last call
dtChange in time since last call
Returns:
PID command

Definition at line 320 of file pid.cpp.

void control_toolbox::Pid::dynamicReconfigCallback ( control_toolbox::ParametersConfig &  config,
uint32_t  level 
)

Update the PID parameters from dynamics reconfigure.

Definition at line 246 of file pid.cpp.

Return current command for this PID controller.

Definition at line 383 of file pid.cpp.

void control_toolbox::Pid::getCurrentPIDErrors ( double *  pe,
double *  ie,
double *  de 
)

Return PID error terms for the controller.

Parameters:
peThe proportional error.
ieThe integral error.
deThe derivative error.

Definition at line 388 of file pid.cpp.

void control_toolbox::Pid::getGains ( double &  p,
double &  i,
double &  d,
double &  i_max,
double &  i_min 
)

Get PID gains for the controller.

Parameters:
pThe proportional gain.
iThe integral gain.
dThe derivative gain.
i_maxThe max integral windup.
i_minThe min integral windup.

Definition at line 170 of file pid.cpp.

Get PID gains for the controller.

Returns:
gains A struct of the PID gain values

Definition at line 181 of file pid.cpp.

Initialize PID with the parameters in a NodeHandle namespace Initializes dynamic reconfigure for PID gains.

Parameters:
nThe NodeHandle which should be used to query parameters.

Definition at line 93 of file pid.cpp.

Start the dynamic reconfigure node and load the default values.

Parameters:
node- a node handle where dynamic reconfigure services will be published

Definition at line 144 of file pid.cpp.

bool control_toolbox::Pid::initParam ( const std::string &  prefix)

Initialize PID with the parameters in a namespace Initializes dynamic reconfigure for PID gains.

Parameters:
prefixThe namespace prefix.

Definition at line 87 of file pid.cpp.

void control_toolbox::Pid::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.

Parameters:
pThe proportional gain.
iThe integral gain.
dThe derivative gain.
i_maxThe max integral windup.
i_minThe min integral windup.

Definition at line 80 of file pid.cpp.

void control_toolbox::Pid::initPid ( double  p,
double  i,
double  d,
double  i_max,
double  i_min,
const ros::NodeHandle node 
)

Zeros out Pid values and initialize Pid-gains and integral term limits Initializes dynamic reconfigure for PID gains.

Parameters:
pThe proportional gain.
iThe integral gain.
dThe derivative gain.
i_maxThe max integral windup.
i_minThe min integral windup.

Definition at line 70 of file pid.cpp.

bool control_toolbox::Pid::initXml ( TiXmlElement *  config)

Initialize PID with the parameters in an XML element Initializes dynamic reconfigure for PID gains.

Parameters:
configthe XML element

Definition at line 122 of file pid.cpp.

Pid& control_toolbox::Pid::operator= ( const Pid source) [inline]

Custom assignment operator Does not initialize dynamic reconfigure for PID gains.

Definition at line 349 of file pid.h.

Print to console the current parameters.

Definition at line 398 of file pid.cpp.

Reset the state of this PID controller.

Definition at line 161 of file pid.cpp.

Set current command for this PID controller.

Definition at line 378 of file pid.cpp.

void control_toolbox::Pid::setGains ( double  p,
double  i,
double  d,
double  i_max,
double  i_min 
)

Set PID gains for the controller.

Parameters:
pThe proportional gain.
iThe integral gain.
dThe derivative gain.
i_maxThe max integral windup.
i_minThe min integral windup.

Definition at line 186 of file pid.cpp.

void control_toolbox::Pid::setGains ( const Gains gains)

Set PID gains for the controller.

Parameters:
gainsA struct of the PID gain values

Definition at line 193 of file pid.cpp.

Set Dynamic Reconfigure's gains to Pid's values.

Definition at line 201 of file pid.cpp.

Definition at line 216 of file pid.cpp.

void control_toolbox::Pid::updateDynamicReconfig ( control_toolbox::ParametersConfig  config)

Definition at line 234 of file pid.cpp.

double control_toolbox::Pid::updatePid ( double  p_error,
ros::Duration  dt 
)

Update the Pid loop with nonuniform time step size.

Deprecated:
in ROS Hydro. This function assumes p_error = (state - target) which is an unconventional definition of the error. Please use computeCommand instead, which assumes error = (target - state) . Note that calls to computeCommand should not be mixed with calls to updatePid.
Parameters:
p_errorError since last call (p_state-p_target)
dtChange in time since last call

Definition at line 287 of file pid.cpp.

double control_toolbox::Pid::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.

Deprecated:
in ROS Hydro. This function assumes p_error = (state - target) which is an unconventional definition of the error. Please use computeCommand instead, which assumes error = (target - state) . Note that calls to computeCommand should not be mixed with calls to updatePid.
Parameters:
errorError since last call (p_state-p_target)
error_dotd(Error)/dt since last call
dtChange in time since last call

Definition at line 349 of file pid.cpp.


Member Data Documentation

double control_toolbox::Pid::cmd_ [private]

Command to send.

Definition at line 373 of file pid.h.

Derivative error.

Definition at line 371 of file pid.h.

Definition at line 376 of file pid.h.

Definition at line 367 of file pid.h.

Integral term.

Definition at line 372 of file pid.h.

Position error.

Definition at line 370 of file pid.h.

_Save position state for derivative state calculation.

Definition at line 369 of file pid.h.

DynamicReconfigServer::CallbackType control_toolbox::Pid::param_reconfig_callback_ [private]

Definition at line 379 of file pid.h.

boost::recursive_mutex control_toolbox::Pid::param_reconfig_mutex_ [private]

Definition at line 381 of file pid.h.

Definition at line 378 of file pid.h.


The documentation for this class was generated from the following files:


control_toolbox
Author(s): Melonee Wise, Sachin Chitta, John Hsu
autogenerated on Wed Aug 26 2015 11:09:13