ros2_control - jazzy
Loading...
Searching...
No Matches
Public Types | Public Member Functions | Public Attributes | List of all members
control_toolbox::AntiWindupStrategy Struct Reference

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
 

Detailed Description

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.

Parameters
i_maxUpper integral clamp.
i_minLower integral clamp.
u_maxUpper output clamp.
u_minLower output clamp.
tracking_time_constantSpecifies 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_antiwindupAnti-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_deadbandError deadband is used to stop integration when the error is within the given range.
typeSpecifies 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.

Member Data Documentation

◆ error_deadband

double control_toolbox::AntiWindupStrategy::error_deadband
Initial value:
=
std::numeric_limits<double>::epsilon()

Error deadband to avoid integration.

◆ i_max

double control_toolbox::AntiWindupStrategy::i_max = std::numeric_limits<double>::quiet_NaN()

Maximum allowable integral term.

◆ i_min

double control_toolbox::AntiWindupStrategy::i_min = std::numeric_limits<double>::quiet_NaN()

Minimum allowable integral term.

◆ legacy_antiwindup

bool control_toolbox::AntiWindupStrategy::legacy_antiwindup = false

Use legacy anti-windup strategy.

◆ tracking_time_constant

double control_toolbox::AntiWindupStrategy::tracking_time_constant = 0.0

Tracking time constant for back_calculation strategy.


The documentation for this struct was generated from the following file: