ADORe
ADORe is a modular open source software library and toolkit for decision making, planning, control and simulation of automated vehicles
p_trajectory_generation.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 #include <ros/ros.h>
20 
21 namespace adore
22 {
23  namespace if_ROS
24  {
25  namespace params
26  {
28  {
29  public:
30  PTrajectoryGeneration(ros::NodeHandle n,std::string prefix)
31  :ROSParam(n,prefix + "trajectory_generation/")
32  {
33  }
34  //cor to planning point: movement of planning point shall planned by the trajectory planner
35  virtual double get_rho()const override
36  {
37  double value = 2.2;
38  static const std::string name = prefix_ + "rho";
39  get(name,value);
40  return value;
41  }
42  //zero dynamics integration length
43  virtual double getZDIntegrationLength()const override
44  {
45  double value = 3.0;
46  static const std::string name = prefix_ + "zd_integration_length";
47  get(name,value);
48  return value;
49  }
50  //zero dynamics step size
51  virtual double getZDIntegrationStep()const override
52  {
53  double value = 0.01;
54  static const std::string name = prefix_ + "zd_integration_step";
55  get(name,value);
56  return value;
57  }
58  //number of set points in set-point request
59  virtual int getSetPointCount()const override
60  {
61  int value = 100;
62  static const std::string name = prefix_ + "set_point_count";
63  get(name,value);
64  return value;
65  }
67  virtual double getEmergencyManeuverDelay()const override
68  {
69  double value = 0.5;
70  static const std::string name = prefix_ + "emergency_maneuver_delay";
71  get(name,value);
72  return value;
73  }
74 
75  };
76  }
77  }
78 }
Definition: ros_com_patterns.h:179
std::string prefix_
Definition: ros_com_patterns.h:181
void get(const std::string &name, T &result) const
Definition: ros_com_patterns.h:186
Definition: p_trajectory_generation.h:28
virtual double getZDIntegrationStep() const override
zero dynamics step size
Definition: p_trajectory_generation.h:51
virtual int getSetPointCount() const override
number of set points in set-point request
Definition: p_trajectory_generation.h:59
PTrajectoryGeneration(ros::NodeHandle n, std::string prefix)
Definition: p_trajectory_generation.h:30
virtual double get_rho() const override
cor to planning point: movement of planning point shall planned by the trajectory planner
Definition: p_trajectory_generation.h:35
virtual double getZDIntegrationLength() const override
zero dynamics integration length
Definition: p_trajectory_generation.h:43
virtual double getEmergencyManeuverDelay() const override
time after which emergency maneuver kicks in
Definition: p_trajectory_generation.h:67
abstract class containing parameters to configure the behaviour of trajectory generation
Definition: ap_trajectory_generation.h:26
Definition: areaofeffectconverter.h:20