Store gains in a struct to allow easier realtime buffer 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. | |
Gains (double p, double i, double d, double i_max, double i_min, bool antiwindup) | |
Optional constructor for passing in values. | |
Public Attributes | |
double | p_gain_ |
double | i_gain_ |
double | d_gain_ |
double | i_max_ |
double | i_min_ |
bool | antiwindup_ |
Store gains in a struct to allow easier realtime buffer usage.
|
inline |
Optional constructor for passing in values without antiwindup.
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.
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. |
bool control_toolbox::Pid::Gains::antiwindup_ |
Antiwindup.
double control_toolbox::Pid::Gains::d_gain_ |
Derivative gain.
double control_toolbox::Pid::Gains::i_gain_ |
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_ |
Proportional gain.