ADORe
ADORe is a modular open source software library and toolkit for decision making, planning, control and simulation of automated vehicles
ap_trajectory_generation_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:
30 
31  virtual double get_rho()const
32  {
33  return 2.7;
34  }
36  virtual double getZDIntegrationLength()const override
37  {
38  return 10.0;
39  }
41  virtual double getZDIntegrationStep()const override
42  {
43  return 0.01;
44  }
45  virtual int getSetPointCount()const override
46  {
47  return 100;
48  }
50  virtual double getEmergencyManeuverDelay()const override
51  {
52  return 0.5;
53  }
54  };
55  }
56 }
a dummy implementation for testing purposes
Definition: ap_trajectory_generation_dummy.h:27
virtual double getEmergencyManeuverDelay() const override
time after which emergency maneuver kicks in
Definition: ap_trajectory_generation_dummy.h:50
virtual int getSetPointCount() const override
number of set points in set-point request
Definition: ap_trajectory_generation_dummy.h:45
virtual double getZDIntegrationLength() const override
zero dynamics integration length
Definition: ap_trajectory_generation_dummy.h:36
virtual double get_rho() const
cor to planning point: movement of planning point shall planned by the trajectory planner
Definition: ap_trajectory_generation_dummy.h:31
virtual double getZDIntegrationStep() const override
zero dynamics step size
Definition: ap_trajectory_generation_dummy.h:41
abstract class containing parameters to configure the behaviour of trajectory generation
Definition: ap_trajectory_generation.h:26
Definition: areaofeffectconverter.h:20