ADORe
ADORe is a modular open source software library and toolkit for decision making, planning, control and simulation of automated vehicles
p_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 #include <ros/ros.h>
20 
21 namespace adore
22 {
23  namespace if_ROS
24  {
25  namespace params
26  {
28  {
29  public:
30  PTrajectoryTracking(ros::NodeHandle n,std::string prefix)
31  :ROSParam(n,prefix + "trajectory_tracking/")
32  {
33  }
34  //lateral control gain for lateral error ey
35  virtual double getKey()const override
36  {
37  double value = 0.05;
38  static const std::string name = prefix_ + "key";
39  get(name,value);
40  return value;
41  }
42  //lateral control gain for yaw angle error epsi
43  virtual double getKepsi()const override
44  {
45  double value = 0.4;
46  static const std::string name = prefix_ + "kepsi";
47  get(name,value);
48  return value;
49  }
50  //lateral control gain for yaw rate error eomega
51  virtual double getKeomega()const override
52  {
53  double value = 0.05;
54  static const std::string name = prefix_ + "keomega";
55  get(name,value);
56  return value;
57  }
58  //returns I control gain for lateral direction
59  virtual double getKIy()const override
60  {
61  double value = 0.0;
62  static const std::string name = prefix_ + "kIy";
63  get(name,value);
64  return value;
65  }
66  //returns I control gain for longitudinal direction
67  virtual double getKIx()const override
68  {
69  double value = 0.1;
70  static const std::string name = prefix_ + "kIx";
71  get(name,value);
72  return value;
73  }
74  //returns P control gain for longitudinal direction
75  virtual double getK0x()const override
76  {
77  double value = 0.9;
78  static const std::string name = prefix_ + "k0x";
79  get(name,value);
80  return value;
81  }
82  //returns D control gain for longitudinal direction
83  virtual double getK1x()const override
84  {
85  double value = 1.6;
86  static const std::string name = prefix_ + "k1x";
87  get(name,value);
88  return value;
89  }
90  //returns factor for maximum tire force requestable by controller, |f_requested|<muCtrlMax * f_max
91  virtual double getMuCtrlMax()const override
92  {
93  double value = 1.0;
94  static const std::string name = prefix_ + "muCtrlMax";
95  get(name,value);
96  return value;
97  }
98  //hard coded maximum longitudinal acceleration
99  virtual double getAxMax()const override
100  {
101  double value = 2.0;
102  static const std::string name = prefix_ + "axMax";
103  get(name,value);
104  return value;
105  }
106  //hard coded minimum longitudinal acceleration
107  virtual double getAxMin()const override
108  {
109  double value = -3.0;
110  static const std::string name = prefix_ + "axMin";
111  get(name,value);
112  return value;
113  }
114  //static trajectory tracking offset in longitudinal direction, which should be compensated by tracking controller
115  virtual double getExStatic()const override
116  {
117  double value = 0.0;
118  static const std::string name = prefix_ + "exStatic";
119  get(name,value);
120  return value;
121  }
122  //static trajectory tracking offset in lateral direction, which should be compensated by tracking controller
123  virtual double getEyStatic()const override
124  {
125  double value = 0.0;
126  static const std::string name = prefix_ + "eyStatic";
127  get(name,value);
128  return value;
129  }
130  //the maximum controllable steering angle
131  virtual double getDeltaMax()const override
132  {
133  double value = 1.0;
134  static const std::string name = prefix_ + "deltaMax";
135  get(name,value);
136  return value;
137  }
138  //the minimum controllable steering angle
139  virtual double getDeltaMin()const override
140  {
141  double value = -1.0;
142  static const std::string name = prefix_ + "deltaMin";
143  get(name,value);
144  return value;
145  }
146  //steering angle: maximum absolute control input change per control update. Maximum steering rate then depends on execution rate of controller.
147  virtual double getDDeltaMax()const override
148  {
149  double value = 0.8;
150  static const std::string name = prefix_ + "dDeltaMax";
151  get(name,value);
152  return value;
153  }
154  //returns gain for braking torque calculation
155  virtual double getBrakingTorqueGain()const override
156  {
157  double value = 0.0;
158  static const std::string name = prefix_ + "brakingTorqueGain";
159  get(name,value);
160  return value;
161  }
162  //returns maxium braking torque rate
163  virtual double getDBrakingTorqueMax()const override
164  {
165  double value = 0.0;
166  static const std::string name = prefix_ + "dBrakingTorqueMax";
167  get(name,value);
168  return value;
169  }
170  //reverse controller: control gain for speed error (P)
171  virtual double getKPev_r()const override
172  {
173  double value = 0.0;
174  static const std::string name = prefix_ + "kPev_r";
175  get(name,value);
176  return value;
177  }
178  //reverse controller: control gain for integrated speed error (I)
179  virtual double getKIev_r()const override
180  {
181  double value = 0.0;
182  static const std::string name = prefix_ + "kIev_r";
183  get(name,value);
184  return value;
185  }
186  //reverse controller: control gain for x error (P)
187  virtual double getKPex_r()const override
188  {
189  double value = 0.0;
190  static const std::string name = prefix_ + "kPex_r";
191  get(name,value);
192  return value;
193  }
194  //reverse controller: control gain for integrated x error (I)
195  virtual double getKIex_r()const override
196  {
197  double value = 0.0;
198  static const std::string name = prefix_ + "kIex_r";
199  get(name,value);
200  return value;
201  }
202  //reverse controller: control gain for y error (P)
203  virtual double getKPey_r()const override
204  {
205  double value = 0.0;
206  static const std::string name = prefix_ + "kPey_r";
207  get(name,value);
208  return value;
209  }
210  //reverse controller: control gain for psi error (P)
211  virtual double getKPepsi_r()const override
212  {
213  double value = 0.0;
214  static const std::string name = prefix_ + "kPepsi_r";
215  get(name,value);
216  return value;
217  }
218  //reverse controller: control gain for integrated psi error (I)
219  virtual double getKIepsi_r()const override
220  {
221  double value = 0.0;
222  static const std::string name = prefix_ + "kIepsi_r";
223  get(name,value);
224  return value;
225  }
226  //gain for steering rate limiter
227  virtual double getSteeringRateLimiterGain()const override
228  {
229  double value = 1.3;
230  static const std::string name = prefix_ + "steeringRateLimiterGain";
231  get(name,value);
232  return value;
233  }
234  };
235  }
236  }
237 }
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