CommonDataSubscriberRGBD5.cpp
Go to the documentation of this file.
1 /*
2 Copyright (c) 2010-2016, Mathieu Labbe - IntRoLab - Universite de Sherbrooke
3 All rights reserved.
4 
5 Redistribution and use in source and binary forms, with or without
6 modification, are permitted provided that the following conditions are met:
7  * Redistributions of source code must retain the above copyright
8  notice, this list of conditions and the following disclaimer.
9  * Redistributions in binary form must reproduce the above copyright
10  notice, this list of conditions and the following disclaimer in the
11  documentation and/or other materials provided with the distribution.
12  * Neither the name of the Universite de Sherbrooke nor the
13  names of its contributors may be used to endorse or promote products
14  derived from this software without specific prior written permission.
15 
16 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
17 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
18 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
19 DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY
20 DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
21 (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
22 LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
23 ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
24 (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
25 SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
26 */
27 
32 #include <cv_bridge/cv_bridge.h>
33 
34 namespace rtabmap_ros {
35 
36 #define IMAGE_CONVERSION() \
37  callbackCalled(); \
38  std::vector<cv_bridge::CvImageConstPtr> imageMsgs(5); \
39  std::vector<cv_bridge::CvImageConstPtr> depthMsgs(5); \
40  rtabmap_ros::toCvShare(image1Msg, imageMsgs[0], depthMsgs[0]); \
41  rtabmap_ros::toCvShare(image2Msg, imageMsgs[1], depthMsgs[1]); \
42  rtabmap_ros::toCvShare(image3Msg, imageMsgs[2], depthMsgs[2]); \
43  rtabmap_ros::toCvShare(image4Msg, imageMsgs[3], depthMsgs[3]); \
44  rtabmap_ros::toCvShare(image5Msg, imageMsgs[4], depthMsgs[4]); \
45  if(!depthMsgs[0].get()) \
46  depthMsgs.clear(); \
47  std::vector<sensor_msgs::CameraInfo> cameraInfoMsgs; \
48  cameraInfoMsgs.push_back(image1Msg->rgb_camera_info); \
49  cameraInfoMsgs.push_back(image2Msg->rgb_camera_info); \
50  cameraInfoMsgs.push_back(image3Msg->rgb_camera_info); \
51  cameraInfoMsgs.push_back(image4Msg->rgb_camera_info); \
52  cameraInfoMsgs.push_back(image5Msg->rgb_camera_info); \
53  std::vector<rtabmap_ros::GlobalDescriptor> globalDescriptorMsgs; \
54  std::vector<std::vector<rtabmap_ros::KeyPoint> > localKeyPoints; \
55  std::vector<std::vector<rtabmap_ros::Point3f> > localPoints3d; \
56  std::vector<cv::Mat> localDescriptors; \
57  if(!image1Msg->global_descriptor.data.empty()) \
58  globalDescriptorMsgs.push_back(image1Msg->global_descriptor); \
59  if(!image2Msg->global_descriptor.data.empty()) \
60  globalDescriptorMsgs.push_back(image2Msg->global_descriptor); \
61  if(!image3Msg->global_descriptor.data.empty()) \
62  globalDescriptorMsgs.push_back(image3Msg->global_descriptor); \
63  if(!image4Msg->global_descriptor.data.empty()) \
64  globalDescriptorMsgs.push_back(image4Msg->global_descriptor); \
65  if(!image5Msg->global_descriptor.data.empty()) \
66  globalDescriptorMsgs.push_back(image5Msg->global_descriptor); \
67  localKeyPoints.push_back(image1Msg->key_points); \
68  localKeyPoints.push_back(image2Msg->key_points); \
69  localKeyPoints.push_back(image3Msg->key_points); \
70  localKeyPoints.push_back(image4Msg->key_points); \
71  localKeyPoints.push_back(image5Msg->key_points); \
72  localPoints3d.push_back(image1Msg->points); \
73  localPoints3d.push_back(image2Msg->points); \
74  localPoints3d.push_back(image3Msg->points); \
75  localPoints3d.push_back(image4Msg->points); \
76  localPoints3d.push_back(image5Msg->points); \
77  localDescriptors.push_back(rtabmap::uncompressData(image1Msg->descriptors)); \
78  localDescriptors.push_back(rtabmap::uncompressData(image2Msg->descriptors)); \
79  localDescriptors.push_back(rtabmap::uncompressData(image3Msg->descriptors)); \
80  localDescriptors.push_back(rtabmap::uncompressData(image4Msg->descriptors)); \
81  localDescriptors.push_back(rtabmap::uncompressData(image5Msg->descriptors));
82 
83 // 5 RGBD
84 void CommonDataSubscriber::rgbd5Callback(
85  const rtabmap_ros::RGBDImageConstPtr& image1Msg,
86  const rtabmap_ros::RGBDImageConstPtr& image2Msg,
87  const rtabmap_ros::RGBDImageConstPtr& image3Msg,
88  const rtabmap_ros::RGBDImageConstPtr& image4Msg,
89  const rtabmap_ros::RGBDImageConstPtr& image5Msg)
90 {
92 
93  nav_msgs::OdometryConstPtr odomMsg; // Null
94  rtabmap_ros::UserDataConstPtr userDataMsg; // Null
95  sensor_msgs::LaserScan scanMsg; // Null
96  sensor_msgs::PointCloud2 scan3dMsg; // Null
97  rtabmap_ros::OdomInfoConstPtr odomInfoMsg; // null
98  commonDepthCallback(odomMsg, userDataMsg, imageMsgs, depthMsgs, cameraInfoMsgs, scanMsg, scan3dMsg, odomInfoMsg, globalDescriptorMsgs, localKeyPoints, localPoints3d, localDescriptors);
99 }
100 void CommonDataSubscriber::rgbd5Scan2dCallback(
101  const rtabmap_ros::RGBDImageConstPtr& image1Msg,
102  const rtabmap_ros::RGBDImageConstPtr& image2Msg,
103  const rtabmap_ros::RGBDImageConstPtr& image3Msg,
104  const rtabmap_ros::RGBDImageConstPtr& image4Msg,
105  const rtabmap_ros::RGBDImageConstPtr& image5Msg,
106  const sensor_msgs::LaserScanConstPtr& scanMsg)
107 {
109 
110  nav_msgs::OdometryConstPtr odomMsg; // Null
111  rtabmap_ros::UserDataConstPtr userDataMsg; // Null
112  sensor_msgs::PointCloud2 scan3dMsg; // Null
113  rtabmap_ros::OdomInfoConstPtr odomInfoMsg; // null
114  commonDepthCallback(odomMsg, userDataMsg, imageMsgs, depthMsgs, cameraInfoMsgs, *scanMsg, scan3dMsg, odomInfoMsg, globalDescriptorMsgs, localKeyPoints, localPoints3d, localDescriptors);
115 }
116 void CommonDataSubscriber::rgbd5Scan3dCallback(
117  const rtabmap_ros::RGBDImageConstPtr& image1Msg,
118  const rtabmap_ros::RGBDImageConstPtr& image2Msg,
119  const rtabmap_ros::RGBDImageConstPtr& image3Msg,
120  const rtabmap_ros::RGBDImageConstPtr& image4Msg,
121  const rtabmap_ros::RGBDImageConstPtr& image5Msg,
122  const sensor_msgs::PointCloud2ConstPtr& scan3dMsg)
123 {
125 
126  nav_msgs::OdometryConstPtr odomMsg; // Null
127  rtabmap_ros::UserDataConstPtr userDataMsg; // Null
128  sensor_msgs::LaserScan scanMsg; // Null
129  rtabmap_ros::OdomInfoConstPtr odomInfoMsg; // null
130  commonDepthCallback(odomMsg, userDataMsg, imageMsgs, depthMsgs, cameraInfoMsgs, scanMsg, *scan3dMsg, odomInfoMsg, globalDescriptorMsgs, localKeyPoints, localPoints3d, localDescriptors);
131 }
132 void CommonDataSubscriber::rgbd5ScanDescCallback(
133  const rtabmap_ros::RGBDImageConstPtr& image1Msg,
134  const rtabmap_ros::RGBDImageConstPtr& image2Msg,
135  const rtabmap_ros::RGBDImageConstPtr& image3Msg,
136  const rtabmap_ros::RGBDImageConstPtr& image4Msg,
137  const rtabmap_ros::RGBDImageConstPtr& image5Msg,
138  const rtabmap_ros::ScanDescriptorConstPtr& scanDescMsg)
139 {
141 
142  nav_msgs::OdometryConstPtr odomMsg; // Null
143  rtabmap_ros::UserDataConstPtr userDataMsg; // Null
144  rtabmap_ros::OdomInfoConstPtr odomInfoMsg; // null
145  if(!scanDescMsg->global_descriptor.data.empty())
146  {
147  globalDescriptorMsgs.push_back(scanDescMsg->global_descriptor);
148  }
149  commonDepthCallback(odomMsg, userDataMsg, imageMsgs, depthMsgs, cameraInfoMsgs, scanDescMsg->scan, scanDescMsg->scan_cloud, odomInfoMsg, globalDescriptorMsgs, localKeyPoints, localPoints3d, localDescriptors);
150 }
151 void CommonDataSubscriber::rgbd5InfoCallback(
152  const rtabmap_ros::RGBDImageConstPtr& image1Msg,
153  const rtabmap_ros::RGBDImageConstPtr& image2Msg,
154  const rtabmap_ros::RGBDImageConstPtr& image3Msg,
155  const rtabmap_ros::RGBDImageConstPtr& image4Msg,
156  const rtabmap_ros::RGBDImageConstPtr& image5Msg,
157  const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg)
158 {
160 
161  nav_msgs::OdometryConstPtr odomMsg; // Null
162  rtabmap_ros::UserDataConstPtr userDataMsg; // Null
163  sensor_msgs::LaserScan scanMsg; // Null
164  sensor_msgs::PointCloud2 scan3dMsg; // Null
165  commonDepthCallback(odomMsg, userDataMsg, imageMsgs, depthMsgs, cameraInfoMsgs, scanMsg, scan3dMsg, odomInfoMsg, globalDescriptorMsgs, localKeyPoints, localPoints3d, localDescriptors);
166 }
167 
168 // 5 RGBD + Odom
169 void CommonDataSubscriber::rgbd5OdomCallback(
170  const nav_msgs::OdometryConstPtr & odomMsg,
171  const rtabmap_ros::RGBDImageConstPtr& image1Msg,
172  const rtabmap_ros::RGBDImageConstPtr& image2Msg,
173  const rtabmap_ros::RGBDImageConstPtr& image3Msg,
174  const rtabmap_ros::RGBDImageConstPtr& image4Msg,
175  const rtabmap_ros::RGBDImageConstPtr& image5Msg)
176 {
178 
179  rtabmap_ros::UserDataConstPtr userDataMsg; // Null
180  sensor_msgs::LaserScan scanMsg; // Null
181  sensor_msgs::PointCloud2 scan3dMsg; // Null
182  rtabmap_ros::OdomInfoConstPtr odomInfoMsg; // null
183  commonDepthCallback(odomMsg, userDataMsg, imageMsgs, depthMsgs, cameraInfoMsgs, scanMsg, scan3dMsg, odomInfoMsg, globalDescriptorMsgs, localKeyPoints, localPoints3d, localDescriptors);
184 }
185 void CommonDataSubscriber::rgbd5OdomScan2dCallback(
186  const nav_msgs::OdometryConstPtr & odomMsg,
187  const rtabmap_ros::RGBDImageConstPtr& image1Msg,
188  const rtabmap_ros::RGBDImageConstPtr& image2Msg,
189  const rtabmap_ros::RGBDImageConstPtr& image3Msg,
190  const rtabmap_ros::RGBDImageConstPtr& image4Msg,
191  const rtabmap_ros::RGBDImageConstPtr& image5Msg,
192  const sensor_msgs::LaserScanConstPtr& scanMsg)
193 {
195 
196  rtabmap_ros::UserDataConstPtr userDataMsg; // Null
197  sensor_msgs::PointCloud2 scan3dMsg; // Null
198  rtabmap_ros::OdomInfoConstPtr odomInfoMsg; // null
199  commonDepthCallback(odomMsg, userDataMsg, imageMsgs, depthMsgs, cameraInfoMsgs, *scanMsg, scan3dMsg, odomInfoMsg, globalDescriptorMsgs, localKeyPoints, localPoints3d, localDescriptors);
200 }
201 void CommonDataSubscriber::rgbd5OdomScan3dCallback(
202  const nav_msgs::OdometryConstPtr & odomMsg,
203  const rtabmap_ros::RGBDImageConstPtr& image1Msg,
204  const rtabmap_ros::RGBDImageConstPtr& image2Msg,
205  const rtabmap_ros::RGBDImageConstPtr& image3Msg,
206  const rtabmap_ros::RGBDImageConstPtr& image4Msg,
207  const rtabmap_ros::RGBDImageConstPtr& image5Msg,
208  const sensor_msgs::PointCloud2ConstPtr& scan3dMsg)
209 {
211 
212  rtabmap_ros::UserDataConstPtr userDataMsg; // Null
213  sensor_msgs::LaserScan scanMsg; // Null
214  rtabmap_ros::OdomInfoConstPtr odomInfoMsg; // null
215  commonDepthCallback(odomMsg, userDataMsg, imageMsgs, depthMsgs, cameraInfoMsgs, scanMsg, *scan3dMsg, odomInfoMsg, globalDescriptorMsgs, localKeyPoints, localPoints3d, localDescriptors);
216 }
217 void CommonDataSubscriber::rgbd5OdomScanDescCallback(
218  const nav_msgs::OdometryConstPtr & odomMsg,
219  const rtabmap_ros::RGBDImageConstPtr& image1Msg,
220  const rtabmap_ros::RGBDImageConstPtr& image2Msg,
221  const rtabmap_ros::RGBDImageConstPtr& image3Msg,
222  const rtabmap_ros::RGBDImageConstPtr& image4Msg,
223  const rtabmap_ros::RGBDImageConstPtr& image5Msg,
224  const rtabmap_ros::ScanDescriptorConstPtr& scanDescMsg)
225 {
227 
228  rtabmap_ros::UserDataConstPtr userDataMsg; // Null
229  rtabmap_ros::OdomInfoConstPtr odomInfoMsg; // null
230  if(!scanDescMsg->global_descriptor.data.empty())
231  {
232  globalDescriptorMsgs.push_back(scanDescMsg->global_descriptor);
233  }
234  commonDepthCallback(odomMsg, userDataMsg, imageMsgs, depthMsgs, cameraInfoMsgs, scanDescMsg->scan, scanDescMsg->scan_cloud, odomInfoMsg, globalDescriptorMsgs, localKeyPoints, localPoints3d, localDescriptors);
235 }
236 void CommonDataSubscriber::rgbd5OdomInfoCallback(
237  const nav_msgs::OdometryConstPtr & odomMsg,
238  const rtabmap_ros::RGBDImageConstPtr& image1Msg,
239  const rtabmap_ros::RGBDImageConstPtr& image2Msg,
240  const rtabmap_ros::RGBDImageConstPtr& image3Msg,
241  const rtabmap_ros::RGBDImageConstPtr& image4Msg,
242  const rtabmap_ros::RGBDImageConstPtr& image5Msg,
243  const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg)
244 {
246 
247  rtabmap_ros::UserDataConstPtr userDataMsg; // Null
248  sensor_msgs::LaserScan scanMsg; // Null
249  sensor_msgs::PointCloud2 scan3dMsg; // Null
250  commonDepthCallback(odomMsg, userDataMsg, imageMsgs, depthMsgs, cameraInfoMsgs, scanMsg, scan3dMsg, odomInfoMsg, globalDescriptorMsgs, localKeyPoints, localPoints3d, localDescriptors);
251 }
252 
253 void CommonDataSubscriber::setupRGBD5Callbacks(
254  ros::NodeHandle & nh,
255  ros::NodeHandle & pnh,
256  bool subscribeOdom,
257  bool subscribeUserData,
258  bool subscribeScan2d,
259  bool subscribeScan3d,
260  bool subscribeScanDesc,
261  bool subscribeOdomInfo,
262  int queueSize,
263  bool approxSync)
264 {
265  ROS_INFO("Setup rgbd5 callback");
266 
267  rgbdSubs_.resize(5);
268  for(int i=0; i<5; ++i)
269  {
271  rgbdSubs_[i]->subscribe(nh, uFormat("rgbd_image%d", i), queueSize);
272  }
273  if(subscribeOdom)
274  {
275  odomSub_.subscribe(nh, "odom", queueSize);
276  if(subscribeScanDesc)
277  {
279  scanDescSub_.subscribe(nh, "scan_descriptor", queueSize);
280  if(subscribeOdomInfo)
281  {
282  subscribedToOdomInfo_ = false;
283  ROS_WARN("subscribe_odom_info ignored...");
284  }
285  SYNC_DECL7(rgbd5OdomScanDesc, approxSync, queueSize, odomSub_, (*rgbdSubs_[0]), (*rgbdSubs_[1]), (*rgbdSubs_[2]), (*rgbdSubs_[3]), (*rgbdSubs_[4]), scanDescSub_);
286  }
287  else if(subscribeScan2d)
288  {
289  subscribedToScan2d_ = true;
290  scanSub_.subscribe(nh, "scan", queueSize);
291  if(subscribeOdomInfo)
292  {
293  subscribedToOdomInfo_ = false;
294  ROS_WARN("subscribe_odom_info ignored...");
295  }
296  SYNC_DECL7(rgbd5OdomScan2d, approxSync, queueSize, odomSub_, (*rgbdSubs_[0]), (*rgbdSubs_[1]), (*rgbdSubs_[2]), (*rgbdSubs_[3]), (*rgbdSubs_[4]), scanSub_);
297  }
298  else if(subscribeScan3d)
299  {
300  subscribedToScan3d_ = true;
301  scan3dSub_.subscribe(nh, "scan_cloud", queueSize);
302  if(subscribeOdomInfo)
303  {
304  subscribedToOdomInfo_ = false;
305  ROS_WARN("subscribe_odom_info ignored...");
306  }
307  SYNC_DECL7(rgbd5OdomScan3d, approxSync, queueSize, odomSub_, (*rgbdSubs_[0]), (*rgbdSubs_[1]), (*rgbdSubs_[2]), (*rgbdSubs_[3]), (*rgbdSubs_[4]), scan3dSub_);
308  }
309  else if(subscribeOdomInfo)
310  {
311  subscribedToOdomInfo_ = true;
312  odomInfoSub_.subscribe(nh, "odom_info", queueSize);
313  SYNC_DECL7(rgbd5OdomInfo, approxSync, queueSize, odomSub_, (*rgbdSubs_[0]), (*rgbdSubs_[1]), (*rgbdSubs_[2]), (*rgbdSubs_[3]), (*rgbdSubs_[4]), odomInfoSub_);
314  }
315  else
316  {
317  SYNC_DECL6(rgbd5Odom, approxSync, queueSize, odomSub_, (*rgbdSubs_[0]), (*rgbdSubs_[1]), (*rgbdSubs_[2]), (*rgbdSubs_[3]), (*rgbdSubs_[4]));
318  }
319  }
320  else
321  {
322  if(subscribeScanDesc)
323  {
325  scanDescSub_.subscribe(nh, "scan_descriptor", queueSize);
326  if(subscribeOdomInfo)
327  {
328  subscribedToOdomInfo_ = false;
329  ROS_WARN("subscribe_odom_info ignored...");
330  }
331  SYNC_DECL6(rgbd5ScanDesc, approxSync, queueSize, (*rgbdSubs_[0]), (*rgbdSubs_[1]), (*rgbdSubs_[2]), (*rgbdSubs_[3]), (*rgbdSubs_[4]), scanDescSub_);
332  }
333  else if(subscribeScan2d)
334  {
335  subscribedToScan2d_ = true;
336  scanSub_.subscribe(nh, "scan", queueSize);
337  if(subscribeOdomInfo)
338  {
339  subscribedToOdomInfo_ = false;
340  ROS_WARN("subscribe_odom_info ignored...");
341  }
342  SYNC_DECL6(rgbd5Scan2d, approxSync, queueSize, (*rgbdSubs_[0]), (*rgbdSubs_[1]), (*rgbdSubs_[2]), (*rgbdSubs_[3]), (*rgbdSubs_[4]), scanSub_);
343  }
344  else if(subscribeScan3d)
345  {
346  subscribedToScan3d_ = true;
347  scan3dSub_.subscribe(nh, "scan_cloud", queueSize);
348  if(subscribeOdomInfo)
349  {
350  subscribedToOdomInfo_ = false;
351  ROS_WARN("subscribe_odom_info ignored...");
352  }
353  SYNC_DECL6(rgbd5Scan3d, approxSync, queueSize, (*rgbdSubs_[0]), (*rgbdSubs_[1]), (*rgbdSubs_[2]), (*rgbdSubs_[3]), (*rgbdSubs_[4]), scan3dSub_);
354  }
355  else if(subscribeOdomInfo)
356  {
357  subscribedToOdomInfo_ = true;
358  odomInfoSub_.subscribe(nh, "odom_info", queueSize);
359  SYNC_DECL6(rgbd5Info, approxSync, queueSize, (*rgbdSubs_[0]), (*rgbdSubs_[1]), (*rgbdSubs_[2]), (*rgbdSubs_[3]), (*rgbdSubs_[4]), odomInfoSub_);
360  }
361  else
362  {
363  SYNC_DECL5(rgbd5, approxSync, queueSize, (*rgbdSubs_[0]), (*rgbdSubs_[1]), (*rgbdSubs_[2]), (*rgbdSubs_[3]), (*rgbdSubs_[4]));
364  }
365  }
366 }
367 
368 } /* namespace rtabmap_ros */
std::string uFormat(const char *fmt,...)
#define SYNC_DECL7(PREFIX, APPROX, QUEUE_SIZE, SUB0, SUB1, SUB2, SUB3, SUB4, SUB5, SUB6)
#define SYNC_DECL5(PREFIX, APPROX, QUEUE_SIZE, SUB0, SUB1, SUB2, SUB3, SUB4)
virtual void commonDepthCallback(const nav_msgs::OdometryConstPtr &odomMsg, const rtabmap_ros::UserDataConstPtr &userDataMsg, const std::vector< cv_bridge::CvImageConstPtr > &imageMsgs, const std::vector< cv_bridge::CvImageConstPtr > &depthMsgs, const std::vector< sensor_msgs::CameraInfo > &cameraInfoMsgs, const sensor_msgs::LaserScan &scanMsg, const sensor_msgs::PointCloud2 &scan3dMsg, const rtabmap_ros::OdomInfoConstPtr &odomInfoMsg, const std::vector< rtabmap_ros::GlobalDescriptor > &globalDescriptorMsgs=std::vector< rtabmap_ros::GlobalDescriptor >(), const std::vector< std::vector< rtabmap_ros::KeyPoint > > &localKeyPoints=std::vector< std::vector< rtabmap_ros::KeyPoint > >(), const std::vector< std::vector< rtabmap_ros::Point3f > > &localPoints3d=std::vector< std::vector< rtabmap_ros::Point3f > >(), const std::vector< cv::Mat > &localDescriptors=std::vector< cv::Mat >())=0
#define ROS_WARN(...)
#define SYNC_DECL6(PREFIX, APPROX, QUEUE_SIZE, SUB0, SUB1, SUB2, SUB3, SUB4, SUB5)
message_filters::Subscriber< rtabmap_ros::OdomInfo > odomInfoSub_
#define IMAGE_CONVERSION()
#define ROS_INFO(...)
message_filters::Subscriber< sensor_msgs::LaserScan > scanSub_
message_filters::Subscriber< rtabmap_ros::ScanDescriptor > scanDescSub_
message_filters::Subscriber< nav_msgs::Odometry > odomSub_
message_filters::Subscriber< sensor_msgs::PointCloud2 > scan3dSub_
void subscribe(ros::NodeHandle &nh, const std::string &topic, uint32_t queue_size, const ros::TransportHints &transport_hints=ros::TransportHints(), ros::CallbackQueueInterface *callback_queue=0)
std::vector< message_filters::Subscriber< rtabmap_ros::RGBDImage > * > rgbdSubs_


rtabmap_ros
Author(s): Mathieu Labbe
autogenerated on Mon Dec 14 2020 03:42:18