ADORe
ADORe is a modular open source software library and toolkit for decision making, planning, control and simulation of automated vehicles
ap_lateral_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 getJerkLB() const=0;
66 
68  virtual double getJerkUB() const=0;
69 
71  virtual double getCurvatureUB() const=0;
72 
74  virtual double getCurvatureLB() const=0;
75 
77  virtual double getRelativeHeadingUB() const=0;
78 
80  virtual double getRelativeHeadingLB() const=0;
81 
83  virtual double getMergeConstraintDelay() const=0;
84 
86  virtual double getHardSafetyDistanceToLaneBoundary() const=0;
87 
89  virtual double getSoftSafetyDistanceToLaneBoundary() const=0;
90 
92  virtual double getMinimumLateralControlSpace() const=0;
93 
95  virtual double getMaxCPUTime() const=0;
96 
98  virtual double getLateralGridScale() const=0;
99 
100  };
101  }
102 }
abstract class containing parameters related to configuring the lateral planner
Definition: ap_lateral_planner.h:26
virtual double getMinimumLateralControlSpace() const =0
getMinimumLateralControlSpace returns the minimum desired lateral control space: If vehicle has more ...
virtual double getRelativeHeadingUB() const =0
getRelativeHeadingUB returns upper bound on heading deviation from current lane's coordinate system
virtual double getJerkLB() const =0
getJerkLB returns lateral jerk lower bound
virtual double getWeightEndAcc() const =0
getWeightEndAcc returns cost function weight for quadratic acceleration term at end point
virtual double getSlackAcc() const =0
getSlackAcc returns maximum slack of soft-constraints for acceleration
virtual double getAccLB() const =0
getAccLB returns lateral acceleration lower bound
virtual double getAccUB() const =0
getAccUB returns lateral acceleration upper bound
virtual double getSlackVel() const =0
getSlackVel returns maximum slack of soft-constraints for velocity
virtual double getSlackPos() const =0
getSlackPos returns maximum slack of soft-constraints for position
virtual double getWeightAcc() const =0
getWeightAcc returns cost function weight for quadratic acceleration term
virtual double getLateralGridScale() const =0
getLateralGridScale returns the size of a grid step d for lateral variations of a maneuver: maneuver ...
virtual double getWeightVel() const =0
getWeightVel returns cost function weight for quadratic velocity error term
virtual double getJerkUB() const =0
getJerkLB returns lateral jerk upper bound
virtual double getCurvatureUB() const =0
getCurvatureUB returns maximum curvature of path (relevant at low speeds)
virtual double getCurvatureLB() const =0
getCurvatureLB returns minimum curvature of path (relevant at low speeds)
virtual double getHardSafetyDistanceToLaneBoundary() const =0
getHardSafetyDistanceToLaneBoundary returns the minimum distance between lane boundary and vehicle si...
virtual double getWeightEndVel() const =0
getWeightEndVel returns cost function weight for quadratic velocity error term at end point
virtual double getMergeConstraintDelay() const =0
getMergeConstraintDelay returns a time-delay after which lateral position constraints are activated,...
virtual double getSoftSafetyDistanceToLaneBoundary() const =0
getSoftSafetyDistanceToLaneBoundary returns the minimum distance between lane boundary and vehicle si...
virtual double getMaxCPUTime() const =0
getMaxCPUTime returns the maximum cpu time for one plan computation
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 getRelativeHeadingLB() const =0
getRelativeHeadingLB returns lower bound on heading deviation from current lane's coordinate system
virtual double getWeightJerk() const =0
getWeightJerk returns cost function weight for quadratic jerk term
Definition: areaofeffectconverter.h:20