ADORe
ADORe is a modular open source software library and toolkit for decision making, planning, control and simulation of automated vehicles
p_cooperation.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  PCooperation(ros::NodeHandle n,std::string prefix)
31  :ROSParam(n,prefix + "cooperation/")
32  {
33  }
34  virtual int getCooperationMode()const override
35  {
36  int value = 1;
37  static const std::string name = prefix_ + "cooperation_mode";
38  get(name,value);
39  return value;
40  }
41  virtual double getAssumedChaseAcceleration()const override
42  {
43  double value = -1.5;
44  static const std::string name = prefix_ + "assumed_chase_acceleration";
45  get(name,value);
46  return value;
47  }
48  virtual double getNegotiationTime()const override
49  {
50  double value = 0.5;
51  static const std::string name = prefix_ + "negotiation_time";
52  get(name,value);
53  return value;
54  }
55  virtual double getAbsTimeUncertaintyForLC()const override
56  {
57  double value = 1.0;
58  static const std::string name = prefix_ + "abs_time_uncertainly_for_lc";
59  get(name,value);
60  return value;
61  }
62  virtual double getAbsPositionUncertainty()const override
63  {
64  double value = 4.0;
65  static const std::string name = prefix_ + "abs_position_uncertainty";
66  get(name,value);
67  return value;
68  }
69  virtual double getAbsVelocityUncertainty()const override
70  {
71  double value = 2.5;
72  static const std::string name = prefix_ + "abs_velocity_uncertainty";
73  get(name,value);
74  return value;
75  }
76  virtual int getSendRepetitiveMessages()const override
77  {
78  int value = 0;
79  static const std::string name = prefix_ + "send_repetitive_messages";
80  get(name,value);
81  return value;
82  }
83  virtual int getUTMZone()const override
84  {
85  int value = 32;
86  static const std::string name = prefix_ + "utm_zone";
87  get(name,value);
88  return value;
89  }
90  };
91  }
92  }
93 }
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_cooperation.h:28
virtual int getSendRepetitiveMessages() const override
Definition: p_cooperation.h:76
virtual int getCooperationMode() const override
Definition: p_cooperation.h:34
virtual double getAssumedChaseAcceleration() const override
Definition: p_cooperation.h:41
virtual double getAbsTimeUncertaintyForLC() const override
Definition: p_cooperation.h:55
virtual double getNegotiationTime() const override
Definition: p_cooperation.h:48
PCooperation(ros::NodeHandle n, std::string prefix)
Definition: p_cooperation.h:30
virtual double getAbsVelocityUncertainty() const override
Definition: p_cooperation.h:69
virtual double getAbsPositionUncertainty() const override
Definition: p_cooperation.h:62
virtual int getUTMZone() const override
Definition: p_cooperation.h:83
abstract class containing cooperative behaviour parameters
Definition: ap_cooperation.h:26
Definition: areaofeffectconverter.h:20