Struct Pid::Gains
Defined in File pid.hpp
Nested Relationships
This struct is a nested type of Class Pid.
Struct Documentation
-
struct Gains
Store gains in a struct to allow easier realtime buffer usage.
Public Functions
-
inline Gains(double p, double i, double d, double i_max, double i_min)
Optional constructor for passing in values without antiwindup and saturation.
- Parameters:
p – The proportional gain.
i – The integral gain.
d – The derivative gain.
i_max – Upper integral clamp.
i_min – Lower integral clamp.
-
inline Gains(double p, double i, double d, double i_max, double i_min, bool antiwindup)
Optional constructor for passing in values without saturation.
- Parameters:
p – The proportional gain.
i – The integral gain.
d – The derivative gain.
i_max – Upper integral clamp.
i_min – Lower integral clamp.
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.
-
inline Gains(double p, double i, double d, double i_max, double i_min, double u_max, double u_min, double trk_tc, bool saturation, bool antiwindup, AntiwindupStrategy antiwindup_strat)
Optional constructor for passing in values.
- Parameters:
p – The proportional gain.
i – The integral gain.
d – The derivative gain.
i_max – Upper integral clamp.
i_min – Lower integral clamp.
u_max – Upper output clamp.
u_min – Lower output clamp.
trk_tc – 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.
saturation – Enables output saturation. When true, the controller output is clamped between u_max and u_min.
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.
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. When a strategy other than ‘none’ is selected, it will override the controller’s default anti-windup behavior.
-
inline Gains(double p, double i, double d, double u_max, double u_min, double trk_tc, bool saturation, AntiwindupStrategy antiwindup_strat)
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.
trk_tc – 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.
saturation – Enables output saturation. When true, the controller output is clamped between u_max and u_min.
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.
-
inline Gains()
Public Members
-
double p_gain_
Proportional gain.
-
double i_gain_
Integral gain.
-
double d_gain_
Derivative gain.
-
double i_max_
Maximum allowable integral term.
-
double i_min_
Minimum allowable integral term.
-
double u_max_
Maximum allowable output.
-
double u_min_
Minimum allowable output.
-
double trk_tc_
Tracking time constant.
-
bool saturation_
Saturation.
-
bool antiwindup_
Anti-windup.
-
AntiwindupStrategy antiwindup_strat_
Anti-windup strategy.
-
inline Gains(double p, double i, double d, double i_max, double i_min)