Class Pid
Defined in File pid.hpp
Nested Relationships
Nested Types
Class Documentation
-
class Pid
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:
\( p_{term} = p_{gain} * p_{error} \)
\( i_{term} = i_{term} + \int{i_{gain} * p_{error} * dt} \)
\( d_{term} = d_{gain} * d_{error} \)
\( d_{error} = (p_{error} - p_{error last}) / dt \)
given:
\( p_{error} = p_{desired} - p_{state} \).
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; }
- Param p:
Proportional gain
- Param d:
Derivative gain
- Param i:
Integral gain
- Param i_clamp:
Min/max bounds for the integral windup, the clamp is applied to the \(i_{term}\)
Public 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.
- Parameters:
p – The proportional gain.
i – The integral gain.
d – The derivative gain.
i_max – Upper integral clamp.
i_min – Lower integral clamp.
antiwindup – Antiwindup 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.
- Throws:
An – std::invalid_argument exception is thrown if i_min > i_max
-
Pid(const Pid &source)
Copy constructor required for preventing mutexes from being copied.
- Parameters:
source – - Pid to copy
-
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.
Note
New gains are not applied if i_min_ > i_max_
- Parameters:
p – The proportional gain.
i – The integral gain.
d – The derivative gain.
i_max – Upper integral clamp.
i_min – Lower integral clamp.
antiwindup – Antiwindup 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.
-
void reset()
Reset the state of this PID controller.
Note
The integral term is not retained and it is reset to zero
-
void reset(bool save_i_term)
Reset the state of this PID controller.
- Parameters:
save_i_term – boolean indicating if integral term is retained on reset()
-
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.
- Parameters:
p – The proportional gain.
i – The integral gain.
d – The derivative gain.
i_max – Upper integral clamp.
i_min – Lower integral clamp.
-
void get_gains(double &p, double &i, double &d, double &i_max, double &i_min, bool &antiwindup)
Get PID gains for the controller.
- Parameters:
p – The proportional gain.
i – The integral gain.
d – The derivative gain.
i_max – Upper integral clamp.
i_min – Lower integral clamp.
antiwindup – Antiwindup 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.
-
void set_gains(double p, double i, double d, double i_max, double i_min, bool antiwindup = false)
Set PID gains for the controller.
Note
New gains are not applied if i_min > i_max
- Parameters:
p – The proportional gain.
i – The integral gain.
d – The derivative gain.
i_max – Upper integral clamp.
i_min – Lower integral clamp.
antiwindup – Antiwindup 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.
-
void set_gains(const Gains &gains)
Set PID gains for the controller.
Note
New gains are not applied if gains.i_min_ > gains.i_max_
- Parameters:
gains – A struct of the PID gain values
-
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.- Parameters:
error – Error since last call (error = target - state)
dt_s – Change in time since last call in seconds
- Returns:
PID command
-
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.- Parameters:
error – Error since last call (error = target - state)
dt_ns – Change in time since last call, measured in nanoseconds.
- Returns:
PID command
-
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.- Parameters:
error – Error since last call (error = target - state)
dt – Change in time since last call
- Returns:
PID command
-
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.- Parameters:
error – Error since last call (error = target - state)
dt_ns – Change in time since last call
- Returns:
PID command
-
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.
- Parameters:
error – Error since last call (error = target - state)
error_dot – d(Error)/dt_s since last call
dt_s – Change in time since last call in seconds
- Returns:
PID command
-
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.
- Parameters:
error – Error since last call (error = target - state)
error_dot – d(Error)/dt_ns since last call
dt_ns – Change in time since last call, measured in nanoseconds.
- Returns:
PID command
-
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.
- Parameters:
error – Error since last call (error = target - state)
error_dot – d(Error)/dt since last call
dt – Change in time since last call
- Returns:
PID command
-
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.
- Parameters:
error – Error since last call (error = target - state)
error_dot – d(Error)/(dt_ns/1e9) since last call
dt_ns – Change in time since last call, measured in nanoseconds.
- Returns:
PID command
-
void set_current_cmd(double cmd)
Set current command for this PID controller.
-
double get_current_cmd()
Return current command for this PID controller.
-
void get_current_pid_errors(double &pe, double &ie, double &de)
Return PID error terms for the controller.
- Parameters:
pe – The proportional error.
ie – The weighted integral error.
de – The derivative error.
Protected Attributes
-
double p_error_last_
-
double p_error_
Save state for derivative state calculation.
-
double d_error_
Error.
-
double i_term_
Derivative of error.
-
double cmd_
Integrator state.
-
struct Gains
Store gains in a struct to allow easier realtime buffer usage.
Public Functions
-
inline Gains(double p, double i, double d, double i_max, double i_min)
Optional constructor for passing in values without antiwindup.
- Parameters:
p – The proportional gain.
i – The integral gain.
d – The derivative gain.
i_max – Upper integral clamp.
i_min – Lower integral clamp.
-
inline Gains(double p, double i, double d, double i_max, double i_min, bool antiwindup)
Optional constructor for passing in values.
- Parameters:
p – The proportional gain.
i – The integral gain.
d – The derivative gain.
i_max – Upper integral clamp.
i_min – Lower integral clamp.
antiwindup – Antiwindup 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.
-
inline Gains()
-
inline Gains(double p, double i, double d, double i_max, double i_min)