CommonDataSubscriber.h
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 
28 #ifndef INCLUDE_RTABMAP_ROS_COMMONDATASUBSCRIBER_H_
29 #define INCLUDE_RTABMAP_ROS_COMMONDATASUBSCRIBER_H_
30 
35 
38 
39 #include <cv_bridge/cv_bridge.h>
40 
41 #include <sensor_msgs/PointCloud2.h>
42 #include <sensor_msgs/Image.h>
43 #include <sensor_msgs/CameraInfo.h>
44 #include <sensor_msgs/LaserScan.h>
45 
46 #include <nav_msgs/Odometry.h>
47 
48 #include <rtabmap_msgs/RGBDImage.h>
49 #include <rtabmap_msgs/RGBDImages.h>
50 #include <rtabmap_msgs/UserData.h>
51 #include <rtabmap_msgs/OdomInfo.h>
52 #include <rtabmap_msgs/ScanDescriptor.h>
53 #include <rtabmap_msgs/SensorData.h>
56 
57 #include <boost/thread.hpp>
58 
59 namespace rtabmap_sync {
60 
62 public:
63  CommonDataSubscriber(bool gui);
64  virtual ~CommonDataSubscriber();
65 
66  bool isSubscribedToDepth() const {return subscribedToDepth_;}
68  bool isSubscribedToRGB() const {return subscribedToRGB_;}
69  bool isSubscribedToOdom() const {return subscribedToOdom_;}
70  bool isSubscribedToRGBD() const {return subscribedToRGBD_;}
76  int rgbdCameras() const {return isSubscribedToRGBD()?(int)rgbdSubs_.size():0;}
77  int getTopicQueueSize() const {return topicQueueSize_;}
78  int getSyncQueueSize() const {return syncQueueSize_;}
79  bool isApproxSync() const {return approxSync_;}
80  const std::string & name() const {return name_;}
81 
82 protected:
83  void setupCallbacks(
84  ros::NodeHandle & nh,
85  ros::NodeHandle & pnh,
86  const std::string & name,
87  std::vector<diagnostic_updater::DiagnosticTask*> otherTasks = std::vector<diagnostic_updater::DiagnosticTask*>());
88  virtual void commonMultiCameraCallback(
89  const nav_msgs::OdometryConstPtr & odomMsg,
90  const rtabmap_msgs::UserDataConstPtr & userDataMsg,
91  const std::vector<cv_bridge::CvImageConstPtr> & imageMsgs,
92  const std::vector<cv_bridge::CvImageConstPtr> & depthMsgs,
93  const std::vector<sensor_msgs::CameraInfo> & cameraInfoMsgs,
94  const std::vector<sensor_msgs::CameraInfo> & depthCameraInfoMsgs,
95  const sensor_msgs::LaserScan& scanMsg,
96  const sensor_msgs::PointCloud2& scan3dMsg,
97  const rtabmap_msgs::OdomInfoConstPtr& odomInfoMsg,
98  const std::vector<rtabmap_msgs::GlobalDescriptor> & globalDescriptorMsgs = std::vector<rtabmap_msgs::GlobalDescriptor>(),
99  const std::vector<std::vector<rtabmap_msgs::KeyPoint> > & localKeyPoints = std::vector<std::vector<rtabmap_msgs::KeyPoint> >(),
100  const std::vector<std::vector<rtabmap_msgs::Point3f> > & localPoints3d = std::vector<std::vector<rtabmap_msgs::Point3f> >(),
101  const std::vector<cv::Mat> & localDescriptors = std::vector<cv::Mat>()) = 0;
102  virtual void commonLaserScanCallback(
103  const nav_msgs::OdometryConstPtr & odomMsg,
104  const rtabmap_msgs::UserDataConstPtr & userDataMsg,
105  const sensor_msgs::LaserScan& scanMsg,
106  const sensor_msgs::PointCloud2& scan3dMsg,
107  const rtabmap_msgs::OdomInfoConstPtr& odomInfoMsg,
108  const rtabmap_msgs::GlobalDescriptor & globalDescriptor = rtabmap_msgs::GlobalDescriptor()) = 0;
109  virtual void commonOdomCallback(
110  const nav_msgs::OdometryConstPtr & odomMsg,
111  const rtabmap_msgs::UserDataConstPtr & userDataMsg,
112  const rtabmap_msgs::OdomInfoConstPtr& odomInfoMsg) = 0;
113  virtual void commonSensorDataCallback(
114  const rtabmap_msgs::SensorDataConstPtr & sensorDataMsg,
115  const nav_msgs::OdometryConstPtr & odomMsg,
116  const rtabmap_msgs::OdomInfoConstPtr& odomInfoMsg) = 0;
117 
119  const nav_msgs::OdometryConstPtr & odomMsg,
120  const rtabmap_msgs::UserDataConstPtr & userDataMsg,
121  const cv_bridge::CvImageConstPtr & imageMsg,
122  const cv_bridge::CvImageConstPtr & depthMsg,
123  const sensor_msgs::CameraInfo & rgbCameraInfoMsg,
124  const sensor_msgs::CameraInfo & depthCameraInfoMsg,
125  const sensor_msgs::LaserScan& scanMsg,
126  const sensor_msgs::PointCloud2& scan3dMsg,
127  const rtabmap_msgs::OdomInfoConstPtr& odomInfoMsg,
128  const std::vector<rtabmap_msgs::GlobalDescriptor> & globalDescriptorMsgs = std::vector<rtabmap_msgs::GlobalDescriptor>(),
129  const std::vector<rtabmap_msgs::KeyPoint> & localKeyPoints = std::vector<rtabmap_msgs::KeyPoint>(),
130  const std::vector<rtabmap_msgs::Point3f> & localPoints3d = std::vector<rtabmap_msgs::Point3f>(),
131  const cv::Mat & localDescriptors = cv::Mat());
132 
133  void tick(const ros::Time & stamp, double targetFrequency = 0);
134 
135 private:
136  void setupDepthCallbacks(
137  ros::NodeHandle & nh,
138  ros::NodeHandle & pnh,
139  bool subscribeOdom,
140  bool subscribeUserData,
141  bool subscribeScan2d,
142  bool subscribeScan3d,
143  bool subscribeScanDesc,
144  bool subscribeOdomInfo);
146  ros::NodeHandle & nh,
147  ros::NodeHandle & pnh,
148  bool subscribeOdom,
149  bool subscribeOdomInfo);
150  void setupRGBCallbacks(
151  ros::NodeHandle & nh,
152  ros::NodeHandle & pnh,
153  bool subscribeOdom,
154  bool subscribeUserData,
155  bool subscribeScan2d,
156  bool subscribeScan3d,
157  bool subscribeScanDesc,
158  bool subscribeOdomInfo);
159  void setupRGBDCallbacks(
160  ros::NodeHandle & nh,
161  ros::NodeHandle & pnh,
162  bool subscribeOdom,
163  bool subscribeUserData,
164  bool subscribeScan2d,
165  bool subscribeScan3d,
166  bool subscribeScanDesc,
167  bool subscribeOdomInfo);
168  void setupRGBDXCallbacks(
169  ros::NodeHandle & nh,
170  ros::NodeHandle & pnh,
171  bool subscribeOdom,
172  bool subscribeUserData,
173  bool subscribeScan2d,
174  bool subscribeScan3d,
175  bool subscribeScanDesc,
176  bool subscribeOdomInfo);
177 #ifdef RTABMAP_SYNC_MULTI_RGBD
178  void setupRGBD2Callbacks(
179  ros::NodeHandle & nh,
180  ros::NodeHandle & pnh,
181  bool subscribeOdom,
182  bool subscribeUserData,
183  bool subscribeScan2d,
184  bool subscribeScan3d,
185  bool subscribeScanDesc,
186  bool subscribeOdomInfo);
187  void setupRGBD3Callbacks(
188  ros::NodeHandle & nh,
189  ros::NodeHandle & pnh,
190  bool subscribeOdom,
191  bool subscribeUserData,
192  bool subscribeScan2d,
193  bool subscribeScan3d,
194  bool subscribeScanDesc,
195  bool subscribeOdomInfo);
196  void setupRGBD4Callbacks(
197  ros::NodeHandle & nh,
198  ros::NodeHandle & pnh,
199  bool subscribeOdom,
200  bool subscribeUserData,
201  bool subscribeScan2d,
202  bool subscribeScan3d,
203  bool subscribeScanDesc,
204  bool subscribeOdomInfo);
205  void setupRGBD5Callbacks(
206  ros::NodeHandle & nh,
207  ros::NodeHandle & pnh,
208  bool subscribeOdom,
209  bool subscribeUserData,
210  bool subscribeScan2d,
211  bool subscribeScan3d,
212  bool subscribeScanDesc,
213  bool subscribeOdomInfo);
214  void setupRGBD6Callbacks(
215  ros::NodeHandle & nh,
216  ros::NodeHandle & pnh,
217  bool subscribeOdom,
218  bool subscribeUserData,
219  bool subscribeScan2d,
220  bool subscribeScan3d,
221  bool subscribeScanDesc,
222  bool subscribeOdomInfo);
223 #endif
225  ros::NodeHandle & nh,
226  ros::NodeHandle & pnh,
227  bool subscribeOdom,
228  bool subscribeOdomInfo);
229  void setupScanCallbacks(
230  ros::NodeHandle & nh,
231  ros::NodeHandle & pnh,
232  bool subscribeScan2d,
233  bool subscribeScanDesc,
234  bool subscribeOdom,
235  bool subscribeUserData,
236  bool subscribeOdomInfo);
237  void setupOdomCallbacks(
238  ros::NodeHandle & nh,
239  ros::NodeHandle & pnh,
240  bool subscribeUserData,
241  bool subscribeOdomInfo);
242 
243 protected:
244  std::string subscribedTopicsMsg_;
247 
248 private:
260  std::string name_;
261 
262  //for depth and rgb-only callbacks
266 
267  //for rgbd callback
269  std::vector<message_filters::Subscriber<rtabmap_msgs::RGBDImage>*> rgbdSubs_;
272 
273  //for sensor data callback
276 
277  //stereo callback
282 
289 
294 
295  std::unique_ptr<SyncDiagnostic> syncDiagnostic_;
296 
297  // RGB + Depth
298  DATA_SYNCS3(depth, sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo);
299  DATA_SYNCS4(depthScan2d, sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo, sensor_msgs::LaserScan);
300  DATA_SYNCS4(depthScan3d, sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo, sensor_msgs::PointCloud2);
301  DATA_SYNCS4(depthScanDesc, sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo, rtabmap_msgs::ScanDescriptor);
302  DATA_SYNCS4(depthInfo, sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo, rtabmap_msgs::OdomInfo);
303  DATA_SYNCS5(depthScan2dInfo, sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo, sensor_msgs::LaserScan, rtabmap_msgs::OdomInfo);
304  DATA_SYNCS5(depthScan3dInfo, sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo, sensor_msgs::PointCloud2, rtabmap_msgs::OdomInfo);
305  DATA_SYNCS5(depthScanDescInfo, sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo, rtabmap_msgs::ScanDescriptor, rtabmap_msgs::OdomInfo);
306 
307  // RGB + Depth + Odom
308  DATA_SYNCS4(depthOdom, nav_msgs::Odometry, sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo);
309  DATA_SYNCS5(depthOdomScan2d, nav_msgs::Odometry, sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo, sensor_msgs::LaserScan);
310  DATA_SYNCS5(depthOdomScan3d, nav_msgs::Odometry, sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo, sensor_msgs::PointCloud2);
311  DATA_SYNCS5(depthOdomScanDesc, nav_msgs::Odometry, sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo, rtabmap_msgs::ScanDescriptor);
312  DATA_SYNCS5(depthOdomInfo, nav_msgs::Odometry, sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo, rtabmap_msgs::OdomInfo);
313  DATA_SYNCS6(depthOdomScan2dInfo, nav_msgs::Odometry, sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo, sensor_msgs::LaserScan, rtabmap_msgs::OdomInfo);
314  DATA_SYNCS6(depthOdomScan3dInfo, nav_msgs::Odometry, sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo, sensor_msgs::PointCloud2, rtabmap_msgs::OdomInfo);
315  DATA_SYNCS6(depthOdomScanDescInfo, nav_msgs::Odometry, sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo, rtabmap_msgs::ScanDescriptor, rtabmap_msgs::OdomInfo);
316 
317 #ifdef RTABMAP_SYNC_USER_DATA
318  // RGB + Depth + User Data
319  DATA_SYNCS4(depthData, rtabmap_msgs::UserData, sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo);
320  DATA_SYNCS5(depthDataScan2d, rtabmap_msgs::UserData, sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo, sensor_msgs::LaserScan);
321  DATA_SYNCS5(depthDataScan3d, rtabmap_msgs::UserData, sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo, sensor_msgs::PointCloud2);
322  DATA_SYNCS5(depthDataScanDesc, rtabmap_msgs::UserData, sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo, rtabmap_msgs::ScanDescriptor);
323  DATA_SYNCS5(depthDataInfo, rtabmap_msgs::UserData, sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo, rtabmap_msgs::OdomInfo);
324  DATA_SYNCS6(depthDataScan2dInfo, rtabmap_msgs::UserData, sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo, sensor_msgs::LaserScan, rtabmap_msgs::OdomInfo);
325  DATA_SYNCS6(depthDataScan3dInfo, rtabmap_msgs::UserData, sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo, sensor_msgs::PointCloud2, rtabmap_msgs::OdomInfo);
326  DATA_SYNCS6(depthDataScanDescInfo, rtabmap_msgs::UserData, sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo, rtabmap_msgs::ScanDescriptor, rtabmap_msgs::OdomInfo);
327 
328  // RGB + Depth + Odom + User Data
329  DATA_SYNCS5(depthOdomData, nav_msgs::Odometry, rtabmap_msgs::UserData, sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo);
330  DATA_SYNCS6(depthOdomDataScan2d, nav_msgs::Odometry, rtabmap_msgs::UserData, sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo, sensor_msgs::LaserScan);
331  DATA_SYNCS6(depthOdomDataScan3d, nav_msgs::Odometry, rtabmap_msgs::UserData, sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo, sensor_msgs::PointCloud2);
332  DATA_SYNCS6(depthOdomDataScanDesc, nav_msgs::Odometry, rtabmap_msgs::UserData, sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo, rtabmap_msgs::ScanDescriptor);
333  DATA_SYNCS6(depthOdomDataInfo, nav_msgs::Odometry, rtabmap_msgs::UserData, sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo, rtabmap_msgs::OdomInfo);
334  DATA_SYNCS7(depthOdomDataScan2dInfo, nav_msgs::Odometry, rtabmap_msgs::UserData, sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo, sensor_msgs::LaserScan, rtabmap_msgs::OdomInfo);
335  DATA_SYNCS7(depthOdomDataScan3dInfo, nav_msgs::Odometry, rtabmap_msgs::UserData, sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo, sensor_msgs::PointCloud2, rtabmap_msgs::OdomInfo);
336  DATA_SYNCS7(depthOdomDataScanDescInfo, nav_msgs::Odometry, rtabmap_msgs::UserData, sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo, rtabmap_msgs::ScanDescriptor, rtabmap_msgs::OdomInfo);
337 #endif
338 
339  // Stereo
340  DATA_SYNCS4(stereo, sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo, sensor_msgs::CameraInfo);
341  DATA_SYNCS5(stereoInfo, sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo, sensor_msgs::CameraInfo, rtabmap_msgs::OdomInfo);
342 
343  // Stereo + Odom
344  DATA_SYNCS5(stereoOdom, nav_msgs::Odometry, sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo, sensor_msgs::CameraInfo);
345  DATA_SYNCS6(stereoOdomInfo, nav_msgs::Odometry, sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo, sensor_msgs::CameraInfo, rtabmap_msgs::OdomInfo);
346 
347  // RGB-only
348  DATA_SYNCS2(rgb, sensor_msgs::Image, sensor_msgs::CameraInfo);
349  DATA_SYNCS3(rgbScan2d, sensor_msgs::Image, sensor_msgs::CameraInfo, sensor_msgs::LaserScan);
350  DATA_SYNCS3(rgbScan3d, sensor_msgs::Image, sensor_msgs::CameraInfo, sensor_msgs::PointCloud2);
351  DATA_SYNCS3(rgbScanDesc, sensor_msgs::Image, sensor_msgs::CameraInfo, rtabmap_msgs::ScanDescriptor);
352  DATA_SYNCS3(rgbInfo, sensor_msgs::Image, sensor_msgs::CameraInfo, rtabmap_msgs::OdomInfo);
353  DATA_SYNCS4(rgbScan2dInfo, sensor_msgs::Image, sensor_msgs::CameraInfo, sensor_msgs::LaserScan, rtabmap_msgs::OdomInfo);
354  DATA_SYNCS4(rgbScan3dInfo, sensor_msgs::Image, sensor_msgs::CameraInfo, sensor_msgs::PointCloud2, rtabmap_msgs::OdomInfo);
355  DATA_SYNCS4(rgbScanDescInfo, sensor_msgs::Image, sensor_msgs::CameraInfo, rtabmap_msgs::ScanDescriptor, rtabmap_msgs::OdomInfo);
356 
357  // RGB-only + Odom
358  DATA_SYNCS3(rgbOdom, nav_msgs::Odometry, sensor_msgs::Image, sensor_msgs::CameraInfo);
359  DATA_SYNCS4(rgbOdomScan2d, nav_msgs::Odometry, sensor_msgs::Image, sensor_msgs::CameraInfo, sensor_msgs::LaserScan);
360  DATA_SYNCS4(rgbOdomScan3d, nav_msgs::Odometry, sensor_msgs::Image, sensor_msgs::CameraInfo, sensor_msgs::PointCloud2);
361  DATA_SYNCS4(rgbOdomScanDesc, nav_msgs::Odometry, sensor_msgs::Image, sensor_msgs::CameraInfo, rtabmap_msgs::ScanDescriptor);
362  DATA_SYNCS4(rgbOdomInfo, nav_msgs::Odometry, sensor_msgs::Image, sensor_msgs::CameraInfo, rtabmap_msgs::OdomInfo);
363  DATA_SYNCS5(rgbOdomScan2dInfo, nav_msgs::Odometry, sensor_msgs::Image, sensor_msgs::CameraInfo, sensor_msgs::LaserScan, rtabmap_msgs::OdomInfo);
364  DATA_SYNCS5(rgbOdomScan3dInfo, nav_msgs::Odometry, sensor_msgs::Image, sensor_msgs::CameraInfo, sensor_msgs::PointCloud2, rtabmap_msgs::OdomInfo);
365  DATA_SYNCS5(rgbOdomScanDescInfo, nav_msgs::Odometry, sensor_msgs::Image, sensor_msgs::CameraInfo, rtabmap_msgs::ScanDescriptor, rtabmap_msgs::OdomInfo);
366 
367 #ifdef RTABMAP_SYNC_USER_DATA
368  // RGB-only + User Data
369  DATA_SYNCS3(rgbData, rtabmap_msgs::UserData, sensor_msgs::Image, sensor_msgs::CameraInfo);
370  DATA_SYNCS4(rgbDataScan2d, rtabmap_msgs::UserData, sensor_msgs::Image, sensor_msgs::CameraInfo, sensor_msgs::LaserScan);
371  DATA_SYNCS4(rgbDataScan3d, rtabmap_msgs::UserData, sensor_msgs::Image, sensor_msgs::CameraInfo, sensor_msgs::PointCloud2);
372  DATA_SYNCS4(rgbDataScanDesc, rtabmap_msgs::UserData, sensor_msgs::Image, sensor_msgs::CameraInfo, rtabmap_msgs::ScanDescriptor);
373  DATA_SYNCS4(rgbDataInfo, rtabmap_msgs::UserData, sensor_msgs::Image, sensor_msgs::CameraInfo, rtabmap_msgs::OdomInfo);
374  DATA_SYNCS5(rgbDataScan2dInfo, rtabmap_msgs::UserData, sensor_msgs::Image, sensor_msgs::CameraInfo, sensor_msgs::LaserScan, rtabmap_msgs::OdomInfo);
375  DATA_SYNCS5(rgbDataScan3dInfo, rtabmap_msgs::UserData, sensor_msgs::Image, sensor_msgs::CameraInfo, sensor_msgs::PointCloud2, rtabmap_msgs::OdomInfo);
376  DATA_SYNCS5(rgbDataScanDescInfo, rtabmap_msgs::UserData, sensor_msgs::Image, sensor_msgs::CameraInfo, rtabmap_msgs::ScanDescriptor, rtabmap_msgs::OdomInfo);
377 
378  // RGB-only + Odom + User Data
379  DATA_SYNCS4(rgbOdomData, nav_msgs::Odometry, rtabmap_msgs::UserData, sensor_msgs::Image, sensor_msgs::CameraInfo);
380  DATA_SYNCS5(rgbOdomDataScan2d, nav_msgs::Odometry, rtabmap_msgs::UserData, sensor_msgs::Image, sensor_msgs::CameraInfo, sensor_msgs::LaserScan);
381  DATA_SYNCS5(rgbOdomDataScan3d, nav_msgs::Odometry, rtabmap_msgs::UserData, sensor_msgs::Image, sensor_msgs::CameraInfo, sensor_msgs::PointCloud2);
382  DATA_SYNCS5(rgbOdomDataScanDesc, nav_msgs::Odometry, rtabmap_msgs::UserData, sensor_msgs::Image, sensor_msgs::CameraInfo, rtabmap_msgs::ScanDescriptor);
383  DATA_SYNCS5(rgbOdomDataInfo, nav_msgs::Odometry, rtabmap_msgs::UserData, sensor_msgs::Image, sensor_msgs::CameraInfo, rtabmap_msgs::OdomInfo);
384  DATA_SYNCS6(rgbOdomDataScan2dInfo, nav_msgs::Odometry, rtabmap_msgs::UserData, sensor_msgs::Image, sensor_msgs::CameraInfo, sensor_msgs::LaserScan, rtabmap_msgs::OdomInfo);
385  DATA_SYNCS6(rgbOdomDataScan3dInfo, nav_msgs::Odometry, rtabmap_msgs::UserData, sensor_msgs::Image, sensor_msgs::CameraInfo, sensor_msgs::PointCloud2, rtabmap_msgs::OdomInfo);
386  DATA_SYNCS6(rgbOdomDataScanDescInfo, nav_msgs::Odometry, rtabmap_msgs::UserData, sensor_msgs::Image, sensor_msgs::CameraInfo, rtabmap_msgs::ScanDescriptor, rtabmap_msgs::OdomInfo);
387 #endif
388 
389  // 1 RGBD
390  void rgbdCallback(const rtabmap_msgs::RGBDImageConstPtr&);
391  DATA_SYNCS2(rgbdScan2d, rtabmap_msgs::RGBDImage, sensor_msgs::LaserScan);
392  DATA_SYNCS2(rgbdScan3d, rtabmap_msgs::RGBDImage, sensor_msgs::PointCloud2)
393  DATA_SYNCS2(rgbdScanDesc, rtabmap_msgs::RGBDImage, rtabmap_msgs::ScanDescriptor);
394  DATA_SYNCS2(rgbdInfo, rtabmap_msgs::RGBDImage, rtabmap_msgs::OdomInfo);
395 
396  // 1 RGBD + Odom
397  DATA_SYNCS2(rgbdOdom, nav_msgs::Odometry, rtabmap_msgs::RGBDImage);
398  DATA_SYNCS3(rgbdOdomScan2d, nav_msgs::Odometry, rtabmap_msgs::RGBDImage, sensor_msgs::LaserScan);
399  DATA_SYNCS3(rgbdOdomScan3d, nav_msgs::Odometry, rtabmap_msgs::RGBDImage, sensor_msgs::PointCloud2);
400  DATA_SYNCS3(rgbdOdomScanDesc, nav_msgs::Odometry, rtabmap_msgs::RGBDImage, rtabmap_msgs::ScanDescriptor);
401  DATA_SYNCS3(rgbdOdomInfo, nav_msgs::Odometry, rtabmap_msgs::RGBDImage, rtabmap_msgs::OdomInfo);
402 
403 #ifdef RTABMAP_SYNC_USER_DATA
404  // 1 RGBD + User Data
405  DATA_SYNCS2(rgbdData, rtabmap_msgs::UserData, rtabmap_msgs::RGBDImage);
406  DATA_SYNCS3(rgbdDataScan2d, rtabmap_msgs::UserData, rtabmap_msgs::RGBDImage, sensor_msgs::LaserScan);
407  DATA_SYNCS3(rgbdDataScan3d, rtabmap_msgs::UserData, rtabmap_msgs::RGBDImage, sensor_msgs::PointCloud2);
408  DATA_SYNCS3(rgbdDataScanDesc, rtabmap_msgs::UserData, rtabmap_msgs::RGBDImage, rtabmap_msgs::ScanDescriptor);
409  DATA_SYNCS3(rgbdDataInfo, rtabmap_msgs::UserData, rtabmap_msgs::RGBDImage, rtabmap_msgs::OdomInfo);
410 
411  // 1 RGBD + Odom + User Data
412  DATA_SYNCS3(rgbdOdomData, nav_msgs::Odometry, rtabmap_msgs::UserData, rtabmap_msgs::RGBDImage);
413  DATA_SYNCS4(rgbdOdomDataScan2d, nav_msgs::Odometry, rtabmap_msgs::UserData, rtabmap_msgs::RGBDImage, sensor_msgs::LaserScan);
414  DATA_SYNCS4(rgbdOdomDataScan3d, nav_msgs::Odometry, rtabmap_msgs::UserData, rtabmap_msgs::RGBDImage, sensor_msgs::PointCloud2);
415  DATA_SYNCS4(rgbdOdomDataScanDesc, nav_msgs::Odometry, rtabmap_msgs::UserData, rtabmap_msgs::RGBDImage, rtabmap_msgs::ScanDescriptor);
416  DATA_SYNCS4(rgbdOdomDataInfo, nav_msgs::Odometry, rtabmap_msgs::UserData, rtabmap_msgs::RGBDImage, rtabmap_msgs::OdomInfo);
417 #endif
418 
419  // X RGBD
420  void rgbdXCallback(const rtabmap_msgs::RGBDImagesConstPtr&);
421  DATA_SYNCS2(rgbdXScan2d, rtabmap_msgs::RGBDImages, sensor_msgs::LaserScan);
422  DATA_SYNCS2(rgbdXScan3d, rtabmap_msgs::RGBDImages, sensor_msgs::PointCloud2)
423  DATA_SYNCS2(rgbdXScanDesc, rtabmap_msgs::RGBDImages, rtabmap_msgs::ScanDescriptor);
424  DATA_SYNCS2(rgbdXInfo, rtabmap_msgs::RGBDImages, rtabmap_msgs::OdomInfo);
425 
426  // X RGBD + Odom
427  DATA_SYNCS2(rgbdXOdom, nav_msgs::Odometry, rtabmap_msgs::RGBDImages);
428  DATA_SYNCS3(rgbdXOdomScan2d, nav_msgs::Odometry, rtabmap_msgs::RGBDImages, sensor_msgs::LaserScan);
429  DATA_SYNCS3(rgbdXOdomScan3d, nav_msgs::Odometry, rtabmap_msgs::RGBDImages, sensor_msgs::PointCloud2);
430  DATA_SYNCS3(rgbdXOdomScanDesc, nav_msgs::Odometry, rtabmap_msgs::RGBDImages, rtabmap_msgs::ScanDescriptor);
431  DATA_SYNCS3(rgbdXOdomInfo, nav_msgs::Odometry, rtabmap_msgs::RGBDImages, rtabmap_msgs::OdomInfo);
432 
433 #ifdef RTABMAP_SYNC_USER_DATA
434  // X RGBD + User Data
435  DATA_SYNCS2(rgbdXData, rtabmap_msgs::UserData, rtabmap_msgs::RGBDImages);
436  DATA_SYNCS3(rgbdXDataScan2d, rtabmap_msgs::UserData, rtabmap_msgs::RGBDImages, sensor_msgs::LaserScan);
437  DATA_SYNCS3(rgbdXDataScan3d, rtabmap_msgs::UserData, rtabmap_msgs::RGBDImages, sensor_msgs::PointCloud2);
438  DATA_SYNCS3(rgbdXDataScanDesc, rtabmap_msgs::UserData, rtabmap_msgs::RGBDImages, rtabmap_msgs::ScanDescriptor);
439  DATA_SYNCS3(rgbdXDataInfo, rtabmap_msgs::UserData, rtabmap_msgs::RGBDImages, rtabmap_msgs::OdomInfo);
440 
441  // X RGBD + Odom + User Data
442  DATA_SYNCS3(rgbdXOdomData, nav_msgs::Odometry, rtabmap_msgs::UserData, rtabmap_msgs::RGBDImages);
443  DATA_SYNCS4(rgbdXOdomDataScan2d, nav_msgs::Odometry, rtabmap_msgs::UserData, rtabmap_msgs::RGBDImages, sensor_msgs::LaserScan);
444  DATA_SYNCS4(rgbdXOdomDataScan3d, nav_msgs::Odometry, rtabmap_msgs::UserData, rtabmap_msgs::RGBDImages, sensor_msgs::PointCloud2);
445  DATA_SYNCS4(rgbdXOdomDataScanDesc, nav_msgs::Odometry, rtabmap_msgs::UserData, rtabmap_msgs::RGBDImages, rtabmap_msgs::ScanDescriptor);
446  DATA_SYNCS4(rgbdXOdomDataInfo, nav_msgs::Odometry, rtabmap_msgs::UserData, rtabmap_msgs::RGBDImages, rtabmap_msgs::OdomInfo);
447 #endif
448 
449  // SensorData
450  void sensorDataCallback(const rtabmap_msgs::SensorDataConstPtr&);
451  DATA_SYNCS2(sensorDataInfo, rtabmap_msgs::SensorData, rtabmap_msgs::OdomInfo);
452 
453  // SensorData + Odom
454  DATA_SYNCS2(sensorDataOdom, nav_msgs::Odometry, rtabmap_msgs::SensorData);
455  DATA_SYNCS3(sensorDataOdomInfo, nav_msgs::Odometry, rtabmap_msgs::SensorData, rtabmap_msgs::OdomInfo);
456 
457 #ifdef RTABMAP_SYNC_MULTI_RGBD
458  // 2 RGBD
459  DATA_SYNCS2(rgbd2, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage);
460  DATA_SYNCS3(rgbd2Scan2d, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, sensor_msgs::LaserScan);
461  DATA_SYNCS3(rgbd2Scan3d, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, sensor_msgs::PointCloud2);
462  DATA_SYNCS3(rgbd2ScanDesc, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::ScanDescriptor);
463  DATA_SYNCS3(rgbd2Info, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::OdomInfo);
464 
465  // 2 RGBD + Odom
466  DATA_SYNCS3(rgbd2Odom, nav_msgs::Odometry, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage);
467  DATA_SYNCS4(rgbd2OdomScan2d, nav_msgs::Odometry, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, sensor_msgs::LaserScan);
468  DATA_SYNCS4(rgbd2OdomScan3d, nav_msgs::Odometry, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, sensor_msgs::PointCloud2);
469  DATA_SYNCS4(rgbd2OdomScanDesc, nav_msgs::Odometry, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::ScanDescriptor);
470  DATA_SYNCS4(rgbd2OdomInfo, nav_msgs::Odometry, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::OdomInfo);
471 
472 #ifdef RTABMAP_SYNC_USER_DATA
473  // 2 RGBD + User Data
474  DATA_SYNCS3(rgbd2Data, rtabmap_msgs::UserData, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage);
475  DATA_SYNCS4(rgbd2DataScan2d, rtabmap_msgs::UserData, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, sensor_msgs::LaserScan);
476  DATA_SYNCS4(rgbd2DataScan3d, rtabmap_msgs::UserData, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, sensor_msgs::PointCloud2);
477  DATA_SYNCS4(rgbd2DataScanDesc, rtabmap_msgs::UserData, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::ScanDescriptor);
478  DATA_SYNCS4(rgbd2DataInfo, rtabmap_msgs::UserData, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::OdomInfo);
479 
480  // 2 RGBD + Odom + User Data
481  DATA_SYNCS4(rgbd2OdomData, nav_msgs::Odometry, rtabmap_msgs::UserData, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage);
482  DATA_SYNCS5(rgbd2OdomDataScan2d, nav_msgs::Odometry, rtabmap_msgs::UserData, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, sensor_msgs::LaserScan);
483  DATA_SYNCS5(rgbd2OdomDataScan3d, nav_msgs::Odometry, rtabmap_msgs::UserData, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, sensor_msgs::PointCloud2);
484  DATA_SYNCS5(rgbd2OdomDataScanDesc, nav_msgs::Odometry, rtabmap_msgs::UserData, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::ScanDescriptor);
485  DATA_SYNCS5(rgbd2OdomDataInfo, nav_msgs::Odometry, rtabmap_msgs::UserData, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::OdomInfo);
486 #endif
487 
488  // 3 RGBD
489  DATA_SYNCS3(rgbd3, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage);
490  DATA_SYNCS4(rgbd3Scan2d, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, sensor_msgs::LaserScan);
491  DATA_SYNCS4(rgbd3Scan3d, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, sensor_msgs::PointCloud2);
492  DATA_SYNCS4(rgbd3ScanDesc, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::ScanDescriptor);
493  DATA_SYNCS4(rgbd3Info, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::OdomInfo);
494 
495  // 3 RGBD + Odom
496  DATA_SYNCS4(rgbd3Odom, nav_msgs::Odometry, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage);
497  DATA_SYNCS5(rgbd3OdomScan2d, nav_msgs::Odometry, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, sensor_msgs::LaserScan);
498  DATA_SYNCS5(rgbd3OdomScan3d, nav_msgs::Odometry, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, sensor_msgs::PointCloud2);
499  DATA_SYNCS5(rgbd3OdomScanDesc, nav_msgs::Odometry, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::ScanDescriptor);
500  DATA_SYNCS5(rgbd3OdomInfo, nav_msgs::Odometry, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::OdomInfo);
501 
502 #ifdef RTABMAP_SYNC_USER_DATA
503  // 3 RGBD + User Data
504  DATA_SYNCS4(rgbd3Data, rtabmap_msgs::UserData, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage);
505  DATA_SYNCS5(rgbd3DataScan2d, rtabmap_msgs::UserData, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, sensor_msgs::LaserScan);
506  DATA_SYNCS5(rgbd3DataScan3d, rtabmap_msgs::UserData, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, sensor_msgs::PointCloud2);
507  DATA_SYNCS5(rgbd3DataScanDesc, rtabmap_msgs::UserData, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::ScanDescriptor);
508  DATA_SYNCS5(rgbd3DataInfo, rtabmap_msgs::UserData, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::OdomInfo);
509 
510  // 3 RGBD + Odom + User Data
511  DATA_SYNCS5(rgbd3OdomData, nav_msgs::Odometry, rtabmap_msgs::UserData, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage);
512  DATA_SYNCS6(rgbd3OdomDataScan2d, nav_msgs::Odometry, rtabmap_msgs::UserData, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, sensor_msgs::LaserScan);
513  DATA_SYNCS6(rgbd3OdomDataScan3d, nav_msgs::Odometry, rtabmap_msgs::UserData, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, sensor_msgs::PointCloud2);
514  DATA_SYNCS6(rgbd3OdomDataScanDesc, nav_msgs::Odometry, rtabmap_msgs::UserData, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::ScanDescriptor);
515  DATA_SYNCS6(rgbd3OdomDataInfo, nav_msgs::Odometry, rtabmap_msgs::UserData, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::OdomInfo);
516 #endif
517 
518  // 4 RGBD
519  DATA_SYNCS4(rgbd4, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage);
520  DATA_SYNCS5(rgbd4Scan2d, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, sensor_msgs::LaserScan);
521  DATA_SYNCS5(rgbd4Scan3d, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, sensor_msgs::PointCloud2);
522  DATA_SYNCS5(rgbd4ScanDesc, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::ScanDescriptor);
523  DATA_SYNCS5(rgbd4Info, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::OdomInfo);
524 
525  // 4 RGBD + Odom
526  DATA_SYNCS5(rgbd4Odom, nav_msgs::Odometry, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage);
527  DATA_SYNCS6(rgbd4OdomScan2d, nav_msgs::Odometry, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, sensor_msgs::LaserScan);
528  DATA_SYNCS6(rgbd4OdomScan3d, nav_msgs::Odometry, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, sensor_msgs::PointCloud2);
529  DATA_SYNCS6(rgbd4OdomScanDesc, nav_msgs::Odometry, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::ScanDescriptor);
530  DATA_SYNCS6(rgbd4OdomInfo, nav_msgs::Odometry, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::OdomInfo);
531 
532 #ifdef RTABMAP_SYNC_USER_DATA
533  // 4 RGBD + User Data
534  DATA_SYNCS5(rgbd4Data, rtabmap_msgs::UserData, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage);
535  DATA_SYNCS6(rgbd4DataScan2d, rtabmap_msgs::UserData, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, sensor_msgs::LaserScan);
536  DATA_SYNCS6(rgbd4DataScan3d, rtabmap_msgs::UserData, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, sensor_msgs::PointCloud2);
537  DATA_SYNCS6(rgbd4DataScanDesc, rtabmap_msgs::UserData, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::ScanDescriptor);
538  DATA_SYNCS6(rgbd4DataInfo, rtabmap_msgs::UserData, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::OdomInfo);
539 
540  // 4 RGBD + Odom + User Data
541  DATA_SYNCS6(rgbd4OdomData, nav_msgs::Odometry, rtabmap_msgs::UserData, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage);
542  DATA_SYNCS7(rgbd4OdomDataScan2d, nav_msgs::Odometry, rtabmap_msgs::UserData, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, sensor_msgs::LaserScan);
543  DATA_SYNCS7(rgbd4OdomDataScan3d, nav_msgs::Odometry, rtabmap_msgs::UserData, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, sensor_msgs::PointCloud2);
544  DATA_SYNCS7(rgbd4OdomDataScanDesc, nav_msgs::Odometry, rtabmap_msgs::UserData, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::ScanDescriptor);
545  DATA_SYNCS7(rgbd4OdomDataInfo, nav_msgs::Odometry, rtabmap_msgs::UserData, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::OdomInfo);
546 #endif
547 
548  // 5 RGBD
549  DATA_SYNCS5(rgbd5, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage);
550  DATA_SYNCS6(rgbd5Scan2d, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, sensor_msgs::LaserScan);
551  DATA_SYNCS6(rgbd5Scan3d, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, sensor_msgs::PointCloud2);
552  DATA_SYNCS6(rgbd5ScanDesc, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::ScanDescriptor);
553  DATA_SYNCS6(rgbd5Info, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::OdomInfo);
554 
555  // 5 RGBD + Odom
556  DATA_SYNCS6(rgbd5Odom, nav_msgs::Odometry, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage);
557  DATA_SYNCS7(rgbd5OdomScan2d, nav_msgs::Odometry, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, sensor_msgs::LaserScan);
558  DATA_SYNCS7(rgbd5OdomScan3d, nav_msgs::Odometry, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, sensor_msgs::PointCloud2);
559  DATA_SYNCS7(rgbd5OdomScanDesc, nav_msgs::Odometry, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::ScanDescriptor);
560  DATA_SYNCS7(rgbd5OdomInfo, nav_msgs::Odometry, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::OdomInfo);
561 
562  // 6 RGBD
563  DATA_SYNCS6(rgbd6, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage);
564  DATA_SYNCS7(rgbd6Scan2d, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, sensor_msgs::LaserScan);
565  DATA_SYNCS7(rgbd6Scan3d, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, sensor_msgs::PointCloud2);
566  DATA_SYNCS7(rgbd6ScanDesc, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::ScanDescriptor);
567  DATA_SYNCS7(rgbd6Info, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::OdomInfo);
568 
569  // 6 RGBD + Odom
570  DATA_SYNCS7(rgbd6Odom, nav_msgs::Odometry, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage);
571  DATA_SYNCS8(rgbd6OdomScan2d, nav_msgs::Odometry, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, sensor_msgs::LaserScan);
572  DATA_SYNCS8(rgbd6OdomScan3d, nav_msgs::Odometry, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, sensor_msgs::PointCloud2);
573  DATA_SYNCS8(rgbd6OdomScanDesc, nav_msgs::Odometry, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::ScanDescriptor);
574  DATA_SYNCS8(rgbd6OdomInfo, nav_msgs::Odometry, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::OdomInfo);
575 
576 #endif //RTABMAP_SYNC_MULTI_RGBD
577 
578  // Scan
579  void scan2dCallback(const sensor_msgs::LaserScanConstPtr&);
580  void scan3dCallback(const sensor_msgs::PointCloud2ConstPtr&);
581  void scanDescCallback(const rtabmap_msgs::ScanDescriptorConstPtr&);
582  DATA_SYNCS2(scan2dInfo, sensor_msgs::LaserScan, rtabmap_msgs::OdomInfo);
583  DATA_SYNCS2(scan3dInfo, sensor_msgs::PointCloud2, rtabmap_msgs::OdomInfo);
584  DATA_SYNCS2(scanDescInfo, rtabmap_msgs::ScanDescriptor, rtabmap_msgs::OdomInfo);
585 
586  // Scan + Odom
587  DATA_SYNCS2(odomScan2d, nav_msgs::Odometry, sensor_msgs::LaserScan);
588  DATA_SYNCS2(odomScan3d, nav_msgs::Odometry, sensor_msgs::PointCloud2);
589  DATA_SYNCS2(odomScanDesc, nav_msgs::Odometry, rtabmap_msgs::ScanDescriptor);
590  DATA_SYNCS3(odomScan2dInfo, nav_msgs::Odometry, sensor_msgs::LaserScan, rtabmap_msgs::OdomInfo);
591  DATA_SYNCS3(odomScan3dInfo, nav_msgs::Odometry, sensor_msgs::PointCloud2, rtabmap_msgs::OdomInfo);
592  DATA_SYNCS3(odomScanDescInfo, nav_msgs::Odometry, rtabmap_msgs::ScanDescriptor, rtabmap_msgs::OdomInfo);
593 
594 #ifdef RTABMAP_SYNC_USER_DATA
595  // Scan + User Data
596  DATA_SYNCS2(dataScan2d, rtabmap_msgs::UserData, sensor_msgs::LaserScan);
597  DATA_SYNCS2(dataScan3d, rtabmap_msgs::UserData, sensor_msgs::PointCloud2);
598  DATA_SYNCS2(dataScanDesc, rtabmap_msgs::UserData, rtabmap_msgs::ScanDescriptor);
599  DATA_SYNCS3(dataScan2dInfo, rtabmap_msgs::UserData, sensor_msgs::LaserScan, rtabmap_msgs::OdomInfo);
600  DATA_SYNCS3(dataScan3dInfo, rtabmap_msgs::UserData, sensor_msgs::PointCloud2, rtabmap_msgs::OdomInfo);
601  DATA_SYNCS3(dataScanDescInfo, rtabmap_msgs::UserData, rtabmap_msgs::ScanDescriptor, rtabmap_msgs::OdomInfo);
602 
603  // Scan + Odom + User Data
604  DATA_SYNCS3(odomDataScan2d, nav_msgs::Odometry, rtabmap_msgs::UserData, sensor_msgs::LaserScan);
605  DATA_SYNCS3(odomDataScan3d, nav_msgs::Odometry, rtabmap_msgs::UserData, sensor_msgs::PointCloud2);
606  DATA_SYNCS3(odomDataScanDesc, nav_msgs::Odometry, rtabmap_msgs::UserData, rtabmap_msgs::ScanDescriptor);
607  DATA_SYNCS4(odomDataScan2dInfo, nav_msgs::Odometry, rtabmap_msgs::UserData, sensor_msgs::LaserScan, rtabmap_msgs::OdomInfo);
608  DATA_SYNCS4(odomDataScan3dInfo, nav_msgs::Odometry, rtabmap_msgs::UserData, sensor_msgs::PointCloud2, rtabmap_msgs::OdomInfo);
609  DATA_SYNCS4(odomDataScanDescInfo, nav_msgs::Odometry, rtabmap_msgs::UserData, rtabmap_msgs::ScanDescriptor, rtabmap_msgs::OdomInfo);
610 #endif
611 
612  // Odom
613  void odomCallback(const nav_msgs::OdometryConstPtr&);
614  DATA_SYNCS2(odomInfo, nav_msgs::Odometry, rtabmap_msgs::OdomInfo);
615 
616 #ifdef RTABMAP_SYNC_USER_DATA
617  // Odom + User Data
618  DATA_SYNCS2(odomData, nav_msgs::Odometry, rtabmap_msgs::UserData);
619  DATA_SYNCS3(odomDataInfo, nav_msgs::Odometry, rtabmap_msgs::UserData, rtabmap_msgs::OdomInfo);
620 #endif
621 };
622 
623 } /* namespace rtabmap_sync */
624 
625 #endif /* INCLUDE_RTABMAP_ROS_COMMONDATASUBSCRIBER_H_ */
rtabmap_sync::CommonDataSubscriber::name_
std::string name_
Definition: CommonDataSubscriber.h:260
int
int
image_transport::SubscriberFilter
rtabmap_sync::CommonDataSubscriber::scan3dSubOnly_
ros::Subscriber scan3dSubOnly_
Definition: CommonDataSubscriber.h:291
name
rtabmap_sync::CommonDataSubscriber::setupSensorDataCallbacks
void setupSensorDataCallbacks(ros::NodeHandle &nh, ros::NodeHandle &pnh, bool subscribeOdom, bool subscribeOdomInfo)
Definition: CommonDataSubscriberSensorData.cpp:67
rtabmap_sync::CommonDataSubscriber::imageRectLeft_
image_transport::SubscriberFilter imageRectLeft_
Definition: CommonDataSubscriber.h:278
rtabmap_sync::CommonDataSubscriber::setupOdomCallbacks
void setupOdomCallbacks(ros::NodeHandle &nh, ros::NodeHandle &pnh, bool subscribeUserData, bool subscribeOdomInfo)
Definition: CommonDataSubscriberOdom.cpp:66
rtabmap_sync::CommonDataSubscriber::DATA_SYNCS2
DATA_SYNCS2(rgb, sensor_msgs::Image, sensor_msgs::CameraInfo)
rtabmap_sync::CommonDataSubscriber::rgbdCameras
int rgbdCameras() const
Definition: CommonDataSubscriber.h:76
boost::shared_ptr
rtabmap_sync::CommonDataSubscriber::setupRGBCallbacks
void setupRGBCallbacks(ros::NodeHandle &nh, ros::NodeHandle &pnh, bool subscribeOdom, bool subscribeUserData, bool subscribeScan2d, bool subscribeScan3d, bool subscribeScanDesc, bool subscribeOdomInfo)
Definition: CommonDataSubscriberRGB.cpp:458
rtabmap_sync::CommonDataSubscriber::DATA_SYNCS5
DATA_SYNCS5(depthScan2dInfo, sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo, sensor_msgs::LaserScan, rtabmap_msgs::OdomInfo)
rtabmap_sync::CommonDataSubscriber::~CommonDataSubscriber
virtual ~CommonDataSubscriber()
Definition: CommonDataSubscriber.cpp:731
rtabmap_sync::CommonDataSubscriber::rgbdXCallback
void rgbdXCallback(const rtabmap_msgs::RGBDImagesConstPtr &)
Definition: CommonDataSubscriberRGBDX.cpp:61
rtabmap_sync::CommonDataSubscriber::sensorDataSubOnly_
ros::Subscriber sensorDataSubOnly_
Definition: CommonDataSubscriber.h:274
rtabmap_sync
Definition: CommonDataSubscriber.h:59
rtabmap_sync::CommonDataSubscriber::scan2dSubOnly_
ros::Subscriber scan2dSubOnly_
Definition: CommonDataSubscriber.h:290
rtabmap_sync::CommonDataSubscriber::isSubscribedToRGBD
bool isSubscribedToRGBD() const
Definition: CommonDataSubscriber.h:70
SyncDiagnostic.h
rtabmap_sync::CommonDataSubscriber::getTopicQueueSize
int getTopicQueueSize() const
Definition: CommonDataSubscriber.h:77
rtabmap_sync::CommonDataSubscriber::imageDepthSub_
image_transport::SubscriberFilter imageDepthSub_
Definition: CommonDataSubscriber.h:264
rtabmap_sync::CommonDataSubscriber::isSubscribedToRGB
bool isSubscribedToRGB() const
Definition: CommonDataSubscriber.h:68
rtabmap_sync::CommonDataSubscriber::setupStereoCallbacks
void setupStereoCallbacks(ros::NodeHandle &nh, ros::NodeHandle &pnh, bool subscribeOdom, bool subscribeOdomInfo)
Definition: CommonDataSubscriberStereo.cpp:88
rtabmap_sync::CommonDataSubscriber::odomSubOnly_
ros::Subscriber odomSubOnly_
Definition: CommonDataSubscriber.h:293
rtabmap_sync::CommonDataSubscriber::commonLaserScanCallback
virtual void commonLaserScanCallback(const nav_msgs::OdometryConstPtr &odomMsg, const rtabmap_msgs::UserDataConstPtr &userDataMsg, const sensor_msgs::LaserScan &scanMsg, const sensor_msgs::PointCloud2 &scan3dMsg, const rtabmap_msgs::OdomInfoConstPtr &odomInfoMsg, const rtabmap_msgs::GlobalDescriptor &globalDescriptor=rtabmap_msgs::GlobalDescriptor())=0
rtabmap_sync::CommonDataSubscriber::isSubscribedToDepth
bool isSubscribedToDepth() const
Definition: CommonDataSubscriber.h:66
rtabmap_sync::CommonDataSubscriber::commonOdomCallback
virtual void commonOdomCallback(const nav_msgs::OdometryConstPtr &odomMsg, const rtabmap_msgs::UserDataConstPtr &userDataMsg, const rtabmap_msgs::OdomInfoConstPtr &odomInfoMsg)=0
rtabmap_sync::CommonDataSubscriber::setupCallbacks
void setupCallbacks(ros::NodeHandle &nh, ros::NodeHandle &pnh, const std::string &name, std::vector< diagnostic_updater::DiagnosticTask * > otherTasks=std::vector< diagnostic_updater::DiagnosticTask * >())
Definition: CommonDataSubscriber.cpp:362
rtabmap_sync::CommonDataSubscriber::name
const std::string & name() const
Definition: CommonDataSubscriber.h:80
rtabmap_sync::CommonDataSubscriber::rgbdXSubOnly_
ros::Subscriber rgbdXSubOnly_
Definition: CommonDataSubscriber.h:270
rtabmap_sync::CommonDataSubscriber::commonSingleCameraCallback
void commonSingleCameraCallback(const nav_msgs::OdometryConstPtr &odomMsg, const rtabmap_msgs::UserDataConstPtr &userDataMsg, const cv_bridge::CvImageConstPtr &imageMsg, const cv_bridge::CvImageConstPtr &depthMsg, const sensor_msgs::CameraInfo &rgbCameraInfoMsg, const sensor_msgs::CameraInfo &depthCameraInfoMsg, const sensor_msgs::LaserScan &scanMsg, const sensor_msgs::PointCloud2 &scan3dMsg, const rtabmap_msgs::OdomInfoConstPtr &odomInfoMsg, const std::vector< rtabmap_msgs::GlobalDescriptor > &globalDescriptorMsgs=std::vector< rtabmap_msgs::GlobalDescriptor >(), const std::vector< rtabmap_msgs::KeyPoint > &localKeyPoints=std::vector< rtabmap_msgs::KeyPoint >(), const std::vector< rtabmap_msgs::Point3f > &localPoints3d=std::vector< rtabmap_msgs::Point3f >(), const cv::Mat &localDescriptors=cv::Mat())
Definition: CommonDataSubscriber.cpp:1048
rtabmap_sync::CommonDataSubscriber::scan3dSub_
message_filters::Subscriber< sensor_msgs::PointCloud2 > scan3dSub_
Definition: CommonDataSubscriber.h:286
rtabmap_sync::CommonDataSubscriber::imageRectRight_
image_transport::SubscriberFilter imageRectRight_
Definition: CommonDataSubscriber.h:279
rtabmap_sync::CommonDataSubscriber::isSubscribedToScan3d
bool isSubscribedToScan3d() const
Definition: CommonDataSubscriber.h:72
rtabmap_sync::CommonDataSubscriber::isSubscribedToScan2d
bool isSubscribedToScan2d() const
Definition: CommonDataSubscriber.h:71
rtabmap_sync::CommonDataSubscriber::odomInfoSub_
message_filters::Subscriber< rtabmap_msgs::OdomInfo > odomInfoSub_
Definition: CommonDataSubscriber.h:288
rtabmap_sync::CommonDataSubscriber::subscribedTopicsMsg_
std::string subscribedTopicsMsg_
Definition: CommonDataSubscriber.h:244
rtabmap_sync::CommonDataSubscriber::syncQueueSize_
int syncQueueSize_
Definition: CommonDataSubscriber.h:246
message_filters::Subscriber< sensor_msgs::CameraInfo >
rtabmap_sync::CommonDataSubscriber::subscribedToOdom_
bool subscribedToOdom_
Definition: CommonDataSubscriber.h:253
rtabmap_sync::CommonDataSubscriber::commonSensorDataCallback
virtual void commonSensorDataCallback(const rtabmap_msgs::SensorDataConstPtr &sensorDataMsg, const nav_msgs::OdometryConstPtr &odomMsg, const rtabmap_msgs::OdomInfoConstPtr &odomInfoMsg)=0
rtabmap_sync::CommonDataSubscriber::scanDescSub_
message_filters::Subscriber< rtabmap_msgs::ScanDescriptor > scanDescSub_
Definition: CommonDataSubscriber.h:287
rtabmap_sync::CommonDataSubscriber::topicQueueSize_
int topicQueueSize_
Definition: CommonDataSubscriber.h:245
subscriber_filter.h
rtabmap_sync::CommonDataSubscriber::setupDepthCallbacks
void setupDepthCallbacks(ros::NodeHandle &nh, ros::NodeHandle &pnh, bool subscribeOdom, bool subscribeUserData, bool subscribeScan2d, bool subscribeScan3d, bool subscribeScanDesc, bool subscribeOdomInfo)
Definition: CommonDataSubscriberDepth.cpp:458
rtabmap_sync::CommonDataSubscriber::DATA_SYNCS6
DATA_SYNCS6(depthOdomScan2dInfo, nav_msgs::Odometry, sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo, sensor_msgs::LaserScan, rtabmap_msgs::OdomInfo)
rtabmap_sync::CommonDataSubscriber::sensorDataCallback
void sensorDataCallback(const rtabmap_msgs::SensorDataConstPtr &)
Definition: CommonDataSubscriberSensorData.cpp:37
rtabmap_sync::CommonDataSubscriber::CommonDataSubscriber
CommonDataSubscriber(bool gui)
Definition: CommonDataSubscriber.cpp:32
rtabmap_sync::CommonDataSubscriber::subscribedToDepth_
bool subscribedToDepth_
Definition: CommonDataSubscriber.h:250
rtabmap_sync::CommonDataSubscriber::DATA_SYNCS3
DATA_SYNCS3(depth, sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo)
rtabmap_sync::CommonDataSubscriber::cameraInfoLeft_
message_filters::Subscriber< sensor_msgs::CameraInfo > cameraInfoLeft_
Definition: CommonDataSubscriber.h:280
rtabmap_sync::CommonDataSubscriber::subscribedToScan3d_
bool subscribedToScan3d_
Definition: CommonDataSubscriber.h:257
subscriber.h
rtabmap_sync::CommonDataSubscriber::subscribedToRGB_
bool subscribedToRGB_
Definition: CommonDataSubscriber.h:252
rtabmap_sync::CommonDataSubscriber::scanSub_
message_filters::Subscriber< sensor_msgs::LaserScan > scanSub_
Definition: CommonDataSubscriber.h:285
rtabmap_sync::CommonDataSubscriber::subscribedToScanDescriptor_
bool subscribedToScanDescriptor_
Definition: CommonDataSubscriber.h:258
rtabmap_sync::CommonDataSubscriber::isSubscribedToSensorData
bool isSubscribedToSensorData() const
Definition: CommonDataSubscriber.h:73
rtabmap_sync::CommonDataSubscriber::setupRGBDCallbacks
void setupRGBDCallbacks(ros::NodeHandle &nh, ros::NodeHandle &pnh, bool subscribeOdom, bool subscribeUserData, bool subscribeScan2d, bool subscribeScan3d, bool subscribeScanDesc, bool subscribeOdomInfo)
Definition: CommonDataSubscriberRGBD.cpp:534
rtabmap_sync::CommonDataSubscriber::isDataSubscribed
bool isDataSubscribed() const
Definition: CommonDataSubscriber.h:75
rtabmap_sync::CommonDataSubscriber::rgbdSub_
ros::Subscriber rgbdSub_
Definition: CommonDataSubscriber.h:268
rtabmap_sync::CommonDataSubscriber::DATA_SYNCS4
DATA_SYNCS4(depthScan2d, sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo, sensor_msgs::LaserScan)
CommonDataSubscriberDefines.h
DATA_SYNCS8
#define DATA_SYNCS8(PREFIX, MSG0, MSG1, MSG2, MSG3, MSG4, MSG5, MSG6, MSG7)
Definition: CommonDataSubscriberDefines.h:91
rtabmap_sync::CommonDataSubscriber::setupRGBDXCallbacks
void setupRGBDXCallbacks(ros::NodeHandle &nh, ros::NodeHandle &pnh, bool subscribeOdom, bool subscribeUserData, bool subscribeScan2d, bool subscribeScan3d, bool subscribeScanDesc, bool subscribeOdomInfo)
Definition: CommonDataSubscriberRGBDX.cpp:321
rtabmap_sync::CommonDataSubscriber::imageSub_
image_transport::SubscriberFilter imageSub_
Definition: CommonDataSubscriber.h:263
rtabmap_sync::CommonDataSubscriber::setupScanCallbacks
void setupScanCallbacks(ros::NodeHandle &nh, ros::NodeHandle &pnh, bool subscribeScan2d, bool subscribeScanDesc, bool subscribeOdom, bool subscribeUserData, bool subscribeOdomInfo)
Definition: CommonDataSubscriberScan.cpp:246
rtabmap_sync::CommonDataSubscriber::scan3dCallback
void scan3dCallback(const sensor_msgs::PointCloud2ConstPtr &)
Definition: CommonDataSubscriberScan.cpp:41
rtabmap_sync::CommonDataSubscriber::tick
void tick(const ros::Time &stamp, double targetFrequency=0)
Definition: CommonDataSubscriber.cpp:1100
image_transport.h
exact_time.h
rtabmap_sync::CommonDataSubscriber::getSyncQueueSize
int getSyncQueueSize() const
Definition: CommonDataSubscriber.h:78
rtabmap_sync::CommonDataSubscriber::odomCallback
void odomCallback(const nav_msgs::OdometryConstPtr &)
Definition: CommonDataSubscriberOdom.cpp:32
DATA_SYNCS7
#define DATA_SYNCS7(PREFIX, MSG0, MSG1, MSG2, MSG3, MSG4, MSG5, MSG6)
Definition: CommonDataSubscriberDefines.h:82
rtabmap_sync::CommonDataSubscriber::approxSync_
bool approxSync_
Definition: CommonDataSubscriber.h:249
rtabmap_sync::CommonDataSubscriber::scanDescCallback
void scanDescCallback(const rtabmap_msgs::ScanDescriptorConstPtr &)
Definition: CommonDataSubscriberScan.cpp:50
rtabmap_sync::CommonDataSubscriber::rgbdSubs_
std::vector< message_filters::Subscriber< rtabmap_msgs::RGBDImage > * > rgbdSubs_
Definition: CommonDataSubscriber.h:269
rtabmap_sync::CommonDataSubscriber::cameraInfoRight_
message_filters::Subscriber< sensor_msgs::CameraInfo > cameraInfoRight_
Definition: CommonDataSubscriber.h:281
rtabmap_sync::CommonDataSubscriber::subscribedToSensorData_
bool subscribedToSensorData_
Definition: CommonDataSubscriber.h:255
rtabmap_sync::CommonDataSubscriber::subscribedToRGBD_
bool subscribedToRGBD_
Definition: CommonDataSubscriber.h:254
rtabmap_sync::CommonDataSubscriber::syncDiagnostic_
std::unique_ptr< SyncDiagnostic > syncDiagnostic_
Definition: CommonDataSubscriber.h:295
ros::Time
rtabmap_sync::CommonDataSubscriber::odomSub_
message_filters::Subscriber< nav_msgs::Odometry > odomSub_
Definition: CommonDataSubscriber.h:283
cv_bridge.h
rtabmap_sync::CommonDataSubscriber::isSubscribedToOdom
bool isSubscribedToOdom() const
Definition: CommonDataSubscriber.h:69
rtabmap_sync::CommonDataSubscriber::subscribedToStereo_
bool subscribedToStereo_
Definition: CommonDataSubscriber.h:251
synchronizer.h
approximate_time.h
rtabmap_sync::CommonDataSubscriber::subscribedToOdomInfo_
bool subscribedToOdomInfo_
Definition: CommonDataSubscriber.h:259
rtabmap_sync::CommonDataSubscriber::rgbdCallback
void rgbdCallback(const rtabmap_msgs::RGBDImageConstPtr &)
Definition: CommonDataSubscriberRGBD.cpp:37
rtabmap_sync::CommonDataSubscriber::scanDescSubOnly_
ros::Subscriber scanDescSubOnly_
Definition: CommonDataSubscriber.h:292
rtabmap_sync::CommonDataSubscriber::subscribedToScan2d_
bool subscribedToScan2d_
Definition: CommonDataSubscriber.h:256
rtabmap_sync::CommonDataSubscriber::isSubscribedToOdomInfo
bool isSubscribedToOdomInfo() const
Definition: CommonDataSubscriber.h:74
rtabmap_sync::CommonDataSubscriber::sensorDataSub_
message_filters::Subscriber< rtabmap_msgs::SensorData > sensorDataSub_
Definition: CommonDataSubscriber.h:275
rtabmap_sync::CommonDataSubscriber::userDataSub_
message_filters::Subscriber< rtabmap_msgs::UserData > userDataSub_
Definition: CommonDataSubscriber.h:284
rtabmap_sync::CommonDataSubscriber::cameraInfoSub_
message_filters::Subscriber< sensor_msgs::CameraInfo > cameraInfoSub_
Definition: CommonDataSubscriber.h:265
rtabmap_sync::CommonDataSubscriber::commonMultiCameraCallback
virtual void commonMultiCameraCallback(const nav_msgs::OdometryConstPtr &odomMsg, const rtabmap_msgs::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_msgs::OdomInfoConstPtr &odomInfoMsg, const std::vector< rtabmap_msgs::GlobalDescriptor > &globalDescriptorMsgs=std::vector< rtabmap_msgs::GlobalDescriptor >(), const std::vector< std::vector< rtabmap_msgs::KeyPoint > > &localKeyPoints=std::vector< std::vector< rtabmap_msgs::KeyPoint > >(), const std::vector< std::vector< rtabmap_msgs::Point3f > > &localPoints3d=std::vector< std::vector< rtabmap_msgs::Point3f > >(), const std::vector< cv::Mat > &localDescriptors=std::vector< cv::Mat >())=0
rtabmap_sync::CommonDataSubscriber::isSubscribedToStereo
bool isSubscribedToStereo() const
Definition: CommonDataSubscriber.h:67
rtabmap_sync::CommonDataSubscriber
Definition: CommonDataSubscriber.h:61
rtabmap_sync::CommonDataSubscriber::scan2dCallback
void scan2dCallback(const sensor_msgs::LaserScanConstPtr &)
Definition: CommonDataSubscriberScan.cpp:32
rtabmap_sync::CommonDataSubscriber::rgbdXSub_
message_filters::Subscriber< rtabmap_msgs::RGBDImages > rgbdXSub_
Definition: CommonDataSubscriber.h:271
ros::NodeHandle
ros::Subscriber
rtabmap_sync::CommonDataSubscriber::isApproxSync
bool isApproxSync() const
Definition: CommonDataSubscriber.h:79


rtabmap_sync
Author(s): Mathieu Labbe
autogenerated on Mon Apr 28 2025 02:39:12