![]() |
ros2_control - jazzy
|
Antiwindup strategy for PID controllers. More...
#include <pid.hpp>
Public Types | |
enum | Value : int8_t { UNDEFINED = -1 , NONE , LEGACY , BACK_CALCULATION , CONDITIONAL_INTEGRATION } |
Public Member Functions | |
void | set_type (const std::string &s) |
void | validate () const |
operator std::string () const | |
constexpr bool | operator== (Value other) const |
constexpr bool | operator!= (Value other) const |
std::string | to_string () const |
Public Attributes | |
Value | type = UNDEFINED |
double | i_min = std::numeric_limits<double>::quiet_NaN() |
double | i_max = std::numeric_limits<double>::quiet_NaN() |
bool | legacy_antiwindup = false |
double | tracking_time_constant = 0.0 |
double | error_deadband |
Antiwindup strategy for PID controllers.
This class defines various antiwindup strategies that can be used in PID controllers. It allows setting the type of antiwindup strategy and validates the parameters accordingly.
i_max | Upper integral clamp. |
i_min | Lower integral clamp. |
u_max | Upper output clamp. |
u_min | Lower output clamp. |
tracking_time_constant | Specifies the tracking time constant for the 'back_calculation' strategy. If set to 0.0 when this strategy is selected, a recommended default value will be applied. |
legacy_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. |
error_deadband | Error deadband is used to stop integration when the error is within the given range. |
type | Specifies the antiwindup strategy type. Valid values are:
|
double control_toolbox::AntiWindupStrategy::error_deadband |
Error deadband to avoid integration.
Maximum allowable integral term.
Minimum allowable integral term.
Use legacy anti-windup strategy.
double control_toolbox::AntiWindupStrategy::tracking_time_constant = 0.0 |
Tracking time constant for back_calculation strategy.