ros2_control - rolling
Loading...
Searching...
No Matches
Public Member Functions | Public Attributes | List of all members
control_toolbox::Pid::Gains Struct Reference

Store gains in a struct to allow easier realtime box usage. More...

#include <pid.hpp>

Collaboration diagram for control_toolbox::Pid::Gains:
Collaboration graph
[legend]

Public Member Functions

 Gains (double p, double i, double d, double u_max, double u_min, const AntiWindupStrategy &antiwindup_strat)
 Constructor for passing in values.
 
bool validate (std::string &error_msg) const
 
void print () const
 

Public Attributes

double p_gain_ = 0.0
 
double i_gain_ = 0.0
 
double d_gain_ = 0.0
 
double i_max_
 
double i_min_
 
double u_max_ = std::numeric_limits<double>::infinity()
 
double u_min_ = -std::numeric_limits<double>::infinity()
 
AntiWindupStrategy antiwindup_strat_
 

Detailed Description

Store gains in a struct to allow easier realtime box usage.

Constructor & Destructor Documentation

◆ Gains()

control_toolbox::Pid::Gains::Gains ( double  p,
double  i,
double  d,
double  u_max,
double  u_min,
const AntiWindupStrategy antiwindup_strat 
)
inline

Constructor for passing in values.

Parameters
pThe proportional gain.
iThe integral gain.
dThe derivative gain.
u_maxUpper output clamp.
u_minLower output clamp.
antiwindup_stratSpecifies 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.

Member Data Documentation

◆ antiwindup_strat_

AntiWindupStrategy control_toolbox::Pid::Gains::antiwindup_strat_

Anti-windup strategy.

◆ d_gain_

double control_toolbox::Pid::Gains::d_gain_ = 0.0

Derivative gain.

◆ i_gain_

double control_toolbox::Pid::Gains::i_gain_ = 0.0

Integral gain.

◆ i_max_

double control_toolbox::Pid::Gains::i_max_
Initial value:
=
std::numeric_limits<double>::infinity()

Maximum allowable integral term.

◆ i_min_

double control_toolbox::Pid::Gains::i_min_
Initial value:
=
-std::numeric_limits<double>::infinity()

Minimum allowable integral term.

◆ p_gain_

double control_toolbox::Pid::Gains::p_gain_ = 0.0

Proportional gain.

◆ u_max_

double control_toolbox::Pid::Gains::u_max_ = std::numeric_limits<double>::infinity()

Maximum allowable output.

◆ u_min_

double control_toolbox::Pid::Gains::u_min_ = -std::numeric_limits<double>::infinity()

Minimum allowable output.


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