ros_sub_pub.hpp
Go to the documentation of this file.
1 
22 #ifndef __ROS_SUB_PUB__
23 #define __ROS_SUB_PUB__
24 #include <ros/ros.h>
25 
26 #include <sensor_msgs/Imu.h>
27 #define MSG_TYPE1 "sensor_msgs/Imu"
28 #define MSG_CLASS1 sensor_msgs::Imu
29 
30 #include <geometry_msgs/Twist.h>
31 #define MSG_TYPE2 "geometry_msgs/Twist"
32 #define MSG_CLASS2 geometry_msgs::Twist
33 
34 #include <std_msgs/String.h>
35 #define MSG_TYPE3 "std_msgs/String"
36 #define MSG_CLASS3 std_msgs::String
37 
38 // #include <xxx/yy.h>
39 // #define MSG_TYPE4 "xxx/yy"
40 // #define MSG_CLASS4 xxx::yy
41 
42 // ......
43 
44 // #include <xxx/yy.h>
45 // #define MSG_TYPE10 "xxx/yy"
46 // #define MSG_CLASS10 xxx::yy
47 
48 # define SUB_MAX 50 // max number of subscriber callbacks
49 
50 template <typename T, int i>
51 void sub_cb(const T &msg);
52 
53 template <typename T>
54 void (*sub_callbacks[])(const T &);
55 
56 template <typename T>
57 ros::Subscriber nh_sub(std::string topic_name, ros::NodeHandle nh, int i);
58 
59 ros::Subscriber topic_subscriber(std::string topic_name, std::string msg_type, ros::NodeHandle nh, int i);
60 
61 ros::Publisher topic_publisher(std::string topic_name, std::string msg_type, ros::NodeHandle nh);
62 
63 template<typename T>
64 void deserialize_pub(uint8_t* buffer_ptr, size_t msg_size, int i);
65 
66 void deserialize_publish(uint8_t* buffer_ptr, size_t msg_size, std::string msg_type, int i);
67 
68 
69 template <typename T>
70 void (*sub_callbacks[])(const T &)=
71 {
72  sub_cb<T,0>, sub_cb<T,1>, sub_cb<T,2>, sub_cb<T,3>, sub_cb<T,4>,
73  sub_cb<T,5>, sub_cb<T,6>, sub_cb<T,7>, sub_cb<T,8>, sub_cb<T,9>,
74  sub_cb<T,10>, sub_cb<T,11>, sub_cb<T,12>, sub_cb<T,13>, sub_cb<T,14>,
75  sub_cb<T,15>, sub_cb<T,16>, sub_cb<T,17>, sub_cb<T,18>, sub_cb<T,19>,
76  sub_cb<T,20>, sub_cb<T,21>, sub_cb<T,22>, sub_cb<T,23>, sub_cb<T,24>,
77  sub_cb<T,25>, sub_cb<T,26>, sub_cb<T,27>, sub_cb<T,28>, sub_cb<T,29>,
78  sub_cb<T,30>, sub_cb<T,31>, sub_cb<T,32>, sub_cb<T,33>, sub_cb<T,34>,
79  sub_cb<T,35>, sub_cb<T,36>, sub_cb<T,37>, sub_cb<T,38>, sub_cb<T,39>,
80  sub_cb<T,40>, sub_cb<T,41>, sub_cb<T,42>, sub_cb<T,43>, sub_cb<T,44>,
81  sub_cb<T,45>, sub_cb<T,46>, sub_cb<T,47>, sub_cb<T,48>, sub_cb<T,49>
82 };
83 
84 template <typename T>
85 ros::Subscriber nh_sub(std::string topic_name, ros::NodeHandle nh, int i)
86 {
87  return nh.subscribe(topic_name, 10, sub_callbacks<T>[i], ros::TransportHints().tcpNoDelay());
88 }
89 
90 ros::Subscriber topic_subscriber(std::string topic_name, std::string msg_type, ros::NodeHandle nh, int i)
91 {
92  #ifdef MSG_TYPE1
93  if (msg_type == MSG_TYPE1)
94  return nh_sub<MSG_CLASS1>(topic_name, nh, i);
95  #endif
96  #ifdef MSG_TYPE2
97  if (msg_type == MSG_TYPE2)
98  return nh_sub<MSG_CLASS2>(topic_name, nh, i);
99  #endif
100  #ifdef MSG_TYPE3
101  if (msg_type == MSG_TYPE3)
102  return nh_sub<MSG_CLASS3>(topic_name, nh, i);
103  #endif
104  #ifdef MSG_TYPE4
105  if (msg_type == MSG_TYPE4)
106  return nh_sub<MSG_CLASS4>(topic_name, nh, i);
107  #endif
108  #ifdef MSG_TYPE5
109  if (msg_type == MSG_TYPE5)
110  return nh_sub<MSG_CLASS5>(topic_name, nh, i);
111  #endif
112  #ifdef MSG_TYPE6
113  if (msg_type == MSG_TYPE6)
114  return nh_sub<MSG_CLASS6>(topic_name, nh, i);
115  #endif
116  #ifdef MSG_TYPE7
117  if (msg_type == MSG_TYPE7)
118  return nh_sub<MSG_CLASS7>(topic_name, nh, i);
119  #endif
120  #ifdef MSG_TYPE8
121  if (msg_type == MSG_TYPE8)
122  return nh_sub<MSG_CLASS8>(topic_name, nh, i);
123  #endif
124  #ifdef MSG_TYPE9
125  if (msg_type == MSG_TYPE9)
126  return nh_sub<MSG_CLASS9>(topic_name, nh, i);
127  #endif
128  #ifdef MSG_TYPE10
129  if (msg_type == MSG_TYPE10)
130  return nh_sub<MSG_CLASS10>(topic_name, nh, i);
131  #endif
132  ROS_FATAL("Invalid ROS msg_type \"%s\" in configuration!", msg_type.c_str());
133  exit(1);
134 }
135 
136 ros::Publisher topic_publisher(std::string topic_name, std::string msg_type, ros::NodeHandle nh)
137 {
138  #ifdef MSG_TYPE1
139  if (msg_type == MSG_TYPE1)
140  return nh.advertise<MSG_CLASS1>(topic_name, 10);
141  #endif
142  #ifdef MSG_TYPE2
143  if (msg_type == MSG_TYPE2)
144  return nh.advertise<MSG_CLASS2>(topic_name, 10);
145  #endif
146  #ifdef MSG_TYPE3
147  if (msg_type == MSG_TYPE3)
148  return nh.advertise<MSG_CLASS3>(topic_name, 10);
149  #endif
150  #ifdef MSG_TYPE4
151  if (msg_type == MSG_TYPE4)
152  return nh.advertise<MSG_CLASS4>(topic_name, 10);
153  #endif
154  #ifdef MSG_TYPE5
155  if (msg_type == MSG_TYPE5)
156  return nh.advertise<MSG_CLASS5>(topic_name, 10);
157  #endif
158  #ifdef MSG_TYPE6
159  if (msg_type == MSG_TYPE6)
160  return nh.advertise<MSG_CLASS6>(topic_name, 10);
161  #endif
162  #ifdef MSG_TYPE7
163  if (msg_type == MSG_TYPE7)
164  return nh.advertise<MSG_CLASS7>(topic_name, 10);
165  #endif
166  #ifdef MSG_TYPE8
167  if (msg_type == MSG_TYPE8)
168  return nh.advertise<MSG_CLASS8>(topic_name, 10);
169  #endif
170  #ifdef MSG_TYPE9
171  if (msg_type == MSG_TYPE9)
172  return nh.advertise<MSG_CLASS9>(topic_name, 10);
173  #endif
174  #ifdef MSG_TYPE10
175  if (msg_type == MSG_TYPE10)
176  return nh.advertise<MSG_CLASS10>(topic_name, 10);
177  #endif
178  ROS_FATAL("Invalid ROS msg_type \"%s\" in configuration!", msg_type.c_str());
179  exit(1);
180 }
181 
182 void deserialize_publish(uint8_t* buffer_ptr, size_t msg_size, std::string msg_type, int i)
183 {
184  #ifdef MSG_TYPE1
185  if (msg_type == MSG_TYPE1)
186  return deserialize_pub<MSG_CLASS1>(buffer_ptr, msg_size, i);
187  #endif
188  #ifdef MSG_TYPE2
189  if (msg_type == MSG_TYPE2)
190  return deserialize_pub<MSG_CLASS2>(buffer_ptr, msg_size, i);
191  #endif
192  #ifdef MSG_TYPE3
193  if (msg_type == MSG_TYPE3)
194  return deserialize_pub<MSG_CLASS3>(buffer_ptr, msg_size, i);
195  #endif
196  #ifdef MSG_TYPE4
197  if (msg_type == MSG_TYPE4)
198  return deserialize_pub<MSG_CLASS4>(buffer_ptr, msg_size, i);
199  #endif
200  #ifdef MSG_TYPE5
201  if (msg_type == MSG_TYPE5)
202  return deserialize_pub<MSG_CLASS5>(buffer_ptr, msg_size, i);
203  #endif
204  #ifdef MSG_TYPE6
205  if (msg_type == MSG_TYPE6)
206  return deserialize_pub<MSG_CLASS6>(buffer_ptr, msg_size, i);
207  #endif
208  #ifdef MSG_TYPE7
209  if (msg_type == MSG_TYPE7)
210  return deserialize_pub<MSG_CLASS7>(buffer_ptr, msg_size, i);
211  #endif
212  #ifdef MSG_TYPE8
213  if (msg_type == MSG_TYPE8)
214  return deserialize_pub<MSG_CLASS8>(buffer_ptr, msg_size, i);
215  #endif
216  #ifdef MSG_TYPE9
217  if (msg_type == MSG_TYPE9)
218  return deserialize_pub<MSG_CLASS9>(buffer_ptr, msg_size, i);
219  #endif
220  #ifdef MSG_TYPE10
221  if (msg_type == MSG_TYPE10)
222  return deserialize_pub<MSG_CLASS10>(buffer_ptr, msg_size, i);
223  #endif
224  ROS_FATAL("Invalid ROS msg_type \"%s\" in configuration!", msg_type.c_str());
225  exit(1);
226 }
227 
228 #endif
ros::Subscriber nh_sub(std::string topic_name, ros::NodeHandle nh, int i)
Definition: ros_sub_pub.hpp:85
#define ROS_FATAL(...)
#define MSG_TYPE1
Definition: ros_sub_pub.hpp:27
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
void deserialize_publish(uint8_t *buffer_ptr, size_t msg_size, std::string msg_type, int i)
ros::Subscriber topic_subscriber(std::string topic_name, std::string msg_type, ros::NodeHandle nh, int i)
Definition: ros_sub_pub.hpp:90
#define MSG_TYPE2
Definition: ros_sub_pub.hpp:31
void(* sub_callbacks[])(const T &)
Definition: ros_sub_pub.hpp:54
#define MSG_CLASS1
Definition: ros_sub_pub.hpp:28
#define MSG_CLASS3
Definition: ros_sub_pub.hpp:36
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
void sub_cb(const T &msg)
Definition: bridge_node.cpp:65
void deserialize_pub(uint8_t *buffer_ptr, size_t msg_size, int i)
ros::Publisher topic_publisher(std::string topic_name, std::string msg_type, ros::NodeHandle nh)
#define MSG_CLASS2
Definition: ros_sub_pub.hpp:32
#define MSG_TYPE3
Definition: ros_sub_pub.hpp:35


swarm_ros_bridge
Author(s):
autogenerated on Tue Feb 21 2023 03:43:52