abstract class containing parameters to configure the behaviour of the trajactory tracking controller
Definition: ap_trajectory_tracking.h:26
virtual double getDeltaMin() const =0
the minimum controllable steering angle
virtual double getKIev_r() const =0
reverse controller: control gain for integrated speed error (I)
virtual double getDDeltaMax() const =0
steering angle: maximum absolute control input change per control update. Maximum steering rate then ...
virtual double getEyStatic() const =0
static trajectory tracking offset in lateral direction, which should be compensated by tracking contr...
virtual double getKepsi() const =0
lateral control gain for yaw angle error epsi
virtual double getAxMax() const =0
hard coded maximum longitudinal acceleration
virtual double getK0x() const =0
returns P control gain for longitudinal direction
virtual double getDeltaMax() const =0
the maximum controllable steering angle
virtual double getMuCtrlMax() const =0
returns factor for maximum tire force requestable by controller, |f_requested|<muCtrlMax * f_max
virtual double getK1x() const =0
returns D control gain for longitudinal direction
virtual double getKIepsi_r() const =0
reverse controller: control gain for integrated psi error (I)
virtual double getDBrakingTorqueMax() const =0
returns maxium braking torque rate
virtual double getKey() const =0
lateral control gain for lateral error ey
virtual double getSteeringRateLimiterGain() const =0
gain for steering rate limiter
virtual double getBrakingTorqueGain() const =0
returns gain for braking torque calculation
virtual double getKPev_r() const =0
reverse controller: control gain for speed error (P)
virtual double getAxMin() const =0
hard coded minimum longitudinal acceleration
virtual double getKPepsi_r() const =0
reverse controller: control gain for psi error (P)
virtual double getKIx() const =0
returns I control gain for longitudinal direction
virtual double getKPey_r() const =0
reverse controller: control gain for y error (P)
virtual double getKIex_r() const =0
reverse controller: control gain for integrated x error (I)
virtual double getKeomega() const =0
lateral control gain for yaw rate error eomega
virtual double getExStatic() const =0
static trajectory tracking offset in longitudinal direction, which should be compensated by tracking ...
virtual double getKPex_r() const =0
reverse controller: control gain for x error (P)
virtual double getKIy() const =0
returns I control gain for lateral direction
Definition: areaofeffectconverter.h:20