Store gains in a struct to allow easier realtime buffer usage.
More...
#include <pid.hpp>
|
| Gains (double p, double i, double d, double i_max, double i_min) |
| Optional constructor for passing in values without antiwindup. More...
|
|
| Gains (double p, double i, double d, double i_max, double i_min, bool antiwindup) |
| Optional constructor for passing in values. More...
|
|
Store gains in a struct to allow easier realtime buffer usage.
◆ Gains() [1/2]
control_toolbox::Pid::Gains::Gains |
( |
double |
p, |
|
|
double |
i, |
|
|
double |
d, |
|
|
double |
i_max, |
|
|
double |
i_min |
|
) |
| |
|
inline |
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. |
- Exceptions
-
An | std::invalid_argument exception is thrown if i_min > i_max |
◆ Gains() [2/2]
control_toolbox::Pid::Gains::Gains |
( |
double |
p, |
|
|
double |
i, |
|
|
double |
d, |
|
|
double |
i_max, |
|
|
double |
i_min, |
|
|
bool |
antiwindup |
|
) |
| |
|
inline |
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 |
- Exceptions
-
An | std::invalid_argument exception is thrown if i_min > i_max |
◆ antiwindup_
bool control_toolbox::Pid::Gains::antiwindup_ |
◆ d_gain_
double control_toolbox::Pid::Gains::d_gain_ |
◆ i_gain_
double control_toolbox::Pid::Gains::i_gain_ |
◆ i_max_
double control_toolbox::Pid::Gains::i_max_ |
Maximum allowable integral term.
◆ i_min_
double control_toolbox::Pid::Gains::i_min_ |
Minimum allowable integral term.
◆ p_gain_
double control_toolbox::Pid::Gains::p_gain_ |
The documentation for this struct was generated from the following file:
- control_toolbox/include/control_toolbox/pid.hpp