28 #ifndef INCLUDE_RTABMAP_ROS_COMMONDATASUBSCRIBER_H_
29 #define INCLUDE_RTABMAP_ROS_COMMONDATASUBSCRIBER_H_
41 #include <sensor_msgs/PointCloud2.h>
42 #include <sensor_msgs/Image.h>
43 #include <sensor_msgs/CameraInfo.h>
44 #include <sensor_msgs/LaserScan.h>
46 #include <nav_msgs/Odometry.h>
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>
57 #include <boost/thread.hpp>
86 const std::string &
name,
87 std::vector<diagnostic_updater::DiagnosticTask*> otherTasks = std::vector<diagnostic_updater::DiagnosticTask*>());
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;
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;
110 const nav_msgs::OdometryConstPtr & odomMsg,
111 const rtabmap_msgs::UserDataConstPtr & userDataMsg,
112 const rtabmap_msgs::OdomInfoConstPtr& odomInfoMsg) = 0;
114 const rtabmap_msgs::SensorDataConstPtr & sensorDataMsg,
115 const nav_msgs::OdometryConstPtr & odomMsg,
116 const rtabmap_msgs::OdomInfoConstPtr& odomInfoMsg) = 0;
119 const nav_msgs::OdometryConstPtr & odomMsg,
120 const rtabmap_msgs::UserDataConstPtr & userDataMsg,
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());
133 void tick(
const ros::Time & stamp,
double targetFrequency = 0);
140 bool subscribeUserData,
141 bool subscribeScan2d,
142 bool subscribeScan3d,
143 bool subscribeScanDesc,
144 bool subscribeOdomInfo);
149 bool subscribeOdomInfo);
154 bool subscribeUserData,
155 bool subscribeScan2d,
156 bool subscribeScan3d,
157 bool subscribeScanDesc,
158 bool subscribeOdomInfo);
163 bool subscribeUserData,
164 bool subscribeScan2d,
165 bool subscribeScan3d,
166 bool subscribeScanDesc,
167 bool subscribeOdomInfo);
172 bool subscribeUserData,
173 bool subscribeScan2d,
174 bool subscribeScan3d,
175 bool subscribeScanDesc,
176 bool subscribeOdomInfo);
177 #ifdef RTABMAP_SYNC_MULTI_RGBD
178 void setupRGBD2Callbacks(
182 bool subscribeUserData,
183 bool subscribeScan2d,
184 bool subscribeScan3d,
185 bool subscribeScanDesc,
186 bool subscribeOdomInfo);
187 void setupRGBD3Callbacks(
191 bool subscribeUserData,
192 bool subscribeScan2d,
193 bool subscribeScan3d,
194 bool subscribeScanDesc,
195 bool subscribeOdomInfo);
196 void setupRGBD4Callbacks(
200 bool subscribeUserData,
201 bool subscribeScan2d,
202 bool subscribeScan3d,
203 bool subscribeScanDesc,
204 bool subscribeOdomInfo);
205 void setupRGBD5Callbacks(
209 bool subscribeUserData,
210 bool subscribeScan2d,
211 bool subscribeScan3d,
212 bool subscribeScanDesc,
213 bool subscribeOdomInfo);
214 void setupRGBD6Callbacks(
218 bool subscribeUserData,
219 bool subscribeScan2d,
220 bool subscribeScan3d,
221 bool subscribeScanDesc,
222 bool subscribeOdomInfo);
228 bool subscribeOdomInfo);
232 bool subscribeScan2d,
233 bool subscribeScanDesc,
235 bool subscribeUserData,
236 bool subscribeOdomInfo);
240 bool subscribeUserData,
241 bool subscribeOdomInfo);
269 std::vector<message_filters::Subscriber<rtabmap_msgs::RGBDImage>*>
rgbdSubs_;
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);
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);
317 #ifdef RTABMAP_SYNC_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);
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);
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);
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);
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);
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);
367 #ifdef RTABMAP_SYNC_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);
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);
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);
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);
403 #ifdef RTABMAP_SYNC_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);
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);
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);
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);
433 #ifdef RTABMAP_SYNC_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);
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);
451 DATA_SYNCS2(sensorDataInfo, rtabmap_msgs::SensorData, rtabmap_msgs::OdomInfo);
454 DATA_SYNCS2(sensorDataOdom, nav_msgs::Odometry, rtabmap_msgs::SensorData);
455 DATA_SYNCS3(sensorDataOdomInfo, nav_msgs::Odometry, rtabmap_msgs::SensorData, rtabmap_msgs::OdomInfo);
457 #ifdef RTABMAP_SYNC_MULTI_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);
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);
472 #ifdef RTABMAP_SYNC_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);
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);
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);
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);
502 #ifdef RTABMAP_SYNC_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);
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);
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);
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);
532 #ifdef RTABMAP_SYNC_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);
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);
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);
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);
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);
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);
576 #endif //RTABMAP_SYNC_MULTI_RGBD
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);
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);
594 #ifdef RTABMAP_SYNC_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);
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);
614 DATA_SYNCS2(odomInfo, nav_msgs::Odometry, rtabmap_msgs::OdomInfo);
616 #ifdef RTABMAP_SYNC_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);