22 #ifndef __ROS_SUB_PUB__ 23 #define __ROS_SUB_PUB__ 26 #include <sensor_msgs/Imu.h> 27 #define MSG_TYPE1 "sensor_msgs/Imu" 28 #define MSG_CLASS1 sensor_msgs::Imu 30 #include <geometry_msgs/Twist.h> 31 #define MSG_TYPE2 "geometry_msgs/Twist" 32 #define MSG_CLASS2 geometry_msgs::Twist 34 #include <std_msgs/String.h> 35 #define MSG_TYPE3 "std_msgs/String" 36 #define MSG_CLASS3 std_msgs::String 48 # define SUB_MAX 50 // max number of subscriber callbacks 50 template <
typename T,
int i>
66 void deserialize_publish(uint8_t* buffer_ptr,
size_t msg_size, std::string msg_type,
int i);
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>
94 return nh_sub<MSG_CLASS1>(topic_name, nh, i);
98 return nh_sub<MSG_CLASS2>(topic_name, nh, i);
102 return nh_sub<MSG_CLASS3>(topic_name, nh, i);
105 if (msg_type == MSG_TYPE4)
106 return nh_sub<MSG_CLASS4>(topic_name, nh, i);
109 if (msg_type == MSG_TYPE5)
110 return nh_sub<MSG_CLASS5>(topic_name, nh, i);
113 if (msg_type == MSG_TYPE6)
114 return nh_sub<MSG_CLASS6>(topic_name, nh, i);
117 if (msg_type == MSG_TYPE7)
118 return nh_sub<MSG_CLASS7>(topic_name, nh, i);
121 if (msg_type == MSG_TYPE8)
122 return nh_sub<MSG_CLASS8>(topic_name, nh, i);
125 if (msg_type == MSG_TYPE9)
126 return nh_sub<MSG_CLASS9>(topic_name, nh, i);
129 if (msg_type == MSG_TYPE10)
130 return nh_sub<MSG_CLASS10>(topic_name, nh, i);
132 ROS_FATAL(
"Invalid ROS msg_type \"%s\" in configuration!", msg_type.c_str());
151 if (msg_type == MSG_TYPE4)
152 return nh.
advertise<MSG_CLASS4>(topic_name, 10);
155 if (msg_type == MSG_TYPE5)
156 return nh.
advertise<MSG_CLASS5>(topic_name, 10);
159 if (msg_type == MSG_TYPE6)
160 return nh.
advertise<MSG_CLASS6>(topic_name, 10);
163 if (msg_type == MSG_TYPE7)
164 return nh.
advertise<MSG_CLASS7>(topic_name, 10);
167 if (msg_type == MSG_TYPE8)
168 return nh.
advertise<MSG_CLASS8>(topic_name, 10);
171 if (msg_type == MSG_TYPE9)
172 return nh.
advertise<MSG_CLASS9>(topic_name, 10);
175 if (msg_type == MSG_TYPE10)
176 return nh.
advertise<MSG_CLASS10>(topic_name, 10);
178 ROS_FATAL(
"Invalid ROS msg_type \"%s\" in configuration!", msg_type.c_str());
186 return deserialize_pub<MSG_CLASS1>(buffer_ptr, msg_size, i);
190 return deserialize_pub<MSG_CLASS2>(buffer_ptr, msg_size, i);
194 return deserialize_pub<MSG_CLASS3>(buffer_ptr, msg_size, i);
197 if (msg_type == MSG_TYPE4)
198 return deserialize_pub<MSG_CLASS4>(buffer_ptr, msg_size, i);
201 if (msg_type == MSG_TYPE5)
202 return deserialize_pub<MSG_CLASS5>(buffer_ptr, msg_size, i);
205 if (msg_type == MSG_TYPE6)
206 return deserialize_pub<MSG_CLASS6>(buffer_ptr, msg_size, i);
209 if (msg_type == MSG_TYPE7)
210 return deserialize_pub<MSG_CLASS7>(buffer_ptr, msg_size, i);
213 if (msg_type == MSG_TYPE8)
214 return deserialize_pub<MSG_CLASS8>(buffer_ptr, msg_size, i);
217 if (msg_type == MSG_TYPE9)
218 return deserialize_pub<MSG_CLASS9>(buffer_ptr, msg_size, i);
221 if (msg_type == MSG_TYPE10)
222 return deserialize_pub<MSG_CLASS10>(buffer_ptr, msg_size, i);
224 ROS_FATAL(
"Invalid ROS msg_type \"%s\" in configuration!", msg_type.c_str());
ros::Subscriber nh_sub(std::string topic_name, ros::NodeHandle nh, int i)
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)
void(* sub_callbacks[])(const T &)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
void sub_cb(const T &msg)
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)