![]() |
ros2_control - iron
|
Store gains in a struct to allow easier realtime box usage. More...
#include <pid.hpp>

Public Member Functions | |
| Gains (double p, double i, double d, double i_max, double i_min) | |
| Optional constructor for passing in values without antiwindup and saturation. | |
| Gains (double p, double i, double d, double i_max, double i_min, bool antiwindup) | |
| Optional constructor for passing in values without saturation. | |
| Gains (double p, double i, double d, double u_max, double u_min, const AntiWindupStrategy &antiwindup_strat) | |
| Constructor for passing in values. | |
| bool | validate (std::string &error_msg) const |
| void | print () const |
Public Attributes | |
| double | p_gain_ = 0.0 |
| double | i_gain_ = 0.0 |
| double | d_gain_ = 0.0 |
| double | i_max_ |
| double | i_min_ |
| double | u_max_ = std::numeric_limits<double>::infinity() |
| double | u_min_ = -std::numeric_limits<double>::infinity() |
| bool | antiwindup_ = false |
| AntiWindupStrategy | antiwindup_strat_ |
Store gains in a struct to allow easier realtime box usage.
|
inline |
Optional constructor for passing in values without antiwindup and saturation.
| p | The proportional gain. |
| i | The integral gain. |
| d | The derivative gain. |
| i_max | Upper integral clamp. |
| i_min | Lower integral clamp. |
|
inline |
Optional constructor for passing in values without saturation.
| p | The proportional gain. |
| i | The integral gain. |
| d | The derivative gain. |
| i_max | Upper integral clamp. |
| i_min | Lower integral clamp. |
| antiwindup | Anti-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. |
|
inline |
Constructor for passing in values.
| p | The proportional gain. |
| i | The integral gain. |
| d | The derivative gain. |
| u_max | Upper output clamp. |
| u_min | Lower output clamp. |
| antiwindup_strat | Specifies 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. |
| AntiWindupStrategy control_toolbox::Pid::Gains::antiwindup_strat_ |
Anti-windup strategy.
| double control_toolbox::Pid::Gains::d_gain_ = 0.0 |
Derivative gain.
| double control_toolbox::Pid::Gains::i_gain_ = 0.0 |
Integral gain.
| double control_toolbox::Pid::Gains::i_max_ |
Maximum allowable integral term.
| double control_toolbox::Pid::Gains::i_min_ |
Minimum allowable integral term.
| double control_toolbox::Pid::Gains::p_gain_ = 0.0 |
Proportional gain.
Maximum allowable output.
Minimum allowable output.