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.
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.initPid(6.0, 1.0, 2.0, 0.3, -0.3); double position_desi_ = 0.5; ... rclcpp::Time last_time = get_clock()->now(); while (true) { rclcpp::Time time = get_clock()->now(); double effort = pid.computeCommand(position_desi_ - currentPosition(), (time - last_time).nanoseconds()); 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 – The max integral windup.
i_min – The min integral windup.
antiwindup – If true, antiwindup is enabled and i_max/i_min are enforced
- 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 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.
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 – The max integral windup.
i_min – The min integral windup.
antiwindup – If true, antiwindup is enabled and i_max/i_min are enforced
-
void reset()
Reset the state of this PID controller.
-
void getGains(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 – The max integral windup.
i_min – The min integral windup.
-
void getGains(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 – The max integral windup.
i_min – The min integral windup.
antiwindup – If true, antiwindup is enabled and i_max/i_min are enforced
-
void setGains(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 – The max integral windup.
i_min – The min integral windup.
antiwindup – If true, antiwindup is enabled and i_max/i_min are enforced
-
void setGains(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 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:
error – Error since last call (error = target - state)
dt – Change in time since last call in nanoseconds
- Returns:
PID command
-
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.
- Parameters:
error – Error since last call (error = target - state)
error_dot – d(Error)/dt since last call
dt – Change in time since last call in nanoseconds
- Returns:
PID command
-
void setCurrentCmd(double cmd)
Set current command for this PID controller.
-
double getCurrentCmd()
Return current command for this PID controller.
-
double getDerivativeError()
Return derivative error.
-
void getCurrentPIDErrors(double &pe, double &ie, double &de)
Return PID error terms for the controller.
- Parameters:
pe – The proportional error.
ie – The integral error.
de – The derivative error.
Protected Attributes
-
double p_error_last_
_Save position state for derivative state calculation.
-
double p_error_
Position error.
-
double i_error_
Integral of position error.
-
double d_error_
Derivative of position error.
-
double cmd_
Command to send.
-
double error_dot_
Derivative error
-
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 – The max integral windup.
i_min – The min integral windup.
- Throws:
An – std::invalid_argument exception is thrown if i_min > i_max
-
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 – The max integral windup.
i_min – The min integral windup.
antiwindup – If true, antiwindup is enabled and i_max/i_min are enforced
- Throws:
An – std::invalid_argument exception is thrown if i_min > i_max
-
inline Gains()
-
inline Gains(double p, double i, double d, double i_max, double i_min)