ADORe
ADORe is a modular open source software library and toolkit for decision making, planning, control and simulation of automated vehicles
p_prediction.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  PPrediction(ros::NodeHandle n,std::string prefix)
31  :ROSParam(n,prefix + "prediction/")
32  {
33  }
35  virtual double get_roadbased_prediction_duration()const override
36  {
37  double value = 5.0;
38  static const std::string name = prefix_ + "roadbased_prediction_duration";
39  get(name,value);
40  return value;
41  }
43  virtual double get_roadbased_expected_acc_ub()const override
44  {
45  double value = 0.0;
46  static const std::string name = prefix_ + "roadbased_expected_acc_ub";
47  get(name,value);
48  return value;
49  }
51  virtual double get_roadbased_expected_acc_ub_delay()const override
52  {
53  double value = 0.0;
54  static const std::string name = prefix_ + "roadbased_expected_acc_ub_delay";
55  get(name,value);
56  return value;
57  }
59  virtual double get_roadbased_expected_acc_lb()const override
60  {
61  double value = -3.0;
62  static const std::string name = prefix_ + "roadbased_expected_acc_lb";
63  get(name,value);
64  return value;
65  }
67  virtual double get_roadbased_expected_vel_ub()const override
68  {
69  double value = 30.0;
70  static const std::string name = prefix_ + "roadbased_expected_vel_ub";
71  get(name,value);
72  return value;
73  }
75  virtual double get_roadbased_worstcase_acc_ub()const override
76  {
77  double value = 3.0;
78  static const std::string name = prefix_ + "roadbased_worstcase_acc_ub";
79  get(name,value);
80  return value;
81  }
83  virtual double get_roadbased_worstcase_acc_ub_delay()const override
84  {
85  double value = 0.0;
86  static const std::string name = prefix_ + "roadbased_worstcase_acc_ub_delay";
87  get(name,value);
88  return value;
89  }
91  virtual double get_roadbased_worstcase_acc_lb()const override
92  {
93  double value = -10.0;
94  static const std::string name = prefix_ + "roadbased_worstcase_acc_lb";
95  get(name,value);
96  return value;
97  }
99  virtual double get_roadbased_worstcase_vel_ub()const override
100  {
101  double value = 30.0;
102  static const std::string name = prefix_ + "roadbased_worstcase_vel_ub";
103  get(name,value);
104  return value;
105  }
107  virtual double get_roadbased_heading_deviation_ub()const override
108  {
109  double value = M_PI*0.25;
110  static const std::string name = prefix_ + "roadbased_heading_deviation_ub";
111  get(name,value);
112  return value;
113  }
115  virtual double get_roadbased_lat_precision()const override
116  {
117  double value = 0.2;
118  static const std::string name = prefix_ + "roadbased_lat_precision";
119  get(name,value);
120  return value;
121  }
123  virtual double get_roadbased_lat_error()const override
124  {
125  double value = 0.1;
126  static const std::string name = prefix_ + "roadbased_lat_error";
127  get(name,value);
128  return value;
129  }
131  virtual double get_roadbased_lon_error()const override
132  {
133  double value = 0.5;
134  static const std::string name = prefix_ + "roadbased_lon_error";
135  get(name,value);
136  return value;
137  }
139  virtual double get_roadbased_time_headway()const override
140  {
141  double value = 2.0;
142  static const std::string name = prefix_ + "roadbased_time_headway";
143  get(name,value);
144  return value;
145  }
147  virtual double get_roadbased_time_leeway()const override
148  {
149  double value = 1.0;
150  static const std::string name = prefix_ + "roadbased_time_leeway";
151  get(name,value);
152  return value;
153  }
155  virtual double get_offroad_prediction_duration()const override
156  {
157  double value = 5.0;
158  static const std::string name = prefix_ + "offroad_prediction_duration";
159  get(name,value);
160  return value;
161  }
163  virtual double get_offroad_expected_acc_ub()const override
164  {
165  double value = 0.0;
166  static const std::string name = prefix_ + "offroad_expected_acc_ub";
167  get(name,value);
168  return value;
169  }
171  virtual double get_offroad_expected_acc_lb()const override
172  {
173  double value = -3.0;
174  static const std::string name = prefix_ + "offroad_expected_acc_lb";
175  get(name,value);
176  return value;
177  }
179  virtual double get_offroad_expected_vel_ub()const override
180  {
181  double value = 30.0;
182  static const std::string name = prefix_ + "offroad_expected_vel_ub";
183  get(name,value);
184  return value;
185  }
187  virtual double get_offroad_worstcase_acc_ub()const override
188  {
189  double value = 3.0;
190  static const std::string name = prefix_ + "offroad_worstcase_acc_ub";
191  get(name,value);
192  return value;
193  }
195  virtual double get_offroad_worstcase_acc_ub_delay()const override
196  {
197  double value = 0.0;
198  static const std::string name = prefix_ + "offroad_worstcase_acc_ub_delay";
199  get(name,value);
200  return value;
201  }
203  virtual double get_offroad_worstcase_acc_lb()const override
204  {
205  double value = -10.0;
206  static const std::string name = prefix_ + "offroad_worstcase_acc_lb";
207  get(name,value);
208  return value;
209  }
211  virtual double get_offroad_worstcase_vel_ub()const override
212  {
213  double value = 30.0;
214  static const std::string name = prefix_ + "offroad_worstcase_vel_ub";
215  get(name,value);
216  return value;
217  }
219  virtual double get_offroad_lat_precision()const override
220  {
221  double value = 0.2;
222  static const std::string name = prefix_ + "offroad_lat_precision";
223  get(name,value);
224  return value;
225  }
227  virtual double get_offroad_lat_error()const override
228  {
229  double value = 0.1;
230  static const std::string name = prefix_ + "offroad_lat_error";
231  get(name,value);
232  return value;
233  }
235  virtual double get_offroad_lon_error()const override
236  {
237  double value = 0.5;
238  static const std::string name = prefix_ + "offroad_lon_error";
239  get(name,value);
240  return value;
241  }
243  virtual double get_offroad_time_headway()const override
244  {
245  double value = 2.0;
246  static const std::string name = prefix_ + "offroad_time_headway";
247  get(name,value);
248  return value;
249  }
251  virtual double get_offroad_time_leeway()const override
252  {
253  double value = 1.0;
254  static const std::string name = prefix_ + "offroad_time_leeway";
255  get(name,value);
256  return value;
257  }
259  virtual double get_area_of_interest_shrink()const override
260  {
261  double value = 0.3;
262  static const std::string name = prefix_ + "area_of_interest_shrink";
263  get(name,value);
264  return value;
265  }
267  virtual double get_area_of_effect_shrink()const override
268  {
269  double value = 0.0;
270  static const std::string name = prefix_ + "area_of_effect_shrink";
271  get(name,value);
272  return value;
273  }
276  {
277  bool value = true;
278  static const std::string name = prefix_ + "worstcase_filter_precedence";
279  get(name,value);
280  return value;
281  }
283  virtual bool get_worstcase_filter_tcd()const
284  {
285  bool value = true;
286  static const std::string name = prefix_ + "worstcase_filter_tcd";
287  get(name,value);
288  return value;
289  }
292  {
293  int value=0;
294  static const std::string name = prefix_ + "setbased_prediction_strategy";
295  get(name,value);
296  return value;
297  }
299  virtual double get_prediction_width_ub()const
300  {
301  double value = 10.0;
302  static const std::string name = prefix_ + "prediction_width_ub";
303  get(name,value);
304  return value;
305  }
307  virtual double get_prediction_width_lb()const
308  {
309  double value = 0.5;
310  static const std::string name = prefix_ + "prediction_width_lb";
311  get(name,value);
312  return value;
313  }
314 
315  };
316  }
317  }
318 }
#define M_PI
Definition: arraymatrixtools.h:24
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_prediction.h:28
virtual double get_roadbased_heading_deviation_ub() const override
maximum difference between object and road heading for object to be matchable to road
Definition: p_prediction.h:107
virtual bool get_worstcase_filter_tcd() const
filtering of tcd for worstcase maneuvers:
Definition: p_prediction.h:283
virtual double get_roadbased_expected_vel_ub() const override
maximum velocity for normal behavior for objects that can be matched to road
Definition: p_prediction.h:67
virtual double get_roadbased_expected_acc_lb() const override
minimum acceleration for normal behavior for objects that can be matched to road
Definition: p_prediction.h:59
virtual double get_roadbased_worstcase_acc_lb() const override
minimum acceleration for worst-case for objects that can be matched to road
Definition: p_prediction.h:91
virtual double get_offroad_expected_acc_lb() const override
minimum acceleration for normal behavior for objects that can not be matched to road
Definition: p_prediction.h:171
virtual double get_area_of_effect_shrink() const override
filtering out all static objects not inside area of effect
Definition: p_prediction.h:267
virtual double get_offroad_time_leeway() const override
time buffer behind object (object predicted to leave a location given seconds later)
Definition: p_prediction.h:251
virtual int get_setbased_prediction_strategy() const
returns prediction strategy: 0 width of object, 1 width of road, 2 width of object-> width of road
Definition: p_prediction.h:291
virtual double get_roadbased_expected_acc_ub_delay() const override
delay after which expected_acc_ub is applied
Definition: p_prediction.h:51
virtual double get_roadbased_lon_error() const override
assumed maximum longitudinal detection error for objects that can be matched to road (buffer zone)
Definition: p_prediction.h:131
virtual double get_offroad_prediction_duration() const override
prediction duration for objects that can not be matched to road
Definition: p_prediction.h:155
virtual double get_offroad_lat_precision() const override
precision of object shape approximation in lateral direction for objects that can not be matched to r...
Definition: p_prediction.h:219
virtual double get_offroad_lon_error() const override
assumed maximum longitudinal detection error for objects that can not be matched to road
Definition: p_prediction.h:235
virtual bool get_worstcase_filter_precedence() const
filtering of precedence rules for worstcase maneuvers:
Definition: p_prediction.h:275
virtual double get_offroad_worstcase_acc_ub_delay() const override
delay after which worstcase_acc_ub is applied
Definition: p_prediction.h:195
virtual double get_offroad_expected_vel_ub() const override
maximum velocity for normal behavior for objects that can not be matched to road
Definition: p_prediction.h:179
virtual double get_offroad_time_headway() const override
time buffer ahead of an object (objrect predicted to arrive given seconds earlier at a location)
Definition: p_prediction.h:243
virtual double get_offroad_worstcase_acc_ub() const override
maximum acceleration for worst-case behavior for objects that can not be matched to road
Definition: p_prediction.h:187
virtual double get_offroad_lat_error() const override
assumed maximum lateral detection error for objects that can not be matched to road
Definition: p_prediction.h:227
virtual double get_roadbased_time_leeway() const override
time buffer behind object (object predicted to leave a location given seconds later)
Definition: p_prediction.h:147
virtual double get_roadbased_prediction_duration() const override
prediction duration for objects that can be matched to road
Definition: p_prediction.h:35
virtual double get_prediction_width_lb() const
returns the minimum width for a prediction
Definition: p_prediction.h:307
virtual double get_roadbased_worstcase_vel_ub() const override
maximum velocity for worst-case for objects that can be matched to road
Definition: p_prediction.h:99
virtual double get_roadbased_worstcase_acc_ub_delay() const override
delay after which worstcase_acc_ub is applied
Definition: p_prediction.h:83
virtual double get_prediction_width_ub() const
returns maximum width for a prediction
Definition: p_prediction.h:299
virtual double get_roadbased_worstcase_acc_ub() const override
maximum acceleration for worst-case behavior for objects that can be matched to road
Definition: p_prediction.h:75
virtual double get_roadbased_time_headway() const override
time buffer ahead of an object (objrect predicted to arrive given seconds earlier at a location)
Definition: p_prediction.h:139
virtual double get_offroad_worstcase_acc_lb() const override
minimum acceleration for worst-case behavior for objects that can not be matched to road
Definition: p_prediction.h:203
virtual double get_offroad_expected_acc_ub() const override
maximum acceleration for normal behavior for objects that can not be matched to road
Definition: p_prediction.h:163
virtual double get_area_of_interest_shrink() const override
distinction between clutter and static traffic objects: how far into road has object to extend to be ...
Definition: p_prediction.h:259
PPrediction(ros::NodeHandle n, std::string prefix)
Definition: p_prediction.h:30
virtual double get_roadbased_lat_precision() const override
precision of object shape approximation in lateral direction for objects that can be matched to road
Definition: p_prediction.h:115
virtual double get_roadbased_lat_error() const override
assumed maximum lateral detection error for objects that can be matched to road (buffer zone)
Definition: p_prediction.h:123
virtual double get_offroad_worstcase_vel_ub() const override
maximum velocity for worst-case behavior for objects that can not be matched to road
Definition: p_prediction.h:211
virtual double get_roadbased_expected_acc_ub() const override
maximum acceleration for normal behavior for objects that can be matched to road
Definition: p_prediction.h:43
parameter interface for parameters related to prediction
Definition: ap_prediction.h:28
Definition: areaofeffectconverter.h:20