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 box 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 u_max, double u_min, const 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.
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 bool validate(std::string &error_msg) const
-
inline Gains()
-
inline void print() const
Public Members
-
double p_gain_ = 0.0
Proportional gain.
-
double i_gain_ = 0.0
Integral gain.
-
double d_gain_ = 0.0
Derivative gain.
-
double i_max_ = 0.0
Maximum allowable integral term.
-
double i_min_ = 0.0
Minimum allowable integral term.
-
double u_max_ = std::numeric_limits<double>::infinity()
Maximum allowable output.
-
double u_min_ = -std::numeric_limits<double>::infinity()
Minimum allowable output.
-
bool antiwindup_ = false
Anti-windup.
-
AntiWindupStrategy antiwindup_strat_
Anti-windup strategy.
-
inline Gains(double p, double i, double d, double i_max, double i_min)