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<sensor_msgs::CameraInfo> depthCameraInfoMsgs; \
54  depthCameraInfoMsgs.push_back(image1Msg->depth_camera_info); \
55  depthCameraInfoMsgs.push_back(image2Msg->depth_camera_info); \
56  depthCameraInfoMsgs.push_back(image3Msg->depth_camera_info); \
57  depthCameraInfoMsgs.push_back(image4Msg->depth_camera_info); \
58  depthCameraInfoMsgs.push_back(image5Msg->depth_camera_info); \
59  std::vector<rtabmap_ros::GlobalDescriptor> globalDescriptorMsgs; \
60  std::vector<std::vector<rtabmap_ros::KeyPoint> > localKeyPoints; \
61  std::vector<std::vector<rtabmap_ros::Point3f> > localPoints3d; \
62  std::vector<cv::Mat> localDescriptors; \
63  if(!image1Msg->global_descriptor.data.empty()) \
64  globalDescriptorMsgs.push_back(image1Msg->global_descriptor); \
65  if(!image2Msg->global_descriptor.data.empty()) \
66  globalDescriptorMsgs.push_back(image2Msg->global_descriptor); \
67  if(!image3Msg->global_descriptor.data.empty()) \
68  globalDescriptorMsgs.push_back(image3Msg->global_descriptor); \
69  if(!image4Msg->global_descriptor.data.empty()) \
70  globalDescriptorMsgs.push_back(image4Msg->global_descriptor); \
71  if(!image5Msg->global_descriptor.data.empty()) \
72  globalDescriptorMsgs.push_back(image5Msg->global_descriptor); \
73  localKeyPoints.push_back(image1Msg->key_points); \
74  localKeyPoints.push_back(image2Msg->key_points); \
75  localKeyPoints.push_back(image3Msg->key_points); \
76  localKeyPoints.push_back(image4Msg->key_points); \
77  localKeyPoints.push_back(image5Msg->key_points); \
78  localPoints3d.push_back(image1Msg->points); \
79  localPoints3d.push_back(image2Msg->points); \
80  localPoints3d.push_back(image3Msg->points); \
81  localPoints3d.push_back(image4Msg->points); \
82  localPoints3d.push_back(image5Msg->points); \
83  localDescriptors.push_back(rtabmap::uncompressData(image1Msg->descriptors)); \
84  localDescriptors.push_back(rtabmap::uncompressData(image2Msg->descriptors)); \
85  localDescriptors.push_back(rtabmap::uncompressData(image3Msg->descriptors)); \
86  localDescriptors.push_back(rtabmap::uncompressData(image4Msg->descriptors)); \
87  localDescriptors.push_back(rtabmap::uncompressData(image5Msg->descriptors));
88 
89 // 5 RGBD
90 void CommonDataSubscriber::rgbd5Callback(
91  const rtabmap_ros::RGBDImageConstPtr& image1Msg,
92  const rtabmap_ros::RGBDImageConstPtr& image2Msg,
93  const rtabmap_ros::RGBDImageConstPtr& image3Msg,
94  const rtabmap_ros::RGBDImageConstPtr& image4Msg,
95  const rtabmap_ros::RGBDImageConstPtr& image5Msg)
96 {
98 
99  nav_msgs::OdometryConstPtr odomMsg; // Null
100  rtabmap_ros::UserDataConstPtr userDataMsg; // Null
101  sensor_msgs::LaserScan scanMsg; // Null
102  sensor_msgs::PointCloud2 scan3dMsg; // Null
103  rtabmap_ros::OdomInfoConstPtr odomInfoMsg; // null
104  commonMultiCameraCallback(odomMsg, userDataMsg, imageMsgs, depthMsgs, cameraInfoMsgs, depthCameraInfoMsgs, scanMsg, scan3dMsg, odomInfoMsg, globalDescriptorMsgs, localKeyPoints, localPoints3d, localDescriptors);
105 }
106 void CommonDataSubscriber::rgbd5Scan2dCallback(
107  const rtabmap_ros::RGBDImageConstPtr& image1Msg,
108  const rtabmap_ros::RGBDImageConstPtr& image2Msg,
109  const rtabmap_ros::RGBDImageConstPtr& image3Msg,
110  const rtabmap_ros::RGBDImageConstPtr& image4Msg,
111  const rtabmap_ros::RGBDImageConstPtr& image5Msg,
112  const sensor_msgs::LaserScanConstPtr& scanMsg)
113 {
115 
116  nav_msgs::OdometryConstPtr odomMsg; // Null
117  rtabmap_ros::UserDataConstPtr userDataMsg; // Null
118  sensor_msgs::PointCloud2 scan3dMsg; // Null
119  rtabmap_ros::OdomInfoConstPtr odomInfoMsg; // null
120  commonMultiCameraCallback(odomMsg, userDataMsg, imageMsgs, depthMsgs, cameraInfoMsgs, depthCameraInfoMsgs, *scanMsg, scan3dMsg, odomInfoMsg, globalDescriptorMsgs, localKeyPoints, localPoints3d, localDescriptors);
121 }
122 void CommonDataSubscriber::rgbd5Scan3dCallback(
123  const rtabmap_ros::RGBDImageConstPtr& image1Msg,
124  const rtabmap_ros::RGBDImageConstPtr& image2Msg,
125  const rtabmap_ros::RGBDImageConstPtr& image3Msg,
126  const rtabmap_ros::RGBDImageConstPtr& image4Msg,
127  const rtabmap_ros::RGBDImageConstPtr& image5Msg,
128  const sensor_msgs::PointCloud2ConstPtr& scan3dMsg)
129 {
131 
132  nav_msgs::OdometryConstPtr odomMsg; // Null
133  rtabmap_ros::UserDataConstPtr userDataMsg; // Null
134  sensor_msgs::LaserScan scanMsg; // Null
135  rtabmap_ros::OdomInfoConstPtr odomInfoMsg; // null
136  commonMultiCameraCallback(odomMsg, userDataMsg, imageMsgs, depthMsgs, cameraInfoMsgs, depthCameraInfoMsgs, scanMsg, *scan3dMsg, odomInfoMsg, globalDescriptorMsgs, localKeyPoints, localPoints3d, localDescriptors);
137 }
138 void CommonDataSubscriber::rgbd5ScanDescCallback(
139  const rtabmap_ros::RGBDImageConstPtr& image1Msg,
140  const rtabmap_ros::RGBDImageConstPtr& image2Msg,
141  const rtabmap_ros::RGBDImageConstPtr& image3Msg,
142  const rtabmap_ros::RGBDImageConstPtr& image4Msg,
143  const rtabmap_ros::RGBDImageConstPtr& image5Msg,
144  const rtabmap_ros::ScanDescriptorConstPtr& scanDescMsg)
145 {
147 
148  nav_msgs::OdometryConstPtr odomMsg; // Null
149  rtabmap_ros::UserDataConstPtr userDataMsg; // Null
150  rtabmap_ros::OdomInfoConstPtr odomInfoMsg; // null
151  if(!scanDescMsg->global_descriptor.data.empty())
152  {
153  globalDescriptorMsgs.push_back(scanDescMsg->global_descriptor);
154  }
155  commonMultiCameraCallback(odomMsg, userDataMsg, imageMsgs, depthMsgs, cameraInfoMsgs, depthCameraInfoMsgs, scanDescMsg->scan, scanDescMsg->scan_cloud, odomInfoMsg, globalDescriptorMsgs, localKeyPoints, localPoints3d, localDescriptors);
156 }
157 void CommonDataSubscriber::rgbd5InfoCallback(
158  const rtabmap_ros::RGBDImageConstPtr& image1Msg,
159  const rtabmap_ros::RGBDImageConstPtr& image2Msg,
160  const rtabmap_ros::RGBDImageConstPtr& image3Msg,
161  const rtabmap_ros::RGBDImageConstPtr& image4Msg,
162  const rtabmap_ros::RGBDImageConstPtr& image5Msg,
163  const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg)
164 {
166 
167  nav_msgs::OdometryConstPtr odomMsg; // Null
168  rtabmap_ros::UserDataConstPtr userDataMsg; // Null
169  sensor_msgs::LaserScan scanMsg; // Null
170  sensor_msgs::PointCloud2 scan3dMsg; // Null
171  commonMultiCameraCallback(odomMsg, userDataMsg, imageMsgs, depthMsgs, cameraInfoMsgs, depthCameraInfoMsgs, scanMsg, scan3dMsg, odomInfoMsg, globalDescriptorMsgs, localKeyPoints, localPoints3d, localDescriptors);
172 }
173 
174 // 5 RGBD + Odom
175 void CommonDataSubscriber::rgbd5OdomCallback(
176  const nav_msgs::OdometryConstPtr & odomMsg,
177  const rtabmap_ros::RGBDImageConstPtr& image1Msg,
178  const rtabmap_ros::RGBDImageConstPtr& image2Msg,
179  const rtabmap_ros::RGBDImageConstPtr& image3Msg,
180  const rtabmap_ros::RGBDImageConstPtr& image4Msg,
181  const rtabmap_ros::RGBDImageConstPtr& image5Msg)
182 {
184 
185  rtabmap_ros::UserDataConstPtr userDataMsg; // Null
186  sensor_msgs::LaserScan scanMsg; // Null
187  sensor_msgs::PointCloud2 scan3dMsg; // Null
188  rtabmap_ros::OdomInfoConstPtr odomInfoMsg; // null
189  commonMultiCameraCallback(odomMsg, userDataMsg, imageMsgs, depthMsgs, cameraInfoMsgs, depthCameraInfoMsgs, scanMsg, scan3dMsg, odomInfoMsg, globalDescriptorMsgs, localKeyPoints, localPoints3d, localDescriptors);
190 }
191 void CommonDataSubscriber::rgbd5OdomScan2dCallback(
192  const nav_msgs::OdometryConstPtr & odomMsg,
193  const rtabmap_ros::RGBDImageConstPtr& image1Msg,
194  const rtabmap_ros::RGBDImageConstPtr& image2Msg,
195  const rtabmap_ros::RGBDImageConstPtr& image3Msg,
196  const rtabmap_ros::RGBDImageConstPtr& image4Msg,
197  const rtabmap_ros::RGBDImageConstPtr& image5Msg,
198  const sensor_msgs::LaserScanConstPtr& scanMsg)
199 {
201 
202  rtabmap_ros::UserDataConstPtr userDataMsg; // Null
203  sensor_msgs::PointCloud2 scan3dMsg; // Null
204  rtabmap_ros::OdomInfoConstPtr odomInfoMsg; // null
205  commonMultiCameraCallback(odomMsg, userDataMsg, imageMsgs, depthMsgs, cameraInfoMsgs, depthCameraInfoMsgs, *scanMsg, scan3dMsg, odomInfoMsg, globalDescriptorMsgs, localKeyPoints, localPoints3d, localDescriptors);
206 }
207 void CommonDataSubscriber::rgbd5OdomScan3dCallback(
208  const nav_msgs::OdometryConstPtr & odomMsg,
209  const rtabmap_ros::RGBDImageConstPtr& image1Msg,
210  const rtabmap_ros::RGBDImageConstPtr& image2Msg,
211  const rtabmap_ros::RGBDImageConstPtr& image3Msg,
212  const rtabmap_ros::RGBDImageConstPtr& image4Msg,
213  const rtabmap_ros::RGBDImageConstPtr& image5Msg,
214  const sensor_msgs::PointCloud2ConstPtr& scan3dMsg)
215 {
217 
218  rtabmap_ros::UserDataConstPtr userDataMsg; // Null
219  sensor_msgs::LaserScan scanMsg; // Null
220  rtabmap_ros::OdomInfoConstPtr odomInfoMsg; // null
221  commonMultiCameraCallback(odomMsg, userDataMsg, imageMsgs, depthMsgs, cameraInfoMsgs, depthCameraInfoMsgs, scanMsg, *scan3dMsg, odomInfoMsg, globalDescriptorMsgs, localKeyPoints, localPoints3d, localDescriptors);
222 }
223 void CommonDataSubscriber::rgbd5OdomScanDescCallback(
224  const nav_msgs::OdometryConstPtr & odomMsg,
225  const rtabmap_ros::RGBDImageConstPtr& image1Msg,
226  const rtabmap_ros::RGBDImageConstPtr& image2Msg,
227  const rtabmap_ros::RGBDImageConstPtr& image3Msg,
228  const rtabmap_ros::RGBDImageConstPtr& image4Msg,
229  const rtabmap_ros::RGBDImageConstPtr& image5Msg,
230  const rtabmap_ros::ScanDescriptorConstPtr& scanDescMsg)
231 {
233 
234  rtabmap_ros::UserDataConstPtr userDataMsg; // Null
235  rtabmap_ros::OdomInfoConstPtr odomInfoMsg; // null
236  if(!scanDescMsg->global_descriptor.data.empty())
237  {
238  globalDescriptorMsgs.push_back(scanDescMsg->global_descriptor);
239  }
240  commonMultiCameraCallback(odomMsg, userDataMsg, imageMsgs, depthMsgs, cameraInfoMsgs, depthCameraInfoMsgs, scanDescMsg->scan, scanDescMsg->scan_cloud, odomInfoMsg, globalDescriptorMsgs, localKeyPoints, localPoints3d, localDescriptors);
241 }
242 void CommonDataSubscriber::rgbd5OdomInfoCallback(
243  const nav_msgs::OdometryConstPtr & odomMsg,
244  const rtabmap_ros::RGBDImageConstPtr& image1Msg,
245  const rtabmap_ros::RGBDImageConstPtr& image2Msg,
246  const rtabmap_ros::RGBDImageConstPtr& image3Msg,
247  const rtabmap_ros::RGBDImageConstPtr& image4Msg,
248  const rtabmap_ros::RGBDImageConstPtr& image5Msg,
249  const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg)
250 {
252 
253  rtabmap_ros::UserDataConstPtr userDataMsg; // Null
254  sensor_msgs::LaserScan scanMsg; // Null
255  sensor_msgs::PointCloud2 scan3dMsg; // Null
256  commonMultiCameraCallback(odomMsg, userDataMsg, imageMsgs, depthMsgs, cameraInfoMsgs, depthCameraInfoMsgs, scanMsg, scan3dMsg, odomInfoMsg, globalDescriptorMsgs, localKeyPoints, localPoints3d, localDescriptors);
257 }
258 
259 void CommonDataSubscriber::setupRGBD5Callbacks(
260  ros::NodeHandle & nh,
261  ros::NodeHandle & pnh,
262  bool subscribeOdom,
263  bool subscribeUserData,
264  bool subscribeScan2d,
265  bool subscribeScan3d,
266  bool subscribeScanDesc,
267  bool subscribeOdomInfo,
268  int queueSize,
269  bool approxSync)
270 {
271  ROS_INFO("Setup rgbd5 callback");
272 
273  rgbdSubs_.resize(5);
274  for(int i=0; i<5; ++i)
275  {
277  rgbdSubs_[i]->subscribe(nh, uFormat("rgbd_image%d", i), queueSize);
278  }
279  if(subscribeOdom)
280  {
281  odomSub_.subscribe(nh, "odom", queueSize);
282  if(subscribeScanDesc)
283  {
285  scanDescSub_.subscribe(nh, "scan_descriptor", queueSize);
286  if(subscribeOdomInfo)
287  {
288  subscribedToOdomInfo_ = false;
289  ROS_WARN("subscribe_odom_info ignored...");
290  }
291  SYNC_DECL7(CommonDataSubscriber, rgbd5OdomScanDesc, approxSync, queueSize, odomSub_, (*rgbdSubs_[0]), (*rgbdSubs_[1]), (*rgbdSubs_[2]), (*rgbdSubs_[3]), (*rgbdSubs_[4]), scanDescSub_);
292  }
293  else if(subscribeScan2d)
294  {
295  subscribedToScan2d_ = true;
296  scanSub_.subscribe(nh, "scan", queueSize);
297  if(subscribeOdomInfo)
298  {
299  subscribedToOdomInfo_ = false;
300  ROS_WARN("subscribe_odom_info ignored...");
301  }
302  SYNC_DECL7(CommonDataSubscriber, rgbd5OdomScan2d, approxSync, queueSize, odomSub_, (*rgbdSubs_[0]), (*rgbdSubs_[1]), (*rgbdSubs_[2]), (*rgbdSubs_[3]), (*rgbdSubs_[4]), scanSub_);
303  }
304  else if(subscribeScan3d)
305  {
306  subscribedToScan3d_ = true;
307  scan3dSub_.subscribe(nh, "scan_cloud", queueSize);
308  if(subscribeOdomInfo)
309  {
310  subscribedToOdomInfo_ = false;
311  ROS_WARN("subscribe_odom_info ignored...");
312  }
313  SYNC_DECL7(CommonDataSubscriber, rgbd5OdomScan3d, approxSync, queueSize, odomSub_, (*rgbdSubs_[0]), (*rgbdSubs_[1]), (*rgbdSubs_[2]), (*rgbdSubs_[3]), (*rgbdSubs_[4]), scan3dSub_);
314  }
315  else if(subscribeOdomInfo)
316  {
317  subscribedToOdomInfo_ = true;
318  odomInfoSub_.subscribe(nh, "odom_info", queueSize);
319  SYNC_DECL7(CommonDataSubscriber, rgbd5OdomInfo, approxSync, queueSize, odomSub_, (*rgbdSubs_[0]), (*rgbdSubs_[1]), (*rgbdSubs_[2]), (*rgbdSubs_[3]), (*rgbdSubs_[4]), odomInfoSub_);
320  }
321  else
322  {
323  SYNC_DECL6(CommonDataSubscriber, rgbd5Odom, approxSync, queueSize, odomSub_, (*rgbdSubs_[0]), (*rgbdSubs_[1]), (*rgbdSubs_[2]), (*rgbdSubs_[3]), (*rgbdSubs_[4]));
324  }
325  }
326  else
327  {
328  if(subscribeScanDesc)
329  {
331  scanDescSub_.subscribe(nh, "scan_descriptor", queueSize);
332  if(subscribeOdomInfo)
333  {
334  subscribedToOdomInfo_ = false;
335  ROS_WARN("subscribe_odom_info ignored...");
336  }
337  SYNC_DECL6(CommonDataSubscriber, rgbd5ScanDesc, approxSync, queueSize, (*rgbdSubs_[0]), (*rgbdSubs_[1]), (*rgbdSubs_[2]), (*rgbdSubs_[3]), (*rgbdSubs_[4]), scanDescSub_);
338  }
339  else if(subscribeScan2d)
340  {
341  subscribedToScan2d_ = true;
342  scanSub_.subscribe(nh, "scan", queueSize);
343  if(subscribeOdomInfo)
344  {
345  subscribedToOdomInfo_ = false;
346  ROS_WARN("subscribe_odom_info ignored...");
347  }
348  SYNC_DECL6(CommonDataSubscriber, rgbd5Scan2d, approxSync, queueSize, (*rgbdSubs_[0]), (*rgbdSubs_[1]), (*rgbdSubs_[2]), (*rgbdSubs_[3]), (*rgbdSubs_[4]), scanSub_);
349  }
350  else if(subscribeScan3d)
351  {
352  subscribedToScan3d_ = true;
353  scan3dSub_.subscribe(nh, "scan_cloud", queueSize);
354  if(subscribeOdomInfo)
355  {
356  subscribedToOdomInfo_ = false;
357  ROS_WARN("subscribe_odom_info ignored...");
358  }
359  SYNC_DECL6(CommonDataSubscriber, rgbd5Scan3d, approxSync, queueSize, (*rgbdSubs_[0]), (*rgbdSubs_[1]), (*rgbdSubs_[2]), (*rgbdSubs_[3]), (*rgbdSubs_[4]), scan3dSub_);
360  }
361  else if(subscribeOdomInfo)
362  {
363  subscribedToOdomInfo_ = true;
364  odomInfoSub_.subscribe(nh, "odom_info", queueSize);
365  SYNC_DECL6(CommonDataSubscriber, rgbd5Info, approxSync, queueSize, (*rgbdSubs_[0]), (*rgbdSubs_[1]), (*rgbdSubs_[2]), (*rgbdSubs_[3]), (*rgbdSubs_[4]), odomInfoSub_);
366  }
367  else
368  {
369  SYNC_DECL5(CommonDataSubscriber, rgbd5, approxSync, queueSize, (*rgbdSubs_[0]), (*rgbdSubs_[1]), (*rgbdSubs_[2]), (*rgbdSubs_[3]), (*rgbdSubs_[4]));
370  }
371  }
372 }
373 
374 } /* namespace rtabmap_ros */
std::string uFormat(const char *fmt,...)
#define ROS_WARN(...)
message_filters::Subscriber< rtabmap_ros::OdomInfo > odomInfoSub_
#define IMAGE_CONVERSION()
#define SYNC_DECL5(CLASS, PREFIX, APPROX, QUEUE_SIZE, SUB0, SUB1, SUB2, SUB3, SUB4)
#define ROS_INFO(...)
message_filters::Subscriber< sensor_msgs::LaserScan > scanSub_
message_filters::Subscriber< rtabmap_ros::ScanDescriptor > scanDescSub_
virtual void commonMultiCameraCallback(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 std::vector< sensor_msgs::CameraInfo > &depthCameraInfoMsgs, 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
message_filters::Subscriber< nav_msgs::Odometry > odomSub_
#define SYNC_DECL6(CLASS, PREFIX, APPROX, QUEUE_SIZE, SUB0, SUB1, SUB2, SUB3, SUB4, SUB5)
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)
#define SYNC_DECL7(CLASS, PREFIX, APPROX, QUEUE_SIZE, SUB0, SUB1, SUB2, SUB3, SUB4, SUB5, SUB6)
std::vector< message_filters::Subscriber< rtabmap_ros::RGBDImage > * > rgbdSubs_


rtabmap_ros
Author(s): Mathieu Labbe
autogenerated on Tue Jan 24 2023 04:04:40