Store gains in a struct to allow easier realtime box usage.
More...
#include <pid.hpp>
|
| | 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 |
| |
Store gains in a struct to allow easier realtime box usage.
◆ Gains()
| control_toolbox::Pid::Gains::Gains |
( |
double |
p, |
|
|
double |
i, |
|
|
double |
d, |
|
|
double |
u_max, |
|
|
double |
u_min, |
|
|
const AntiWindupStrategy & |
antiwindup_strat |
|
) |
| |
|
inline |
Constructor for passing in values.
- Parameters
-
| 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. |
◆ antiwindup_strat_
◆ d_gain_
| double control_toolbox::Pid::Gains::d_gain_ = 0.0 |
◆ i_gain_
| double control_toolbox::Pid::Gains::i_gain_ = 0.0 |
◆ p_gain_
| double control_toolbox::Pid::Gains::p_gain_ = 0.0 |
◆ u_max_
| double control_toolbox::Pid::Gains::u_max_ = std::numeric_limits<double>::infinity() |
Maximum allowable output.
◆ u_min_
| double control_toolbox::Pid::Gains::u_min_ = -std::numeric_limits<double>::infinity() |
Minimum allowable output.
The documentation for this struct was generated from the following file:
- control_toolbox/control_toolbox/include/control_toolbox/pid.hpp