ADORe
ADORe is a modular open source software library and toolkit for decision making, planning, control and simulation of automated vehicles
ap_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  * Daniel Heß - initial API and implementation
13  ********************************************************************************/
14 
15 #pragma once
16 
17 
18 namespace adore
19 {
20  namespace params
21  {
22 
28  {
29  public:
31  virtual double get_roadbased_prediction_duration()const=0;
33  virtual double get_roadbased_expected_acc_ub()const=0;
35  virtual double get_roadbased_expected_acc_ub_delay()const=0;
37  virtual double get_roadbased_expected_acc_lb()const=0;
39  virtual double get_roadbased_expected_vel_ub()const=0;
41  virtual double get_roadbased_worstcase_acc_ub()const=0;
43  virtual double get_roadbased_worstcase_acc_ub_delay()const=0;
45  virtual double get_roadbased_worstcase_acc_lb()const=0;
47  virtual double get_roadbased_worstcase_vel_ub()const=0;
49  virtual double get_roadbased_heading_deviation_ub()const=0;
51  virtual double get_roadbased_lat_precision()const=0;
53  virtual double get_roadbased_lat_error()const=0;
55  virtual double get_roadbased_lon_error()const=0;
57  virtual double get_roadbased_time_headway()const =0;
59  virtual double get_roadbased_time_leeway()const =0;
61  virtual double get_offroad_prediction_duration()const=0;
63  virtual double get_offroad_expected_acc_ub()const=0;
65  virtual double get_offroad_expected_acc_lb()const=0;
67  virtual double get_offroad_expected_vel_ub()const=0;
69  virtual double get_offroad_worstcase_acc_ub()const=0;
71  virtual double get_offroad_worstcase_acc_ub_delay()const=0;
73  virtual double get_offroad_worstcase_acc_lb()const=0;
75  virtual double get_offroad_worstcase_vel_ub()const=0;
77  virtual double get_offroad_lat_precision()const=0;
79  virtual double get_offroad_lat_error()const=0;
81  virtual double get_offroad_lon_error()const=0;
83  virtual double get_offroad_time_headway()const =0;
85  virtual double get_offroad_time_leeway()const =0;
87  virtual double get_area_of_interest_shrink()const =0;
89  virtual double get_area_of_effect_shrink()const =0;
91  virtual bool get_worstcase_filter_precedence()const=0;
93  virtual bool get_worstcase_filter_tcd()const=0;
95  virtual int get_setbased_prediction_strategy()const=0;
97  virtual double get_prediction_width_ub()const=0;
99  virtual double get_prediction_width_lb()const=0;
100  };
101  }
102 }
parameter interface for parameters related to prediction
Definition: ap_prediction.h:28
virtual double get_offroad_expected_acc_ub() const =0
maximum acceleration for normal behavior for objects that can not be matched to road
virtual double get_offroad_expected_acc_lb() const =0
minimum acceleration for normal behavior for objects that can not be matched to road
virtual double get_prediction_width_lb() const =0
returns the minimum width for a prediction
virtual double get_offroad_worstcase_vel_ub() const =0
maximum velocity for worst-case behavior for objects that can not be matched to road
virtual bool get_worstcase_filter_tcd() const =0
filtering of tcd for worstcase maneuvers:
virtual double get_roadbased_lat_error() const =0
assumed maximum lateral detection error for objects that can be matched to road (buffer zone)
virtual double get_offroad_time_headway() const =0
time buffer ahead of an object (objrect predicted to arrive given seconds earlier at a location)
virtual double get_roadbased_worstcase_vel_ub() const =0
maximum velocity for worst-case for objects that can be matched to road
virtual double get_area_of_effect_shrink() const =0
filtering out all static objects not inside area of effect
virtual bool get_worstcase_filter_precedence() const =0
filtering of precedence rules for worstcase maneuvers:
virtual double get_prediction_width_ub() const =0
returns maximum width for a prediction
virtual double get_roadbased_time_leeway() const =0
time buffer behind object (object predicted to leave a location given seconds later)
virtual double get_roadbased_expected_acc_ub() const =0
maximum acceleration for normal behavior for objects that can be matched to road
virtual double get_offroad_worstcase_acc_ub() const =0
maximum acceleration for worst-case behavior for objects that can not be matched to road
virtual double get_offroad_worstcase_acc_ub_delay() const =0
delay after which worstcase_acc_ub is applied
virtual double get_roadbased_expected_acc_lb() const =0
minimum acceleration for normal behavior for objects that can be matched to road
virtual double get_area_of_interest_shrink() const =0
distinction between clutter and static traffic objects: how far into road has object to extend to be ...
virtual double get_roadbased_heading_deviation_ub() const =0
maximum difference between object and road heading for object to be matchable to road
virtual double get_offroad_expected_vel_ub() const =0
maximum velocity for normal behavior for objects that can not be matched to road
virtual double get_roadbased_worstcase_acc_ub() const =0
maximum acceleration for worst-case behavior for objects that can be matched to road
virtual double get_roadbased_lat_precision() const =0
precision of object shape approximation in lateral direction for objects that can be matched to road
virtual double get_roadbased_expected_vel_ub() const =0
maximum velocity for normal behavior for objects that can be matched to road
virtual double get_roadbased_worstcase_acc_ub_delay() const =0
delay after which worstcase_acc_ub is applied
virtual double get_offroad_lat_precision() const =0
precision of object shape approximation in lateral direction for objects that can not be matched to r...
virtual double get_roadbased_lon_error() const =0
assumed maximum longitudinal detectionfor objects that can be matched to road (buffer zone)
virtual int get_setbased_prediction_strategy() const =0
returns prediction strategy: 0 width of object, 1 width of road, 2 width of object-> width of road
virtual double get_offroad_lon_error() const =0
assumed maximum longitudinal detection error for objects that can not be matched to road
virtual double get_roadbased_time_headway() const =0
time buffer ahead of an object (objrect predicted to arrive given seconds earlier at a location)
virtual double get_roadbased_expected_acc_ub_delay() const =0
delay after which expected_acc_ub is applied
virtual double get_offroad_worstcase_acc_lb() const =0
minimum acceleration for worst-case behavior for objects that can not be matched to road
virtual double get_roadbased_prediction_duration() const =0
prediction duration for objects that can be matched to road
virtual double get_offroad_time_leeway() const =0
time buffer behind object (object predicted to leave a location given seconds later)
virtual double get_offroad_lat_error() const =0
assumed maximum lateral detection error for objects that can not be matched to road
virtual double get_offroad_prediction_duration() const =0
prediction duration for objects that can not be matched to road
virtual double get_roadbased_worstcase_acc_lb() const =0
minimum acceleration for worst-case for objects that can be matched to road
Definition: areaofeffectconverter.h:20