31 :
ROSParam(n,prefix +
"trajectory_tracking/")
35 virtual double getKey()
const override
38 static const std::string name =
prefix_ +
"key";
46 static const std::string name =
prefix_ +
"kepsi";
54 static const std::string name =
prefix_ +
"keomega";
59 virtual double getKIy()
const override
62 static const std::string name =
prefix_ +
"kIy";
67 virtual double getKIx()
const override
70 static const std::string name =
prefix_ +
"kIx";
75 virtual double getK0x()
const override
78 static const std::string name =
prefix_ +
"k0x";
83 virtual double getK1x()
const override
86 static const std::string name =
prefix_ +
"k1x";
94 static const std::string name =
prefix_ +
"muCtrlMax";
102 static const std::string name =
prefix_ +
"axMax";
110 static const std::string name =
prefix_ +
"axMin";
118 static const std::string name =
prefix_ +
"exStatic";
126 static const std::string name =
prefix_ +
"eyStatic";
134 static const std::string name =
prefix_ +
"deltaMax";
142 static const std::string name =
prefix_ +
"deltaMin";
150 static const std::string name =
prefix_ +
"dDeltaMax";
158 static const std::string name =
prefix_ +
"brakingTorqueGain";
166 static const std::string name =
prefix_ +
"dBrakingTorqueMax";
174 static const std::string name =
prefix_ +
"kPev_r";
182 static const std::string name =
prefix_ +
"kIev_r";
190 static const std::string name =
prefix_ +
"kPex_r";
198 static const std::string name =
prefix_ +
"kIex_r";
206 static const std::string name =
prefix_ +
"kPey_r";
214 static const std::string name =
prefix_ +
"kPepsi_r";
222 static const std::string name =
prefix_ +
"kIepsi_r";
230 static const std::string name =
prefix_ +
"steeringRateLimiterGain";
Definition: ros_com_patterns.h:179
std::string prefix_
Definition: ros_com_patterns.h:181
void get(const std::string &name, T &result) const
Definition: ros_com_patterns.h:186
Definition: p_trajectory_tracking.h:28
virtual double getKIev_r() const override
reverse controller: control gain for integrated speed error (I)
Definition: p_trajectory_tracking.h:179
virtual double getExStatic() const override
static trajectory tracking offset in longitudinal direction, which should be compensated by tracking ...
Definition: p_trajectory_tracking.h:115
virtual double getDeltaMax() const override
the maximum controllable steering angle
Definition: p_trajectory_tracking.h:131
virtual double getDeltaMin() const override
the minimum controllable steering angle
Definition: p_trajectory_tracking.h:139
virtual double getKIex_r() const override
reverse controller: control gain for integrated x error (I)
Definition: p_trajectory_tracking.h:195
virtual double getKPepsi_r() const override
reverse controller: control gain for psi error (P)
Definition: p_trajectory_tracking.h:211
virtual double getKey() const override
lateral control gain for lateral error ey
Definition: p_trajectory_tracking.h:35
virtual double getBrakingTorqueGain() const override
returns gain for braking torque calculation
Definition: p_trajectory_tracking.h:155
virtual double getKPey_r() const override
reverse controller: control gain for y error (P)
Definition: p_trajectory_tracking.h:203
virtual double getSteeringRateLimiterGain() const override
gain for steering rate limiter
Definition: p_trajectory_tracking.h:227
virtual double getKIx() const override
returns I control gain for longitudinal direction
Definition: p_trajectory_tracking.h:67
virtual double getKIepsi_r() const override
reverse controller: control gain for integrated psi error (I)
Definition: p_trajectory_tracking.h:219
virtual double getAxMin() const override
hard coded minimum longitudinal acceleration
Definition: p_trajectory_tracking.h:107
virtual double getKIy() const override
returns I control gain for lateral direction
Definition: p_trajectory_tracking.h:59
virtual double getDDeltaMax() const override
steering angle: maximum absolute control input change per control update. Maximum steering rate then ...
Definition: p_trajectory_tracking.h:147
virtual double getDBrakingTorqueMax() const override
returns maxium braking torque rate
Definition: p_trajectory_tracking.h:163
virtual double getEyStatic() const override
static trajectory tracking offset in lateral direction, which should be compensated by tracking contr...
Definition: p_trajectory_tracking.h:123
PTrajectoryTracking(ros::NodeHandle n, std::string prefix)
Definition: p_trajectory_tracking.h:30
virtual double getK0x() const override
returns P control gain for longitudinal direction
Definition: p_trajectory_tracking.h:75
virtual double getKPex_r() const override
reverse controller: control gain for x error (P)
Definition: p_trajectory_tracking.h:187
virtual double getMuCtrlMax() const override
returns factor for maximum tire force requestable by controller, |f_requested|<muCtrlMax * f_max
Definition: p_trajectory_tracking.h:91
virtual double getKeomega() const override
lateral control gain for yaw rate error eomega
Definition: p_trajectory_tracking.h:51
virtual double getK1x() const override
returns D control gain for longitudinal direction
Definition: p_trajectory_tracking.h:83
virtual double getKepsi() const override
lateral control gain for yaw angle error epsi
Definition: p_trajectory_tracking.h:43
virtual double getKPev_r() const override
reverse controller: control gain for speed error (P)
Definition: p_trajectory_tracking.h:171
virtual double getAxMax() const override
hard coded maximum longitudinal acceleration
Definition: p_trajectory_tracking.h:99
abstract class containing parameters to configure the behaviour of the trajactory tracking controller
Definition: ap_trajectory_tracking.h:26
Definition: areaofeffectconverter.h:20