ADORe
ADORe is a modular open source software library and toolkit for decision making, planning, control and simulation of automated vehicles
ap_longitudinal_planner.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 namespace adore
18 {
19  namespace params
20  {
26  {
27  public:
29  virtual double getWeightPos() const =0;
30 
32  virtual double getWeightVel() const =0;
33 
35  virtual double getWeightAcc() const =0;
36 
38  virtual double getWeightJerk() const =0;
39 
41  virtual double getWeightEndPos() const =0;
42 
44  virtual double getWeightEndVel() const =0;
45 
47  virtual double getWeightEndAcc() const =0;
48 
50  virtual double getSlackPos() const =0;
51 
53  virtual double getSlackVel() const =0;
54 
56  virtual double getSlackAcc() const =0;
57 
59  virtual double getAccLB() const=0;
60 
62  virtual double getAccUB() const=0;
63 
65  virtual double getAccUBSlow() const=0;
66 
68  virtual double getVAccUBSlow() const=0;
69 
71  virtual double getComfortAccLB() const=0;
72 
74  virtual double getComfortAccUB() const=0;
75 
77  virtual double getJerkLB() const=0;
78 
80  virtual double getJerkUB() const=0;
81 
83  virtual double getAccLatUB() const=0;
84 
86  virtual double getAccLatUB_minVelocity() const=0;
87 
89  virtual double getConstraintClearancePos() const=0;
90 
92  virtual double getConstraintClearanceVel() const=0;
93 
95  virtual double getMinWidthStop() const=0;
96 
98  virtual double getMinWidthSlow() const=0;
99 
101  virtual double getMinWidthSlowSpeed() const=0;
102 
104  virtual double getMinWidthFast() const=0;
105 
107  virtual double getMinWidthFastSpeed() const=0;
108 
110  virtual double getMaxCPUTime() const=0;
111 
113  virtual bool stopAtRedLights_always_before()const=0;
114 
116  virtual double stopAtRedLights_max_connection_length() const=0;
120  virtual double getStopDistanceToConflictPoint()const=0;
121  };
122  }
123 }
abstract class containing parameters related to configuring the longitudinal planner
Definition: ap_longitudinal_planner.h:26
virtual double getMaxCPUTime() const =0
getMaxCPUTime returns the maximum cpu time for one plan computation
virtual double getAccLatUB() const =0
getAccLatUB returns the absolute lateral acceleration bound which has to be maintained by reducing sp...
virtual double getVAccUBSlow() const =0
getVAccUBSlow returns speed up to which slow speed acceleration is used
virtual double getAccUBSlow() const =0
getAccUBSlow returns acceleration upper bound at low speeds
virtual double getJerkUB() const =0
getJerkLB returns longitudinal jerk upper bound
virtual double getAccLatUB_minVelocity() const =0
getAccLatUB_minVelocity returns the minimum velocity, which is always feasible despite getAccLatUB
virtual double getMinWidthFastSpeed() const =0
getMinWidthFastSpeed returns the fast speed to be applied, if lane width equals minWidthFast: Should ...
virtual double stopAtRedLights_max_connection_length() const =0
stopAtRedLights_max_connection_length returns the maximum length for which clearance based on tcd sta...
virtual bool stopAtRedLights_always_before() const =0
determin stop mode for red lights: true - always before red light, continue driving after; false - ba...
virtual double getMinWidthStop() const =0
getMinWidthStop returns the minimum lane width, below/at which vehicle stops: Should be greater or eq...
virtual double getSlackVel() const =0
getSlackVel returns maximum slack of soft-constraints for velocity
virtual double getConstraintClearanceVel() const =0
getConstraintClearanceVel returns the offset of the reference from the velocity constraints
virtual double getComfortAccUB() const =0
getAccUB returns longitudinal acceleration upper bound
virtual double getWeightPos() const =0
getWeightPos returns cost function weight for quadratic position error term
virtual double getWeightEndPos() const =0
getWeightEndPos returns cost function weight for quadratic position error term at end point
virtual double getWeightVel() const =0
getWeightVel returns cost function weight for quadratic velocity error term
virtual double getMinWidthSlow() const =0
getMinWidthSlow returns the minimum lane width, below/at which vehicle moves slowly: Should be greate...
virtual double getWeightJerk() const =0
getWeightJerk returns cost function weight for quadratic jerk term
virtual double getSlackPos() const =0
getSlackPos returns maximum slack of soft-constraints for position
virtual double getWeightEndAcc() const =0
getWeightEndAcc returns cost function weight for quadratic acceleration term at end point
virtual double getAccUB() const =0
getAccUB returns longitudinal acceleration upper bound
virtual double getJerkLB() const =0
getJerkLB returns longitudinal jerk lower bound
virtual double getSlackAcc() const =0
getSlackAcc returns maximum slack of soft-constraints for acceleration
virtual double getStopDistanceToConflictPoint() const =0
distance between stop position and conflict point
virtual double getComfortAccLB() const =0
getAccLB returns longitudinal acceleration lower bound
virtual double getMinWidthFast() const =0
getMinWidthFast returns the minimum lane width, below/at which vehicle moves fast: Should be greater ...
virtual double getWeightEndVel() const =0
getWeightEndVel returns cost function weight for quadratic velocity error term at end point
virtual double getWeightAcc() const =0
getWeightAcc returns cost function weight for quadratic acceleration term
virtual double getAccLB() const =0
getAccLB returns longitudinal acceleration lower bound
virtual double getConstraintClearancePos() const =0
getConstraintClearancePos returns the longitudinal offset of the reference from the position constrai...
virtual double getMinWidthSlowSpeed() const =0
getMinWidthSlowSpeed returns the slow speed to be applied, if lane width equals minWidthSlow: Should ...
Definition: areaofeffectconverter.h:20