ADORe
ADORe is a modular open source software library and toolkit for decision making, planning, control and simulation of automated vehicles
ap_trajectory_tracking.h
Go to the documentation of this file.
1 /********************************************************************************
2  * Copyright (C) 2017-2020 German Aerospace Center (DLR).
3  * Eclipse ADORe, Automated Driving Open Research https://eclipse.org/adore
4  *
5  * This program and the accompanying materials are made available under the
6  * terms of the Eclipse Public License 2.0 which is available at
7  * http://www.eclipse.org/legal/epl-2.0.
8  *
9  * SPDX-License-Identifier: EPL-2.0
10  *
11  * Contributors:
12  * Jan Lauermann - initial API and implementation
13  ********************************************************************************/
14 
15 #pragma once
16 
17 namespace adore
18 {
19  namespace params
20  {
26  {
27 
28  public:
30  virtual double getKey()const =0;
31 
33  virtual double getKepsi()const =0;
34 
36  virtual double getKeomega()const =0;
37 
39  virtual double getKIy()const =0;
40 
42  virtual double getKIx()const =0;
43 
45  virtual double getK0x()const =0;
46 
48  virtual double getK1x()const =0;
49 
51  virtual double getMuCtrlMax()const =0;
52 
54  virtual double getAxMax()const =0;
55 
57  virtual double getAxMin()const =0;
58 
60  virtual double getExStatic()const =0;
61 
63  virtual double getEyStatic()const =0;
64 
66  virtual double getDeltaMax()const=0;
67 
69  virtual double getDeltaMin()const=0;
70 
72  virtual double getDDeltaMax()const =0;
73 
75  virtual double getBrakingTorqueGain()const =0;
76 
78  virtual double getDBrakingTorqueMax()const =0;
79 
81  virtual double getKPev_r()const =0;
82 
84  virtual double getKIev_r()const =0;
85 
87  virtual double getKPex_r()const =0;
88 
90  virtual double getKIex_r()const =0;
91 
93  virtual double getKPey_r()const =0;
94 
96  virtual double getKPepsi_r()const =0;
97 
99  virtual double getKIepsi_r()const =0;
100 
102  virtual double getSteeringRateLimiterGain()const =0;
103  };
104  }
105 }
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