ADORe
ADORe is a modular open source software library and toolkit for decision making, planning, control and simulation of automated vehicles
ap_tactical_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 namespace adore
17 {
18  namespace params
19  {
25  {
26  public:
27  virtual double getGlobalSpeedLimit()const =0;
28  virtual double getResetRadius()const =0;
29  virtual double getAccLatUB()const =0;
30  virtual double getAccLatUB_minVelocity()const =0;
31  virtual double getAccLonUB()const =0;
32  virtual double getAccLonLB()const =0;
33  virtual double getFrontTimeGap()const =0;
34  virtual double getRearTimeGap()const =0;
35  virtual double getFrontSGap()const =0;
36  virtual double getLowerBoundFrontSGapForLF()const =0;
37  virtual double getRearSGap()const =0;
38  virtual double getChaseReferenceOffset()const =0;
39  virtual double getLeadReferenceOffset()const =0;
40  virtual double getFrontReferenceOffset()const =0;
41  virtual double getGapAlignment()const =0;
42  virtual double getAssumedNominalAccelerationMinimum()const =0;
43  virtual double getMaxNavcostLoss()const=0;
44  virtual bool getEnforceMonotonousNavigationCost()const=0;
46  virtual double getLVResetVelocity()const=0;
47  virtual double getTimeoutForLangechangeSuppression()const=0;
48  virtual double getCollisionDetectionFrontBufferSpace()const =0;
49  virtual double getCollisionDetectionLateralPrecision()const =0;
50  virtual double getCollisionDetectionLateralError()const =0;
51  virtual double getCollisionDetectionLongitudinalError()const =0;
52  virtual double getNominalSwathAccelerationError()const=0;
54  virtual int getCoercionPreventionStrategy()const=0;
58  virtual double getIndicatorLookahead()const =0;
59  virtual double getHorizonStopReferenceDistance()const=0;
63  virtual double getTerminateAfterFirstStopThresholdSpeed()const =0;
64  };
65  }
66 }
abstract classs containing parameters to configure aspects and constraints of the tactical planner
Definition: ap_tactical_planner.h:25
virtual double getChaseReferenceOffset() const =0
virtual double getAccLatUB() const =0
virtual double getResetRadius() const =0
virtual double getAccLonUB() const =0
virtual int getCoercionPreventionStrategy() const =0
getCoercionPreventionStrategy returns 0 switched off, 1 objective function, 2 constraint
virtual double getGlobalSpeedLimit() const =0
virtual double getAccLonLB() const =0
virtual double getLVResetVelocity() const =0
virtual double getFrontSGap() const =0
virtual bool getEnforceMonotonousNavigationCost() const =0
virtual double getRearSGap() const =0
virtual double getAccLatUB_minVelocity() const =0
virtual double getCollisionDetectionLateralError() const =0
virtual double getTerminateAfterFirstStopThresholdSpeed() const =0
virtual double getRearTimeGap() const =0
virtual double getGapAlignment() const =0
virtual double getLeadReferenceOffset() const =0
virtual double getTimeoutForLangechangeSuppression() const =0
virtual double getMaxNavcostLoss() const =0
virtual double getCollisionDetectionFrontBufferSpace() const =0
virtual double getTimeoutForPreferredLCAfterManuallySetIndicator() const =0
virtual double getFrontReferenceOffset() const =0
virtual double getCollisionDetectionLongitudinalError() const =0
virtual double getFrontTimeGap() const =0
virtual double getCollisionDetectionLateralPrecision() const =0
virtual double getLowerBoundFrontSGapForLF() const =0
virtual double getHorizonStopReferenceDistance() const =0
virtual double getNominalSwathAccelerationError() const =0
virtual double getIndicatorLookahead() const =0
virtual double getAssumedNominalAccelerationMinimum() const =0
Definition: areaofeffectconverter.h:20