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_ros/RGBDImage.h> 49 #include <rtabmap_ros/UserData.h> 50 #include <rtabmap_ros/OdomInfo.h> 51 #include <rtabmap_ros/ScanDescriptor.h> 54 #include <boost/thread.hpp> 81 const std::string &
name);
83 const nav_msgs::OdometryConstPtr & odomMsg,
84 const rtabmap_ros::UserDataConstPtr & userDataMsg,
85 const std::vector<cv_bridge::CvImageConstPtr> & imageMsgs,
86 const std::vector<cv_bridge::CvImageConstPtr> & depthMsgs,
87 const std::vector<sensor_msgs::CameraInfo> & cameraInfoMsgs,
88 const sensor_msgs::LaserScan& scanMsg,
89 const sensor_msgs::PointCloud2& scan3dMsg,
90 const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg,
91 const std::vector<rtabmap_ros::GlobalDescriptor> & globalDescriptorMsgs = std::vector<rtabmap_ros::GlobalDescriptor>(),
92 const std::vector<std::vector<rtabmap_ros::KeyPoint> > & localKeyPoints = std::vector<std::vector<rtabmap_ros::KeyPoint> >(),
93 const std::vector<std::vector<rtabmap_ros::Point3f> > & localPoints3d = std::vector<std::vector<rtabmap_ros::Point3f> >(),
94 const std::vector<cv::Mat> & localDescriptors = std::vector<cv::Mat>()) = 0;
96 const nav_msgs::OdometryConstPtr & odomMsg,
97 const rtabmap_ros::UserDataConstPtr & userDataMsg,
100 const sensor_msgs::CameraInfo& leftCamInfoMsg,
101 const sensor_msgs::CameraInfo& rightCamInfoMsg,
102 const sensor_msgs::LaserScan& scanMsg,
103 const sensor_msgs::PointCloud2& scan3dMsg,
104 const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg,
105 const std::vector<rtabmap_ros::GlobalDescriptor> & globalDescriptorMsgs = std::vector<rtabmap_ros::GlobalDescriptor>(),
106 const std::vector<rtabmap_ros::KeyPoint> & localKeyPoints = std::vector<rtabmap_ros::KeyPoint>(),
107 const std::vector<rtabmap_ros::Point3f> & localPoints3d = std::vector<rtabmap_ros::Point3f>(),
108 const cv::Mat & localDescriptors = cv::Mat()) = 0;
110 const nav_msgs::OdometryConstPtr & odomMsg,
111 const rtabmap_ros::UserDataConstPtr & userDataMsg,
112 const sensor_msgs::LaserScan& scanMsg,
113 const sensor_msgs::PointCloud2& scan3dMsg,
114 const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg,
115 const rtabmap_ros::GlobalDescriptor & globalDescriptor = rtabmap_ros::GlobalDescriptor()) = 0;
117 const nav_msgs::OdometryConstPtr & odomMsg,
118 const rtabmap_ros::UserDataConstPtr & userDataMsg,
119 const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg) = 0;
122 const nav_msgs::OdometryConstPtr & odomMsg,
123 const rtabmap_ros::UserDataConstPtr & userDataMsg,
126 const sensor_msgs::CameraInfo & rgbCameraInfoMsg,
127 const sensor_msgs::CameraInfo & depthCameraInfoMsg,
128 const sensor_msgs::LaserScan& scanMsg,
129 const sensor_msgs::PointCloud2& scan3dMsg,
130 const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg,
131 const std::vector<rtabmap_ros::GlobalDescriptor> & globalDescriptorMsgs = std::vector<rtabmap_ros::GlobalDescriptor>(),
132 const std::vector<rtabmap_ros::KeyPoint> & localKeyPoints = std::vector<rtabmap_ros::KeyPoint>(),
133 const std::vector<rtabmap_ros::Point3f> & localPoints3d = std::vector<rtabmap_ros::Point3f>(),
134 const cv::Mat & localDescriptors = cv::Mat());
143 bool subscribeUserData,
144 bool subscribeScan2d,
145 bool subscribeScan3d,
146 bool subscribeScanDesc,
147 bool subscribeOdomInfo,
154 bool subscribeOdomInfo,
161 bool subscribeUserData,
162 bool subscribeScan2d,
163 bool subscribeScan3d,
164 bool subscribeScanDesc,
165 bool subscribeOdomInfo,
172 bool subscribeUserData,
173 bool subscribeScan2d,
174 bool subscribeScan3d,
175 bool subscribeScanDesc,
176 bool subscribeOdomInfo,
179 #ifdef RTABMAP_SYNC_MULTI_RGBD 180 void setupRGBD2Callbacks(
184 bool subscribeUserData,
185 bool subscribeScan2d,
186 bool subscribeScan3d,
187 bool subscribeScanDesc,
188 bool subscribeOdomInfo,
191 void setupRGBD3Callbacks(
195 bool subscribeUserData,
196 bool subscribeScan2d,
197 bool subscribeScan3d,
198 bool subscribeScanDesc,
199 bool subscribeOdomInfo,
202 void setupRGBD4Callbacks(
206 bool subscribeUserData,
207 bool subscribeScan2d,
208 bool subscribeScan3d,
209 bool subscribeScanDesc,
210 bool subscribeOdomInfo,
213 void setupRGBD5Callbacks(
217 bool subscribeUserData,
218 bool subscribeScan2d,
219 bool subscribeScan3d,
220 bool subscribeScanDesc,
221 bool subscribeOdomInfo,
224 void setupRGBD6Callbacks(
228 bool subscribeUserData,
229 bool subscribeScan2d,
230 bool subscribeScan3d,
231 bool subscribeScanDesc,
232 bool subscribeOdomInfo,
239 bool subscribeScan2d,
240 bool subscribeScanDesc,
242 bool subscribeUserData,
243 bool subscribeOdomInfo,
249 bool subscribeUserData,
250 bool subscribeOdomInfo,
280 std::vector<message_filters::Subscriber<rtabmap_ros::RGBDImage>*>
rgbdSubs_;
320 #ifdef RTABMAP_SYNC_USER_DATA 370 #ifdef RTABMAP_SYNC_USER_DATA 377 DATA_SYNCS5(rgbDataScan2dInfo, rtabmap_ros::UserData,
sensor_msgs::Image, sensor_msgs::CameraInfo, sensor_msgs::LaserScan, rtabmap_ros::OdomInfo);
378 DATA_SYNCS5(rgbDataScan3dInfo, rtabmap_ros::UserData,
sensor_msgs::Image, sensor_msgs::CameraInfo, sensor_msgs::PointCloud2, rtabmap_ros::OdomInfo);
379 DATA_SYNCS5(rgbDataScanDescInfo, rtabmap_ros::UserData,
sensor_msgs::Image, sensor_msgs::CameraInfo, rtabmap_ros::ScanDescriptor, rtabmap_ros::OdomInfo);
393 void rgbdCallback(
const rtabmap_ros::RGBDImageConstPtr&);
394 DATA_SYNCS2(rgbdScan2d, rtabmap_ros::RGBDImage, sensor_msgs::LaserScan);
395 DATA_SYNCS2(rgbdScan3d, rtabmap_ros::RGBDImage, sensor_msgs::PointCloud2)
406 #ifdef RTABMAP_SYNC_USER_DATA 408 DATA_SYNCS2(rgbdData, rtabmap_ros::UserData, rtabmap_ros::RGBDImage);
409 DATA_SYNCS3(rgbdDataScan2d, rtabmap_ros::UserData, rtabmap_ros::RGBDImage, sensor_msgs::LaserScan);
410 DATA_SYNCS3(rgbdDataScan3d, rtabmap_ros::UserData, rtabmap_ros::RGBDImage, sensor_msgs::PointCloud2);
411 DATA_SYNCS3(rgbdDataScanDesc, rtabmap_ros::UserData, rtabmap_ros::RGBDImage, rtabmap_ros::ScanDescriptor);
412 DATA_SYNCS3(rgbdDataInfo, rtabmap_ros::UserData, rtabmap_ros::RGBDImage, rtabmap_ros::OdomInfo);
422 #ifdef RTABMAP_SYNC_MULTI_RGBD 424 DATA_SYNCS2(rgbd2, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage);
425 DATA_SYNCS3(rgbd2Scan2d, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, sensor_msgs::LaserScan);
426 DATA_SYNCS3(rgbd2Scan3d, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, sensor_msgs::PointCloud2);
427 DATA_SYNCS3(rgbd2ScanDesc, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, rtabmap_ros::ScanDescriptor);
428 DATA_SYNCS3(rgbd2Info, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, rtabmap_ros::OdomInfo);
437 #ifdef RTABMAP_SYNC_USER_DATA 439 DATA_SYNCS3(rgbd2Data, rtabmap_ros::UserData, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage);
440 DATA_SYNCS4(rgbd2DataScan2d, rtabmap_ros::UserData, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, sensor_msgs::LaserScan);
441 DATA_SYNCS4(rgbd2DataScan3d, rtabmap_ros::UserData, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, sensor_msgs::PointCloud2);
442 DATA_SYNCS4(rgbd2DataScanDesc, rtabmap_ros::UserData, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, rtabmap_ros::ScanDescriptor);
443 DATA_SYNCS4(rgbd2DataInfo, rtabmap_ros::UserData, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, rtabmap_ros::OdomInfo);
447 DATA_SYNCS5(rgbd2OdomDataScan2d,
nav_msgs::Odometry, rtabmap_ros::UserData, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, sensor_msgs::LaserScan);
448 DATA_SYNCS5(rgbd2OdomDataScan3d,
nav_msgs::Odometry, rtabmap_ros::UserData, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, sensor_msgs::PointCloud2);
449 DATA_SYNCS5(rgbd2OdomDataScanDesc,
nav_msgs::Odometry, rtabmap_ros::UserData, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, rtabmap_ros::ScanDescriptor);
450 DATA_SYNCS5(rgbd2OdomDataInfo,
nav_msgs::Odometry, rtabmap_ros::UserData, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, rtabmap_ros::OdomInfo);
454 DATA_SYNCS3(rgbd3, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage);
455 DATA_SYNCS4(rgbd3Scan2d, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, sensor_msgs::LaserScan);
456 DATA_SYNCS4(rgbd3Scan3d, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, sensor_msgs::PointCloud2);
457 DATA_SYNCS4(rgbd3ScanDesc, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, rtabmap_ros::ScanDescriptor);
458 DATA_SYNCS4(rgbd3Info, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, rtabmap_ros::OdomInfo);
462 DATA_SYNCS5(rgbd3OdomScan2d,
nav_msgs::Odometry, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, sensor_msgs::LaserScan);
463 DATA_SYNCS5(rgbd3OdomScan3d,
nav_msgs::Odometry, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, sensor_msgs::PointCloud2);
464 DATA_SYNCS5(rgbd3OdomScanDesc,
nav_msgs::Odometry, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, rtabmap_ros::ScanDescriptor);
465 DATA_SYNCS5(rgbd3OdomInfo,
nav_msgs::Odometry, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, rtabmap_ros::OdomInfo);
467 #ifdef RTABMAP_SYNC_USER_DATA 469 DATA_SYNCS4(rgbd3Data, rtabmap_ros::UserData, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage);
470 DATA_SYNCS5(rgbd3DataScan2d, rtabmap_ros::UserData, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, sensor_msgs::LaserScan);
471 DATA_SYNCS5(rgbd3DataScan3d, rtabmap_ros::UserData, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, sensor_msgs::PointCloud2);
472 DATA_SYNCS5(rgbd3DataScanDesc, rtabmap_ros::UserData, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, rtabmap_ros::ScanDescriptor);
473 DATA_SYNCS5(rgbd3DataInfo, rtabmap_ros::UserData, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, rtabmap_ros::OdomInfo);
476 DATA_SYNCS5(rgbd3OdomData,
nav_msgs::Odometry, rtabmap_ros::UserData, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage);
477 DATA_SYNCS6(rgbd3OdomDataScan2d,
nav_msgs::Odometry, rtabmap_ros::UserData, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, sensor_msgs::LaserScan);
478 DATA_SYNCS6(rgbd3OdomDataScan3d,
nav_msgs::Odometry, rtabmap_ros::UserData, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, sensor_msgs::PointCloud2);
479 DATA_SYNCS6(rgbd3OdomDataScanDesc,
nav_msgs::Odometry, rtabmap_ros::UserData, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, rtabmap_ros::ScanDescriptor);
480 DATA_SYNCS6(rgbd3OdomDataInfo,
nav_msgs::Odometry, rtabmap_ros::UserData, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, rtabmap_ros::OdomInfo);
484 DATA_SYNCS4(rgbd4, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage);
485 DATA_SYNCS5(rgbd4Scan2d, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, sensor_msgs::LaserScan);
486 DATA_SYNCS5(rgbd4Scan3d, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, sensor_msgs::PointCloud2);
487 DATA_SYNCS5(rgbd4ScanDesc, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, rtabmap_ros::ScanDescriptor);
488 DATA_SYNCS5(rgbd4Info, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, rtabmap_ros::OdomInfo);
492 DATA_SYNCS6(rgbd4OdomScan2d,
nav_msgs::Odometry, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, sensor_msgs::LaserScan);
493 DATA_SYNCS6(rgbd4OdomScan3d,
nav_msgs::Odometry, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, sensor_msgs::PointCloud2);
494 DATA_SYNCS6(rgbd4OdomScanDesc,
nav_msgs::Odometry, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, rtabmap_ros::ScanDescriptor);
495 DATA_SYNCS6(rgbd4OdomInfo,
nav_msgs::Odometry, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, rtabmap_ros::OdomInfo);
497 #ifdef RTABMAP_SYNC_USER_DATA 499 DATA_SYNCS5(rgbd4Data, rtabmap_ros::UserData, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage);
500 DATA_SYNCS6(rgbd4DataScan2d, rtabmap_ros::UserData, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, sensor_msgs::LaserScan);
501 DATA_SYNCS6(rgbd4DataScan3d, rtabmap_ros::UserData, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, sensor_msgs::PointCloud2);
502 DATA_SYNCS6(rgbd4DataScanDesc, rtabmap_ros::UserData, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, rtabmap_ros::ScanDescriptor);
503 DATA_SYNCS6(rgbd4DataInfo, rtabmap_ros::UserData, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, rtabmap_ros::OdomInfo);
506 DATA_SYNCS6(rgbd4OdomData,
nav_msgs::Odometry, rtabmap_ros::UserData, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage);
507 DATA_SYNCS7(rgbd4OdomDataScan2d,
nav_msgs::Odometry, rtabmap_ros::UserData, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, sensor_msgs::LaserScan);
508 DATA_SYNCS7(rgbd4OdomDataScan3d,
nav_msgs::Odometry, rtabmap_ros::UserData, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, sensor_msgs::PointCloud2);
509 DATA_SYNCS7(rgbd4OdomDataScanDesc,
nav_msgs::Odometry, rtabmap_ros::UserData, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, rtabmap_ros::ScanDescriptor);
510 DATA_SYNCS7(rgbd4OdomDataInfo,
nav_msgs::Odometry, rtabmap_ros::UserData, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, rtabmap_ros::OdomInfo);
514 DATA_SYNCS5(rgbd5, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage);
515 DATA_SYNCS6(rgbd5Scan2d, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, sensor_msgs::LaserScan);
516 DATA_SYNCS6(rgbd5Scan3d, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, sensor_msgs::PointCloud2);
517 DATA_SYNCS6(rgbd5ScanDesc, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, rtabmap_ros::ScanDescriptor);
518 DATA_SYNCS6(rgbd5Info, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, rtabmap_ros::OdomInfo);
521 DATA_SYNCS6(rgbd5Odom,
nav_msgs::Odometry, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage);
522 DATA_SYNCS7(rgbd5OdomScan2d,
nav_msgs::Odometry, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, sensor_msgs::LaserScan);
523 DATA_SYNCS7(rgbd5OdomScan3d,
nav_msgs::Odometry, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, sensor_msgs::PointCloud2);
524 DATA_SYNCS7(rgbd5OdomScanDesc,
nav_msgs::Odometry, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, rtabmap_ros::ScanDescriptor);
525 DATA_SYNCS7(rgbd5OdomInfo,
nav_msgs::Odometry, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, rtabmap_ros::OdomInfo);
528 DATA_SYNCS6(rgbd6, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage);
529 DATA_SYNCS7(rgbd6Scan2d, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, sensor_msgs::LaserScan);
530 DATA_SYNCS7(rgbd6Scan3d, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, sensor_msgs::PointCloud2);
531 DATA_SYNCS7(rgbd6ScanDesc, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, rtabmap_ros::ScanDescriptor);
532 DATA_SYNCS7(rgbd6Info, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, rtabmap_ros::OdomInfo);
535 DATA_SYNCS7(rgbd6Odom,
nav_msgs::Odometry, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage);
536 DATA_SYNCS8(rgbd6OdomScan2d,
nav_msgs::Odometry, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, sensor_msgs::LaserScan);
537 DATA_SYNCS8(rgbd6OdomScan3d,
nav_msgs::Odometry, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, sensor_msgs::PointCloud2);
538 DATA_SYNCS8(rgbd6OdomScanDesc,
nav_msgs::Odometry, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, rtabmap_ros::ScanDescriptor);
539 DATA_SYNCS8(rgbd6OdomInfo,
nav_msgs::Odometry, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, rtabmap_ros::RGBDImage, rtabmap_ros::OdomInfo);
541 #endif //RTABMAP_SYNC_MULTI_RGBD 547 DATA_SYNCS2(scan2dInfo, sensor_msgs::LaserScan, rtabmap_ros::OdomInfo);
548 DATA_SYNCS2(scan3dInfo, sensor_msgs::PointCloud2, rtabmap_ros::OdomInfo);
549 DATA_SYNCS2(scanDescInfo, rtabmap_ros::ScanDescriptor, rtabmap_ros::OdomInfo);
559 #ifdef RTABMAP_SYNC_USER_DATA 561 DATA_SYNCS2(dataScan2d, rtabmap_ros::UserData, sensor_msgs::LaserScan);
562 DATA_SYNCS2(dataScan3d, rtabmap_ros::UserData, sensor_msgs::PointCloud2);
563 DATA_SYNCS2(dataScanDesc, rtabmap_ros::UserData, rtabmap_ros::ScanDescriptor);
564 DATA_SYNCS3(dataScan2dInfo, rtabmap_ros::UserData, sensor_msgs::LaserScan, rtabmap_ros::OdomInfo);
565 DATA_SYNCS3(dataScan3dInfo, rtabmap_ros::UserData, sensor_msgs::PointCloud2, rtabmap_ros::OdomInfo);
566 DATA_SYNCS3(dataScanDescInfo, rtabmap_ros::UserData, rtabmap_ros::ScanDescriptor, rtabmap_ros::OdomInfo);
581 #ifdef RTABMAP_SYNC_USER_DATA
void rgbdCallback(const rtabmap_ros::RGBDImageConstPtr &)
CommonDataSubscriber(bool gui)
void scanDescCallback(const rtabmap_ros::ScanDescriptorConstPtr &)
DATA_SYNCS6(depthOdomScan2dInfo, nav_msgs::Odometry, sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo, sensor_msgs::LaserScan, rtabmap_ros::OdomInfo)
virtual ~CommonDataSubscriber()
bool isSubscribedToRGB() const
bool isSubscribedToOdomInfo() const
bool isSubscribedToScan2d() const
virtual void commonDepthCallback(const nav_msgs::OdometryConstPtr &odomMsg, const rtabmap_ros::UserDataConstPtr &userDataMsg, const std::vector< cv_bridge::CvImageConstPtr > &imageMsgs, const std::vector< cv_bridge::CvImageConstPtr > &depthMsgs, const std::vector< sensor_msgs::CameraInfo > &cameraInfoMsgs, const sensor_msgs::LaserScan &scanMsg, const sensor_msgs::PointCloud2 &scan3dMsg, const rtabmap_ros::OdomInfoConstPtr &odomInfoMsg, const std::vector< rtabmap_ros::GlobalDescriptor > &globalDescriptorMsgs=std::vector< rtabmap_ros::GlobalDescriptor >(), const std::vector< std::vector< rtabmap_ros::KeyPoint > > &localKeyPoints=std::vector< std::vector< rtabmap_ros::KeyPoint > >(), const std::vector< std::vector< rtabmap_ros::Point3f > > &localPoints3d=std::vector< std::vector< rtabmap_ros::Point3f > >(), const std::vector< cv::Mat > &localDescriptors=std::vector< cv::Mat >())=0
message_filters::Subscriber< sensor_msgs::CameraInfo > cameraInfoLeft_
message_filters::Subscriber< rtabmap_ros::UserData > userDataSub_
bool subscribedToOdomInfo_
message_filters::Subscriber< rtabmap_ros::OdomInfo > odomInfoSub_
bool isSubscribedToDepth() const
DATA_SYNCS4(depthScan2d, sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo, sensor_msgs::LaserScan)
virtual void commonLaserScanCallback(const nav_msgs::OdometryConstPtr &odomMsg, const rtabmap_ros::UserDataConstPtr &userDataMsg, const sensor_msgs::LaserScan &scanMsg, const sensor_msgs::PointCloud2 &scan3dMsg, const rtabmap_ros::OdomInfoConstPtr &odomInfoMsg, const rtabmap_ros::GlobalDescriptor &globalDescriptor=rtabmap_ros::GlobalDescriptor())=0
void setupRGBCallbacks(ros::NodeHandle &nh, ros::NodeHandle &pnh, bool subscribeOdom, bool subscribeUserData, bool subscribeScan2d, bool subscribeScan3d, bool subscribeScanDesc, bool subscribeOdomInfo, int queueSize, bool approxSync)
ros::Subscriber scanDescSubOnly_
DATA_SYNCS2(rgb, sensor_msgs::Image, sensor_msgs::CameraInfo)
void setupScanCallbacks(ros::NodeHandle &nh, ros::NodeHandle &pnh, bool subscribeScan2d, bool subscribeScanDesc, bool subscribeOdom, bool subscribeUserData, bool subscribeOdomInfo, int queueSize, bool approxSync)
image_transport::SubscriberFilter imageDepthSub_
bool isSubscribedToRGBD() const
void commonSingleDepthCallback(const nav_msgs::OdometryConstPtr &odomMsg, const rtabmap_ros::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_ros::OdomInfoConstPtr &odomInfoMsg, const std::vector< rtabmap_ros::GlobalDescriptor > &globalDescriptorMsgs=std::vector< rtabmap_ros::GlobalDescriptor >(), const std::vector< rtabmap_ros::KeyPoint > &localKeyPoints=std::vector< rtabmap_ros::KeyPoint >(), const std::vector< rtabmap_ros::Point3f > &localPoints3d=std::vector< rtabmap_ros::Point3f >(), const cv::Mat &localDescriptors=cv::Mat())
void setupOdomCallbacks(ros::NodeHandle &nh, ros::NodeHandle &pnh, bool subscribeUserData, bool subscribeOdomInfo, int queueSize, bool approxSync)
void setupCallbacks(ros::NodeHandle &nh, ros::NodeHandle &pnh, const std::string &name)
void scan3dCallback(const sensor_msgs::PointCloud2ConstPtr &)
bool isSubscribedToStereo() const
bool subscribedToScanDescriptor_
bool isDataSubscribed() const
void scan2dCallback(const sensor_msgs::LaserScanConstPtr &)
virtual void commonStereoCallback(const nav_msgs::OdometryConstPtr &odomMsg, const rtabmap_ros::UserDataConstPtr &userDataMsg, const cv_bridge::CvImageConstPtr &leftImageMsg, const cv_bridge::CvImageConstPtr &rightImageMsg, const sensor_msgs::CameraInfo &leftCamInfoMsg, const sensor_msgs::CameraInfo &rightCamInfoMsg, 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< rtabmap_ros::KeyPoint > &localKeyPoints=std::vector< rtabmap_ros::KeyPoint >(), const std::vector< rtabmap_ros::Point3f > &localPoints3d=std::vector< rtabmap_ros::Point3f >(), const cv::Mat &localDescriptors=cv::Mat())=0
image_transport::SubscriberFilter imageSub_
message_filters::Subscriber< sensor_msgs::LaserScan > scanSub_
message_filters::Subscriber< rtabmap_ros::ScanDescriptor > scanDescSub_
bool isApproxSync() const
DATA_SYNCS3(depth, sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo)
message_filters::Subscriber< nav_msgs::Odometry > odomSub_
#define DATA_SYNCS7(PREFIX, MSG0, MSG1, MSG2, MSG3, MSG4, MSG5, MSG6)
boost::thread * warningThread_
bool isSubscribedToOdom() const
virtual void commonOdomCallback(const nav_msgs::OdometryConstPtr &odomMsg, const rtabmap_ros::UserDataConstPtr &userDataMsg, const rtabmap_ros::OdomInfoConstPtr &odomInfoMsg)=0
message_filters::Subscriber< sensor_msgs::PointCloud2 > scan3dSub_
#define DATA_SYNCS8(PREFIX, MSG0, MSG1, MSG2, MSG3, MSG4, MSG5, MSG6, MSG7)
image_transport::SubscriberFilter imageRectLeft_
const std::string & name() const
ros::Subscriber scan3dSubOnly_
image_transport::SubscriberFilter imageRectRight_
ros::Subscriber scan2dSubOnly_
bool isSubscribedToScan3d() const
void setupRGBDCallbacks(ros::NodeHandle &nh, ros::NodeHandle &pnh, bool subscribeOdom, bool subscribeUserData, bool subscribeScan2d, bool subscribeScan3d, bool subscribeScanDesc, bool subscribeOdomInfo, int queueSize, bool approxSync)
message_filters::Subscriber< sensor_msgs::CameraInfo > cameraInfoSub_
std::string subscribedTopicsMsg_
void setupStereoCallbacks(ros::NodeHandle &nh, ros::NodeHandle &pnh, bool subscribeOdom, bool subscribeOdomInfo, int queueSize, bool approxSync)
ros::Subscriber odomSubOnly_
std::vector< message_filters::Subscriber< rtabmap_ros::RGBDImage > * > rgbdSubs_
DATA_SYNCS5(depthScan2dInfo, sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo, sensor_msgs::LaserScan, rtabmap_ros::OdomInfo)
void odomCallback(const nav_msgs::OdometryConstPtr &)
void setupDepthCallbacks(ros::NodeHandle &nh, ros::NodeHandle &pnh, bool subscribeOdom, bool subscribeUserData, bool subscribeScan2d, bool subscribeScan3d, bool subscribeScanDesc, bool subscribeOdomInfo, int queueSize, bool approxSync)
message_filters::Subscriber< sensor_msgs::CameraInfo > cameraInfoRight_