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

Generic Proportional–Integral–Derivative (PID) controller. 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 box 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.
 
 Pid (double p, double i, double d, double u_max, double u_min, const AntiWindupStrategy &antiwindup_strat)
 Constructor, initialize Pid-gains and term limits.
 
 Pid (const Pid &source)
 Copy constructor required for preventing mutexes from being copied.
 
 ~Pid ()
 Destructor of Pid class.
 
bool 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 term limits.
 
void initPid (double p, double i, double d, double i_max, double i_min, bool antiwindup=false)
 Initialize Pid-gains and term limits.
 
bool initialize (double p, double i, double d, double u_max, double u_min, const AntiWindupStrategy &antiwindup_strat)
 Initialize Pid-gains and term limits.
 
void reset ()
 Reset the state of this PID controller.
 
void reset (bool save_i_term)
 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.
 
void get_gains (double &p, double &i, double &d, double &u_max, double &u_min, AntiWindupStrategy &antiwindup_strat)
 Get PID gains for the controller (preferred).
 
Gains get_gains ()
 Get PID gains for the controller.
 
Gains getGains ()
 Get PID gains for the controller.
 
Gains get_gains_rt ()
 Get PID gains for the controller.
 
bool 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.
 
bool set_gains (double p, double i, double d, double u_max, double u_min, const AntiWindupStrategy &antiwindup_strat)
 Set PID gains for the controller.
 
bool 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

Gains gains_
 
realtime_tools::RealtimeThreadSafeBox< Gainsgains_box_ {gains_}
 
double p_error_last_ = 0
 
double p_error_ = 0
 
double d_error_ = 0
 
double i_term_ = 0
 
double cmd_ = 0
 
double cmd_unsat_ = 0
 

Detailed Description

Generic Proportional–Integral–Derivative (PID) controller.

The PID (Proportional–Integral–Derivative) controller is a widely used feedback controller. 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 control loops. Integral retention on reset is supported, which prevents re-winding the integrator after temporary disabling in presence of constant disturbances.

PID Equation

The standard PID equation is:

\[ command = p\_term + i\_term + d\_term \]

where:

Parameters

Parameters
pProportional gain. Reacts to current error.
iIntegral gain. Accumulates past error to eliminate steady-state error.
dDerivative gain. Predicts future error to reduce overshoot and settling time.
u_minMinimum bound for the controller output.
u_maxMaximum bound for the controller output.
tracking_time_constantTracking time constant for BACK_CALCULATION anti-windup. If zero, a default is chosen based on gains:
  • \( \sqrt{d\_gain / i\_gain} \) if d_gain ≠ 0
  • \( p\_gain / i\_gain \) otherwise.
antiwindup_stratAnti-windup strategy:
  • NONE: no anti-windup (integral always accumulates).
  • BACK_CALCULATION: adjusts i_term based on difference between saturated and unsaturated outputs using tracking_time_constant.
  • CONDITIONAL_INTEGRATION: only integrates when output is not saturated or error drives it away from saturation.

Anti-Windup Strategies

Without anti-windup, clamping causes integral windup, leading to overshoot and sluggish recovery. This class provides two strategies:

Usage Example

Initialize and compute at each control step:

pid.initialize(6.0, 1.0, 2.0, -5.0, 5.0,
2.0, control_toolbox::AntiwindupStrategy::BACK_CALCULATION);
rclcpp::Time last = get_clock()->now();
while (running) {
rclcpp::Time now = get_clock()->now();
double effort = pid.compute_command(setpoint - current(), now - last);
last = now;
}
A Low-pass filter class.
Definition low_pass_filter.hpp:78
Generic Proportional–Integral–Derivative (PID) controller.
Definition pid.hpp:282

Constructor & Destructor Documentation

◆ Pid() [1/3]

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.

Parameters
pThe proportional gain.
iThe integral gain.
dThe derivative gain.
i_maxUpper integral clamp.
i_minLower integral clamp.
antiwindupAnti-windup 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/3]

control_toolbox::Pid::Pid ( double  p,
double  i,
double  d,
double  u_max,
double  u_min,
const AntiWindupStrategy antiwindup_strat 
)

Constructor, initialize Pid-gains and term limits.

Parameters
pThe proportional gain.
iThe integral gain.
dThe derivative gain.
u_maxUpper output clamp.
u_minLower output clamp.
antiwindup_stratSpecifies the anti-windup strategy. Options: 'back_calculation', 'conditional_integration', or 'none'. Note that the 'back_calculation' strategy use the tracking_time_constant parameter to tune the anti-windup behavior.
Exceptions
Anstd::invalid_argument exception is thrown if u_min > u_max

◆ Pid() [3/3]

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 weighted integral error.
deThe derivative error.

◆ get_gains() [1/4]

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

Get PID gains for the controller.

Returns
gains A struct of the PID gain values
Note
This method is not RT safe

◆ get_gains() [2/4]

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.
Note
This method is not RT safe

◆ get_gains() [3/4]

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.
antiwindupAnti-windup 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
This method is not RT safe

◆ get_gains() [4/4]

void control_toolbox::Pid::get_gains ( double p,
double i,
double d,
double u_max,
double u_min,
AntiWindupStrategy antiwindup_strat 
)

Get PID gains for the controller (preferred).

Parameters
pThe proportional gain.
iThe integral gain.
dThe derivative gain.
u_maxUpper output clamp.
u_minLower output clamp.
antiwindup_stratSpecifies the anti-windup strategy. Options: 'back_calculation', 'conditional_integration', or 'none'. Note that the 'back_calculation' strategy use the tracking_time_constant parameter to tune the anti-windup behavior.
Note
This method is not RT safe

◆ get_gains_rt()

Gains control_toolbox::Pid::get_gains_rt ( )
inline

Get PID gains for the controller.

Returns
gains A struct of the PID gain values
Note
This method can be called from the RT loop

◆ 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
Note
This method is not RT safe

◆ 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() [1/2]

bool 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 term limits.

Parameters
pThe proportional gain.
iThe integral gain.
dThe derivative gain.
i_maxUpper integral clamp.
i_minLower integral clamp.
antiwindupAnti-windup 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.
Returns
True if all parameters are successfully set, False otherwise.
Note
New gains are not applied if i_min_ > i_max_

◆ initialize() [2/2]

bool control_toolbox::Pid::initialize ( double  p,
double  i,
double  d,
double  u_max,
double  u_min,
const AntiWindupStrategy antiwindup_strat 
)

Initialize Pid-gains and term limits.

Parameters
pThe proportional gain.
iThe integral gain.
dThe derivative gain.
u_maxUpper output clamp.
u_minLower output clamp.
antiwindup_stratSpecifies the anti-windup strategy. Options: 'back_calculation', 'conditional_integration', or 'none'. Note that the 'back_calculation' strategy use the tracking_time_constant parameter to tune the anti-windup behavior.
Returns
True if all parameters are successfully set, False otherwise.
Note
New gains are not applied if i_min_ > i_max_ or u_min > u_max

◆ initPid()

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

Initialize Pid-gains and term limits.

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_i_term)

Reset the state of this PID controller.

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

◆ set_gains() [1/3]

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

Set PID gains for the controller.

Parameters
gainsA struct of the PID gain values
Returns
True if all parameters are successfully set, False otherwise.
Note
New gains are not applied if gains.i_min_ > gains.i_max_
This method is not RT safe

◆ set_gains() [2/3]

bool 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.
antiwindupAnti-windup 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.
Returns
True if all parameters are successfully set, False otherwise.
Note
New gains are not applied if i_min > i_max
This method is not RT safe

◆ set_gains() [3/3]

bool control_toolbox::Pid::set_gains ( double  p,
double  i,
double  d,
double  u_max,
double  u_min,
const AntiWindupStrategy antiwindup_strat 
)

Set PID gains for the controller.

Parameters
pThe proportional gain.
iThe integral gain.
dThe derivative gain.
u_maxUpper output clamp.
u_minLower output clamp.
antiwindup_stratSpecifies the anti-windup strategy. Options: 'back_calculation', 'conditional_integration', or 'none'. Note that the 'back_calculation' strategy use the tracking_time_constant parameter to tune the anti-windup behavior.
Returns
True if all parameters are successfully set, False otherwise.
Note
New gains are not applied if i_min_ > i_max_ or u_min > u_max
This method is not RT safe

◆ 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_ = 0
protected

Integrator state.

◆ cmd_unsat_

double control_toolbox::Pid::cmd_unsat_ = 0
protected

Command to send.

◆ d_error_

double control_toolbox::Pid::d_error_ = 0
protected

Error.

◆ gains_

Gains control_toolbox::Pid::gains_
protected
Initial value:
{
0.0,
0.0,
0.0,
std::numeric_limits<double>::infinity(),
-std::numeric_limits<double>::infinity(),
AntiWindupStrategy()}

◆ i_term_

double control_toolbox::Pid::i_term_ = 0
protected

Derivative of error.

◆ p_error_

double control_toolbox::Pid::p_error_ = 0
protected

Save state for derivative state calculation.


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