ADORe
ADORe is a modular open source software library and toolkit for decision making, planning, control and simulation of automated vehicles
ap_longitudinal_planner_dummy.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
17 
18 namespace adore
19 {
20  namespace params
21  {
27  {
28 
29  public:
31  virtual double getWeightPos() const
32  {
33  return 2.0;
34  }
36  virtual double getWeightVel() const
37  {
38  return 5.0;
39  }
40 
42  virtual double getWeightAcc() const
43  {
44  return 5.0;
45  }
46 
48  virtual double getWeightJerk() const
49  {
50  return 1.0;
51  }
52 
54  virtual double getWeightEndPos() const
55  {
56  return 0.0;
57  }
58 
60  virtual double getWeightEndVel() const
61  {
62  return 0.0;
63  }
64 
66  virtual double getWeightEndAcc() const
67  {
68  return 0.0;
69  }
70 
72  virtual double getSlackPos() const
73  {
74  return 0.5;
75  }
76 
78  virtual double getSlackVel() const
79  {
80  return 0.01;
81  }
82 
84  virtual double getSlackAcc() const
85  {
86  return 5.0;
87  }
88 
90  virtual double getAccLB() const
91  {
92  return -3.0;
93  }
94 
96  virtual double getAccUB() const
97  {
98  return 2.0;
99  }
100 
101 
103  virtual double getComfortAccLB() const override
104  {
105  return -1.0;
106  }
107 
109  virtual double getComfortAccUB() const override
110  {
111  return 1.0;
112  }
113 
115  virtual double getJerkLB() const
116  {
117  return -100.0;
118  }
119 
121  virtual double getJerkUB() const
122  {
123  return 100.0;
124  }
125 
127  virtual double getAccLatUB() const
128  {
129  return 2.0;
130  }
131 
133  virtual double getAccLatUB_minVelocity() const
134  {
135  return 1.0;
136  }
137 
139  virtual double getConstraintClearancePos() const
140  {
141  return 0.1;
142  }
143 
145  virtual double getConstraintClearanceVel() const
146  {
147  return 0.05;
148  }
149 
151  virtual double getMaxCPUTime() const
152  {
153  return 0.05;
154  }
155 
159  virtual double getStopDistanceToConflictPoint()const
160  {
161  return 5.0;
162  }
163  };
164  }
165 }
a dummy implementation for testing purposes
Definition: ap_longitudinal_planner_dummy.h:27
virtual double getJerkUB() const
getJerkLB returns longitudinal jerk upper bound
Definition: ap_longitudinal_planner_dummy.h:121
virtual double getMaxCPUTime() const
getMaxCPUTime returns the maximum cpu time for one plan computation
Definition: ap_longitudinal_planner_dummy.h:151
virtual double getComfortAccLB() const override
getAccLB returns longitudinal acceleration lower bound
Definition: ap_longitudinal_planner_dummy.h:103
virtual double getSlackAcc() const
getSlackAcc returns maximum slack of soft-constraints for acceleration
Definition: ap_longitudinal_planner_dummy.h:84
virtual double getConstraintClearanceVel() const
getConstraintClearanceVel returns the offset of the reference from the velocity constraints
Definition: ap_longitudinal_planner_dummy.h:145
virtual double getWeightPos() const
getWeightPos returns cost function weight for quadratic position error term
Definition: ap_longitudinal_planner_dummy.h:31
virtual double getAccUB() const
getAccUB returns longitudinal acceleration upper bound
Definition: ap_longitudinal_planner_dummy.h:96
virtual double getWeightEndVel() const
getWeightEndVel returns cost function weight for quadratic velocity error term at end point
Definition: ap_longitudinal_planner_dummy.h:60
virtual double getAccLatUB_minVelocity() const
getAccLatUB_minVelocity returns the minimum velocity, which is always feasible despite getAccLatUB
Definition: ap_longitudinal_planner_dummy.h:133
virtual double getAccLB() const
getAccLB returns longitudinal acceleration lower bound
Definition: ap_longitudinal_planner_dummy.h:90
virtual double getWeightAcc() const
getWeightAcc returns cost function weight for quadratic acceleration term
Definition: ap_longitudinal_planner_dummy.h:42
virtual double getJerkLB() const
getJerkLB returns longitudinal jerk lower bound
Definition: ap_longitudinal_planner_dummy.h:115
virtual double getComfortAccUB() const override
getAccUB returns longitudinal acceleration upper bound
Definition: ap_longitudinal_planner_dummy.h:109
virtual double getWeightVel() const
getWeightVel returns cost function weight for quadratic velocity error term
Definition: ap_longitudinal_planner_dummy.h:36
virtual double getStopDistanceToConflictPoint() const
distance between stop position and conflict point
Definition: ap_longitudinal_planner_dummy.h:159
virtual double getWeightJerk() const
getWeightJerk returns cost function weight for quadratic jerk term
Definition: ap_longitudinal_planner_dummy.h:48
virtual double getWeightEndPos() const
getWeightEndPos returns cost function weight for quadratic position error term at end point
Definition: ap_longitudinal_planner_dummy.h:54
virtual double getSlackPos() const
getSlackPos returns maximum slack of soft-constraints for position
Definition: ap_longitudinal_planner_dummy.h:72
virtual double getAccLatUB() const
getAccLatUB returns the absolute lateral acceleration bound which has to be maintained by reducing sp...
Definition: ap_longitudinal_planner_dummy.h:127
virtual double getConstraintClearancePos() const
getConstraintClearancePos returns the offset of the reference from the position constraints
Definition: ap_longitudinal_planner_dummy.h:139
virtual double getSlackVel() const
getSlackVel returns maximum slack of soft-constraints for velocity
Definition: ap_longitudinal_planner_dummy.h:78
virtual double getWeightEndAcc() const
getWeightEndAcc returns cost function weight for quadratic acceleration term at end point
Definition: ap_longitudinal_planner_dummy.h:66
abstract class containing parameters related to configuring the longitudinal planner
Definition: ap_longitudinal_planner.h:26
Definition: areaofeffectconverter.h:20