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