ADORe
ADORe is a modular open source software library and toolkit for decision making, planning, control and simulation of automated vehicles
p_emergency_operation.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 
16 #pragma once
17 
18 #include <ros/ros.h>
21 
22 namespace adore
23 {
24  namespace if_ROS
25  {
26  namespace params
27  {
29  {
30  public:
31  PEmergencyOperation(ros::NodeHandle n,std::string prefix)
32  :ROSParam(n,prefix + "emergency_operation/")
33  {
34  }
35  //lateral path tracking gain for terminal maneuver
36  virtual double getKy()const override
37  {
38  double value = 0.05;
39  static const std::string name = prefix_ + "kyTerm";
40  get(name,value);
41  return value;
42  }
43  //lateral path tracking gain for terminal maneuver
44  virtual double getKpsi()const override
45  {
46  double value = 0.4;
47  static const std::string name = prefix_ + "kpsiTerm";
48  get(name,value);
49  return value;
50  }
51  //hard coded longitudinal minimum acceleration
52  virtual double getamin()const override
53  {
54  double value = -3.0;
55  static const std::string name = prefix_ + "axMinTerm";
56  get(name,value);
57  return value;
58  }
59  //hard coded maximum longitudinal acceleration
60  virtual double getamax()const override
61  {
62  double value = 2.0;
63  static const std::string name = prefix_ + "axMaxTerm";
64  get(name,value);
65  return value;
66  }
67  virtual double getDeltaMax()const override
68  {
69  double value = 1.0;
70  static const std::string name = prefix_ + "deltaMaxTerm";
71  get(name,value);
72  return value;
73  }
74  virtual double getDeltaMin()const override
75  {
76  double value = -1.0;
77  static const std::string name = prefix_ + "deltaMinTerm";
78  get(name,value);
79  return value;
80  }
81  virtual double getEmergencyManeuverAMin()const override
82  {
83  double value = -3.0;
84  static const std::string name = prefix_ + "emergencyManeuverAMin";
85  get(name,value);
86  return value;
87  }
88  virtual double getEmergencyManeuverAMax()const override
89  {
90  double value = -1.0;
91  static const std::string name = prefix_ + "emergencyManeuverAMax";
92  get(name,value);
93  return value;
94  }
95  virtual double getEmergencyManeuverAStall()const override
96  {
97  double value = -2.0;
98  static const std::string name = prefix_ + "emergencyManeuverAStall";
99  get(name,value);
100  return value;
101  }
102  virtual double getEmergencyManeuverTStall()const override
103  {
104  double value = 0.5;
105  static const std::string name = prefix_ + "emergencyManeuverTStall";
106  get(name,value);
107  return value;
108  }
109  virtual double getEmergencyManeuverJMin()const override
110  {
111  double value = -10.0;
112  static const std::string name = prefix_ + "emergencyManeuverJMin";
113  get(name,value);
114  return value;
115  }
116  };
117  }
118  }
119 }
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_emergency_operation.h:29
virtual double getEmergencyManeuverAMin() const override
Definition: p_emergency_operation.h:81
virtual double getKy() const override
Definition: p_emergency_operation.h:36
virtual double getamax() const override
Definition: p_emergency_operation.h:60
virtual double getEmergencyManeuverAStall() const override
Definition: p_emergency_operation.h:95
virtual double getDeltaMax() const override
Definition: p_emergency_operation.h:67
PEmergencyOperation(ros::NodeHandle n, std::string prefix)
Definition: p_emergency_operation.h:31
virtual double getKpsi() const override
Definition: p_emergency_operation.h:44
virtual double getEmergencyManeuverJMin() const override
Definition: p_emergency_operation.h:109
virtual double getEmergencyManeuverTStall() const override
Definition: p_emergency_operation.h:102
virtual double getDeltaMin() const override
Definition: p_emergency_operation.h:74
virtual double getEmergencyManeuverAMax() const override
Definition: p_emergency_operation.h:88
virtual double getamin() const override
Definition: p_emergency_operation.h:52
abstract class containing parameters concerning emergency operation behaviour
Definition: ap_emergency_operation.h:25
Definition: areaofeffectconverter.h:20