ros2_control - rolling
Loading...
Searching...
No Matches
Classes | Public Member Functions | Protected Attributes | List of all members
control_toolbox::Pid Class Reference

A basic pid class. More...

#include <pid.hpp>

Collaboration diagram for control_toolbox::Pid:
Collaboration graph
[legend]

Classes

struct  Gains
 Store gains in a struct to allow easier realtime buffer usage. More...
 

Public Member Functions

 Pid (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. Does not initialize dynamic reconfigure for PID gains.
 
 Pid (const Pid &source)
 Copy constructor required for preventing mutexes from being copied.
 
 ~Pid ()
 Destructor of Pid class.
 
void initialize (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 the node's parameter interface for PID gains.
 
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 the node's parameter interface for PID gains.
 
void reset ()
 Reset the state of this PID controller.
 
void reset (bool save_iterm)
 Reset the state of this PID controller.
 
void clear_saved_iterm ()
 Clear the saved integrator output of this controller.
 
void get_gains (double &p, double &i, double &d, double &i_max, double &i_min)
 Get PID gains for the controller.
 
void getGains (double &p, double &i, double &d, double &i_max, double &i_min)
 Get PID gains for the controller.
 
void get_gains (double &p, double &i, double &d, double &i_max, double &i_min, bool &antiwindup)
 Get PID gains for the controller.
 
void getGains (double &p, double &i, double &d, double &i_max, double &i_min, bool &antiwindup)
 Get PID gains for the controller.
 
Gains get_gains ()
 Get PID gains for the controller.
 
Gains getGains ()
 Get PID gains for the controller.
 
void set_gains (double p, double i, double d, double i_max, double i_min, bool antiwindup=false)
 Set PID gains for the controller.
 
void setGains (double p, double i, double d, double i_max, double i_min, bool antiwindup=false)
 Set PID gains for the controller.
 
void set_gains (const Gains &gains)
 Set PID gains for the controller.
 
void setGains (const Gains &gains)
 Set PID gains for the controller.
 
double compute_command (double error, const double &dt_s)
 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_s.
 
double computeCommand (double error, uint64_t 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 compute_command (double error, const rcl_duration_value_t &dt_ns)
 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_ns.
 
double compute_command (double error, const rclcpp::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 compute_command (double error, const std::chrono::nanoseconds &dt_ns)
 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_ns.
 
double compute_command (double error, double error_dot, const double &dt_s)
 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.
 
double computeCommand (double error, double error_dot, uint64_t 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.
 
double compute_command (double error, double error_dot, const rcl_duration_value_t &dt_ns)
 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.
 
double compute_command (double error, double error_dot, const rclcpp::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.
 
double compute_command (double error, double error_dot, const std::chrono::nanoseconds &dt_ns)
 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 set_current_cmd (double cmd)
 Set current command for this PID controller.
 
void setCurrentCmd (double cmd)
 Set current command for this PID controller.
 
double get_current_cmd ()
 Return current command for this PID controller.
 
double getCurrentCmd ()
 Return current command for this PID controller.
 
double getDerivativeError ()
 Return derivative error.
 
void get_current_pid_errors (double &pe, double &ie, double &de)
 Return PID error terms for the controller.
 
void getCurrentPIDErrors (double &pe, double &ie, double &de)
 Return PID error terms for the controller.
 
Pidoperator= (const Pid &source)
 Custom assignment operator Does not initialize dynamic reconfigure for PID gains.
 

Protected Attributes

realtime_tools::RealtimeBuffer< Gainsgains_buffer_
 
double p_error_last_
 
double p_error_
 
double i_error_
 
double d_error_
 
double cmd_
 
double error_dot_
 

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.

This class also allows for retention of integral term on reset. This is useful for control loops that are enabled/disabled with a constant steady-state external disturbance. Once the integrator cancels out the external disturbance, disabling/resetting/ re-enabling closed-loop control does not require the integrator to wind up again.

In particular, this class implements the standard pid equation:

\(command = p_{term} + i_{term} + d_{term} \)

where:

given:

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.initialize(6.0, 1.0, 2.0, 0.3, -0.3);
double position_desired = 0.5;
...
rclcpp::Time last_time = get_clock()->now();
while (true) {
rclcpp::Time time = get_clock()->now();
double effort = pid.compute_command(position_desired - currentPosition(), time - last_time);
last_time = time;
}

Constructor & Destructor Documentation

◆ Pid() [1/2]

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,
bool  antiwindup = false 
)

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_maxUpper integral clamp.
i_minLower integral clamp.
antiwindupAntiwindup functionality. When set to true, limits the integral error to prevent windup; otherwise, constrains the integral contribution to the control output. i_max and i_min are applied in both scenarios.
Exceptions
Anstd::invalid_argument exception is thrown if i_min > i_max

◆ Pid() [2/2]

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

Copy constructor required for preventing mutexes from being copied.

Parameters
source- Pid to copy

Member Function Documentation

◆ compute_command() [1/8]

double control_toolbox::Pid::compute_command ( double  error,
const double &  dt_s 
)

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_s.

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

◆ compute_command() [2/8]

double control_toolbox::Pid::compute_command ( double  error,
const rcl_duration_value_t &  dt_ns 
)

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_ns.

Parameters
errorError since last call (error = target - state)
dt_nsChange in time since last call, measured in nanoseconds.
Returns
PID command

◆ compute_command() [3/8]

double control_toolbox::Pid::compute_command ( double  error,
const rclcpp::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

◆ compute_command() [4/8]

double control_toolbox::Pid::compute_command ( double  error,
const std::chrono::nanoseconds &  dt_ns 
)

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_ns.

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

◆ compute_command() [5/8]

double control_toolbox::Pid::compute_command ( double  error,
double  error_dot,
const double &  dt_s 
)

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_s since last call
dt_sChange in time since last call in seconds
Returns
PID command

◆ compute_command() [6/8]

double control_toolbox::Pid::compute_command ( double  error,
double  error_dot,
const rcl_duration_value_t &  dt_ns 
)

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_ns since last call
dt_nsChange in time since last call, measured in nanoseconds.
Returns
PID command

◆ compute_command() [7/8]

double control_toolbox::Pid::compute_command ( double  error,
double  error_dot,
const rclcpp::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

◆ compute_command() [8/8]

double control_toolbox::Pid::compute_command ( double  error,
double  error_dot,
const std::chrono::nanoseconds &  dt_ns 
)

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_ns/1e9) since last call
dt_nsChange in time since last call, measured in nanoseconds.
Returns
PID command

◆ computeCommand() [1/2]

double control_toolbox::Pid::computeCommand ( double  error,
double  error_dot,
uint64_t  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/1e9) since last call
dtChange in time since last call in nanoseconds
Returns
PID command

◆ computeCommand() [2/2]

double control_toolbox::Pid::computeCommand ( double  error,
uint64_t  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 in nanoseconds
Returns
PID command

◆ get_current_pid_errors()

void control_toolbox::Pid::get_current_pid_errors ( double &  pe,
double &  ie,
double &  de 
)

Return PID error terms for the controller.

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

◆ get_gains() [1/3]

Pid::Gains control_toolbox::Pid::get_gains ( )

Get PID gains for the controller.

Returns
gains A struct of the PID gain values

◆ get_gains() [2/3]

void control_toolbox::Pid::get_gains ( 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_maxUpper integral clamp.
i_minLower integral clamp.

◆ get_gains() [3/3]

void control_toolbox::Pid::get_gains ( double &  p,
double &  i,
double &  d,
double &  i_max,
double &  i_min,
bool &  antiwindup 
)

Get PID gains for the controller.

Parameters
pThe proportional gain.
iThe integral gain.
dThe derivative gain.
i_maxUpper integral clamp.
i_minLower integral clamp.
antiwindupAntiwindup functionality. When set to true, limits the integral error to prevent windup; otherwise, constrains the integral contribution to the control output. i_max and i_min are applied in both scenarios.

◆ getCurrentPIDErrors()

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.

◆ getGains() [1/3]

Pid::Gains control_toolbox::Pid::getGains ( )

Get PID gains for the controller.

Returns
gains A struct of the PID gain values

◆ getGains() [2/3]

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_maxUpper integral clamp.
i_minLower integral clamp.

◆ getGains() [3/3]

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

Get PID gains for the controller.

Parameters
pThe proportional gain.
iThe integral gain.
dThe derivative gain.
i_maxUpper integral clamp.
i_minLower integral clamp.
antiwindupAntiwindup functionality. When set to true, limits the integral error to prevent windup; otherwise, constrains the integral contribution to the control output. i_max and i_min are applied in both scenarios.

◆ initialize()

void control_toolbox::Pid::initialize ( 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 the node's parameter interface for PID gains.

Parameters
pThe proportional gain.
iThe integral gain.
dThe derivative gain.
i_maxUpper integral clamp.
i_minLower integral clamp.
antiwindupAntiwindup functionality. When set to true, limits the integral error to prevent windup; otherwise, constrains the integral contribution to the control output. i_max and i_min are applied in both scenarios.
Note
New gains are not applied if i_min_ > i_max_

◆ initPid()

void control_toolbox::Pid::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 the node's parameter interface for PID gains.

Parameters
pThe proportional gain.
iThe integral gain.
dThe derivative gain.
i_maxUpper integral clamp.
i_minLower integral clamp.
antiwindupAntiwindup functionality. When set to true, limits the integral error to prevent windup; otherwise, constrains the integral contribution to the control output. i_max and i_min are applied in both scenarios.
Note
New gains are not applied if i_min_ > i_max_

◆ reset() [1/2]

void control_toolbox::Pid::reset ( )

Reset the state of this PID controller.

Note
The integral term is not retained and it is reset to zero

◆ reset() [2/2]

void control_toolbox::Pid::reset ( bool  save_iterm)

Reset the state of this PID controller.

Parameters
save_itermboolean indicating if integral term is retained on reset()

◆ set_gains() [1/2]

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

Set PID gains for the controller.

Parameters
gainsA struct of the PID gain values
Note
New gains are not applied if gains.i_min_ > gains.i_max_

◆ set_gains() [2/2]

void control_toolbox::Pid::set_gains ( double  p,
double  i,
double  d,
double  i_max,
double  i_min,
bool  antiwindup = false 
)

Set PID gains for the controller.

Parameters
pThe proportional gain.
iThe integral gain.
dThe derivative gain.
i_maxUpper integral clamp.
i_minLower integral clamp.
antiwindupAntiwindup functionality. When set to true, limits the integral error to prevent windup; otherwise, constrains the integral contribution to the control output. i_max and i_min are applied in both scenarios.
Note
New gains are not applied if i_min > i_max

◆ setGains() [1/2]

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

Set PID gains for the controller.

Parameters
gainsA struct of the PID gain values
Note
New gains are not applied if gains.i_min_ > gains.i_max_

◆ setGains() [2/2]

void control_toolbox::Pid::setGains ( double  p,
double  i,
double  d,
double  i_max,
double  i_min,
bool  antiwindup = false 
)

Set PID gains for the controller.

Parameters
pThe proportional gain.
iThe integral gain.
dThe derivative gain.
i_maxUpper integral clamp.
i_minLower integral clamp.
antiwindupAntiwindup functionality. When set to true, limits the integral error to prevent windup; otherwise, constrains the integral contribution to the control output. i_max and i_min are applied in both scenarios.
Note
New gains are not applied if i_min > i_max

Member Data Documentation

◆ cmd_

double control_toolbox::Pid::cmd_
protected

Derivative of error.

◆ d_error_

double control_toolbox::Pid::d_error_
protected

Integral of error.

◆ error_dot_

double control_toolbox::Pid::error_dot_
protected

Command to send.

◆ i_error_

double control_toolbox::Pid::i_error_
protected

Error.

◆ p_error_

double control_toolbox::Pid::p_error_
protected

Save state for derivative state calculation.


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