ADORe
ADORe is a modular open source software library and toolkit for decision making, planning, control and simulation of automated vehicles
stdconverter.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  * Daniel Heß - initial API and implementation
13  ********************************************************************************/
14 #pragma once
15 
16 #include <std_msgs/Float32.h>
17 #include <std_msgs/Float64.h>
18 #include <std_msgs/String.h>
19 #include <std_msgs/Int8.h>
20 #include <std_msgs/Int64.h>
21 #include <std_msgs/Bool.h>
22 #include <nav_msgs/Odometry.h>
23 #include <tf2/LinearMath/Quaternion.h>
24 #include <tf/transform_broadcaster.h>
25 #include <geometry_msgs/Pose.h>
26 #include <geometry_msgs/Twist.h>
27 
28 
29 
30 
31 namespace adore
32 {
33  namespace if_ROS
34  {
38  struct StdConverter
39  {
40  public:
41  std_msgs::Float64 operator()(double value)
42  {
43  std_msgs::Float64 m;
44  m.data = value;
45  return m;
46  }
47  void operator()(std_msgs::Float64ConstPtr msg, double* value)
48  {
49  *value = msg.get()->data;
50  }
51  std_msgs::Bool operator()(bool value)
52  {
53  std_msgs::Bool m;
54  m.data = value;
55  return m;
56  }
57  void operator()(std_msgs::BoolConstPtr msg, bool* value)
58  {
59  *value = msg.get()->data;
60  }
61 
62  std_msgs::String operator()(std::string value)
63  {
64  std_msgs::String m;
65  m.data = value;
66  return m;
67  }
68  void operator()(std_msgs::StringConstPtr msg, std::string* value)
69  {
70  *value = msg.get()->data;
71  }
72  void operator()(std_msgs::StringConstPtr msg, std::string& value)
73  {
74  value = msg.get()->data;
75  }
76  void operator()(const std_msgs::String& msg_string, std::string& std_string)
77  {
78  std_string = msg_string.data;
79  }
80 
81  std_msgs::Int64 operator()(int64_t value)
82  {
83  std_msgs::Int64 m;
84  m.data = value;
85  return m;
86  }
87  void operator()(std_msgs::Int64ConstPtr msg, int64_t* value)
88  {
89  *value = msg.get()->data;
90  }
91  void operator()(std_msgs::Int64ConstPtr msg, int64_t& value)
92  {
93  value = msg.get()->data;
94  }
95  void operator()(const std_msgs::Int64& msg, int64_t& std)
96  {
97  std = msg.data;
98  }
99  };
100  }
101 
102 }
Definition: areaofeffectconverter.h:20
Definition: stdconverter.h:39
std_msgs::String operator()(std::string value)
Definition: stdconverter.h:62
std_msgs::Float64 operator()(double value)
Definition: stdconverter.h:41
void operator()(const std_msgs::Int64 &msg, int64_t &std)
Definition: stdconverter.h:95
void operator()(std_msgs::StringConstPtr msg, std::string *value)
Definition: stdconverter.h:68
std_msgs::Int64 operator()(int64_t value)
Definition: stdconverter.h:81
void operator()(std_msgs::Int64ConstPtr msg, int64_t *value)
Definition: stdconverter.h:87
void operator()(std_msgs::Float64ConstPtr msg, double *value)
Definition: stdconverter.h:47
void operator()(const std_msgs::String &msg_string, std::string &std_string)
Definition: stdconverter.h:76
void operator()(std_msgs::BoolConstPtr msg, bool *value)
Definition: stdconverter.h:57
void operator()(std_msgs::Int64ConstPtr msg, int64_t &value)
Definition: stdconverter.h:91
void operator()(std_msgs::StringConstPtr msg, std::string &value)
Definition: stdconverter.h:72
std_msgs::Bool operator()(bool value)
Definition: stdconverter.h:51