ADORe
ADORe is a modular open source software library and toolkit for decision making, planning, control and simulation of automated vehicles
ap_lateral_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  public:
30  virtual double getWeightPos() const
31  {
32  return 6.0;
33  }
35  virtual double getWeightVel() const
36  {
37  return 1.0;
38  }
39 
41  virtual double getWeightAcc() const
42  {
43  return 1.0;
44  }
45 
47  virtual double getWeightJerk() const
48  {
49  return 1.0;
50  }
51 
53  virtual double getWeightEndPos() const
54  {
55  return 0.0;
56  }
57 
59  virtual double getWeightEndVel() const
60  {
61  return 0.0;
62  }
63 
65  virtual double getWeightEndAcc() const
66  {
67  return 0.0;
68  }
69 
71  virtual double getSlackPos() const
72  {
73  return 0.1;
74  }
75 
77  virtual double getSlackVel() const
78  {
79  return 0.1;
80  }
81 
83  virtual double getSlackAcc() const
84  {
85  return 0.1;
86  }
87 
89  virtual double getAccLB() const
90  {
91  return -10.0;
92  }
93 
95  virtual double getAccUB() const
96  {
97  return 10.0;
98  }
99 
101  virtual double getJerkLB() const
102  {
103  return -100.0;
104  }
105 
107  virtual double getJerkUB() const
108  {
109  return 100.0;
110  }
111 
113  virtual double getCurvatureUB() const
114  {
115  return 1.0/7.0;
116  }
117 
119  virtual double getCurvatureLB() const
120  {
121  return -1.0/7.0;
122  }
123 
125  virtual double getRelativeHeadingUB() const
126  {
127  return 0.7;
128  }
129 
131  virtual double getRelativeHeadingLB() const
132  {
133  return -0.7;
134  }
135 
137  virtual double getMergeConstraintDelay() const
138  {
139  return 3.0;
140  }
141 
143  virtual double getMaxCPUTime() const
144  {
145  return 0.05;
146  }
147 
148  };
149  }
150 }
a dummy implementation for testing purposes
Definition: ap_lateral_planner_dummy.h:27
virtual double getSlackPos() const
getSlackPos returns maximum slack of soft-constraints for position
Definition: ap_lateral_planner_dummy.h:71
virtual double getWeightEndVel() const
getWeightEndVel returns cost function weight for quadratic velocity error term at end point
Definition: ap_lateral_planner_dummy.h:59
virtual double getRelativeHeadingLB() const
getRelativeHeadingLB returns lower bound on heading deviation from current lane's coordinate system
Definition: ap_lateral_planner_dummy.h:131
virtual double getWeightEndAcc() const
getWeightEndAcc returns cost function weight for quadratic acceleration term at end point
Definition: ap_lateral_planner_dummy.h:65
virtual double getRelativeHeadingUB() const
getRelativeHeadingUB returns upper bound on heading deviation from current lane's coordinate system
Definition: ap_lateral_planner_dummy.h:125
virtual double getWeightVel() const
getWeightVel returns cost function weight for quadratic velocity error term
Definition: ap_lateral_planner_dummy.h:35
virtual double getMergeConstraintDelay() const
getMergeConstraintDelay returns a time-delay after which lateral position constraints are activated,...
Definition: ap_lateral_planner_dummy.h:137
virtual double getSlackVel() const
getSlackVel returns maximum slack of soft-constraints for velocity
Definition: ap_lateral_planner_dummy.h:77
virtual double getWeightEndPos() const
getWeightEndPos returns cost function weight for quadratic position error term at end point
Definition: ap_lateral_planner_dummy.h:53
virtual double getJerkLB() const
getJerkLB returns lateral jerk lower bound
Definition: ap_lateral_planner_dummy.h:101
virtual double getAccUB() const
getAccUB returns lateral acceleration upper bound
Definition: ap_lateral_planner_dummy.h:95
virtual double getJerkUB() const
getJerkLB returns lateral jerk upper bound
Definition: ap_lateral_planner_dummy.h:107
virtual double getWeightJerk() const
getWeightJerk returns cost function weight for quadratic jerk term
Definition: ap_lateral_planner_dummy.h:47
virtual double getWeightPos() const
getWeightPos returns cost function weight for quadratic position error term
Definition: ap_lateral_planner_dummy.h:30
virtual double getSlackAcc() const
getSlackAcc returns maximum slack of soft-constraints for acceleration
Definition: ap_lateral_planner_dummy.h:83
virtual double getMaxCPUTime() const
getMaxCPUTime returns the maximum cpu time for one plan computation
Definition: ap_lateral_planner_dummy.h:143
virtual double getCurvatureUB() const
getCurvatureUB returns maximum curvature of path (relevant at low speeds)
Definition: ap_lateral_planner_dummy.h:113
virtual double getAccLB() const
getAccLB returns lateral acceleration lower bound
Definition: ap_lateral_planner_dummy.h:89
virtual double getCurvatureLB() const
getCurvatureLB returns minimum curvature of path (relevant at low speeds)
Definition: ap_lateral_planner_dummy.h:119
virtual double getWeightAcc() const
getWeightAcc returns cost function weight for quadratic acceleration term
Definition: ap_lateral_planner_dummy.h:41
abstract class containing parameters related to configuring the lateral planner
Definition: ap_lateral_planner.h:26
Definition: areaofeffectconverter.h:20