Struct AntiWindupStrategy
Defined in File pid.hpp
Struct Documentation
-
struct AntiWindupStrategy
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.
- Param i_max:
Upper integral clamp.
- Param i_min:
Lower integral clamp.
- Param u_max:
Upper output clamp.
- Param u_min:
Lower output clamp.
- Param 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.
- Param 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.
- Param error_deadband:
Error deadband is used to stop integration when the error is within the given range.
- Param type:
Specifies the antiwindup strategy type. Valid values are:
NONE
: No antiwindup strategy applied.LEGACY
: Legacy antiwindup strategy, which limits the integral term to prevent windup (deprecated: This option will be removed in a future release).BACK_CALCULATION
: Back calculation antiwindup strategy, which uses a tracking time constant.CONDITIONAL_INTEGRATION
: Conditional integration antiwindup strategy, which integrates only when certain conditions are met.
Public Types
Public Functions
-
inline AntiWindupStrategy()
-
inline void set_type(const std::string &s)
-
inline void validate() const
-
inline operator std::string() const
-
inline std::string to_string() const
Public Members
-
double i_min = std::numeric_limits<double>::quiet_NaN()
Minimum allowable integral term.
-
double i_max = std::numeric_limits<double>::quiet_NaN()
Maximum allowable integral term.
-
bool legacy_antiwindup = false
Use legacy anti-windup strategy.
-
double tracking_time_constant = 0.0
Tracking time constant for back_calculation strategy.
-
double error_deadband = std::numeric_limits<double>::epsilon()
Error deadband to avoid integration.