36 #define IMAGE_CONVERSION() \
37 UASSERT(!imagesMsg->rgbd_images.empty()); \
38 std::vector<cv_bridge::CvImageConstPtr> imageMsgs(imagesMsg->rgbd_images.size()); \
39 std::vector<cv_bridge::CvImageConstPtr> depthMsgs(imagesMsg->rgbd_images.size()); \
40 std::vector<sensor_msgs::CameraInfo> cameraInfoMsgs; \
41 std::vector<sensor_msgs::CameraInfo> depthCameraInfoMsgs; \
42 std::vector<rtabmap_msgs::GlobalDescriptor> globalDescriptorMsgs; \
43 std::vector<std::vector<rtabmap_msgs::KeyPoint> > localKeyPoints; \
44 std::vector<std::vector<rtabmap_msgs::Point3f> > localPoints3d; \
45 std::vector<cv::Mat> localDescriptors; \
46 for(size_t i=0; i<imageMsgs.size(); ++i) \
48 rtabmap_conversions::toCvShare(imagesMsg->rgbd_images[i], imagesMsg, imageMsgs[i], depthMsgs[i]); \
49 cameraInfoMsgs.push_back(imagesMsg->rgbd_images[i].rgb_camera_info); \
50 depthCameraInfoMsgs.push_back(imagesMsg->rgbd_images[i].depth_camera_info); \
51 if(!imagesMsg->rgbd_images[i].global_descriptor.data.empty()) \
52 globalDescriptorMsgs.push_back(imagesMsg->rgbd_images[i].global_descriptor); \
53 localKeyPoints.push_back(imagesMsg->rgbd_images[i].key_points); \
54 localPoints3d.push_back(imagesMsg->rgbd_images[i].points); \
55 localDescriptors.push_back(rtabmap::uncompressData(imagesMsg->rgbd_images[i].descriptors)); \
57 if(!depthMsgs[0].get()) \
62 const rtabmap_msgs::RGBDImagesConstPtr& imagesMsg)
66 nav_msgs::OdometryConstPtr odomMsg;
67 rtabmap_msgs::UserDataConstPtr userDataMsg;
68 sensor_msgs::LaserScan scanMsg;
69 sensor_msgs::PointCloud2 scan3dMsg;
70 rtabmap_msgs::OdomInfoConstPtr odomInfoMsg;
71 commonMultiCameraCallback(odomMsg, userDataMsg, imageMsgs, depthMsgs, cameraInfoMsgs, depthCameraInfoMsgs, scanMsg, scan3dMsg, odomInfoMsg, globalDescriptorMsgs, localKeyPoints, localPoints3d, localDescriptors);
73 void CommonDataSubscriber::rgbdXScan2dCallback(
74 const rtabmap_msgs::RGBDImagesConstPtr& imagesMsg,
75 const sensor_msgs::LaserScanConstPtr& scanMsg)
79 nav_msgs::OdometryConstPtr odomMsg;
80 rtabmap_msgs::UserDataConstPtr userDataMsg;
81 sensor_msgs::PointCloud2 scan3dMsg;
82 rtabmap_msgs::OdomInfoConstPtr odomInfoMsg;
83 commonMultiCameraCallback(odomMsg, userDataMsg, imageMsgs, depthMsgs, cameraInfoMsgs, depthCameraInfoMsgs, *scanMsg, scan3dMsg, odomInfoMsg, globalDescriptorMsgs, localKeyPoints, localPoints3d, localDescriptors);
85 void CommonDataSubscriber::rgbdXScan3dCallback(
86 const rtabmap_msgs::RGBDImagesConstPtr& imagesMsg,
87 const sensor_msgs::PointCloud2ConstPtr& scan3dMsg)
91 nav_msgs::OdometryConstPtr odomMsg;
92 rtabmap_msgs::UserDataConstPtr userDataMsg;
93 sensor_msgs::LaserScan scanMsg;
94 rtabmap_msgs::OdomInfoConstPtr odomInfoMsg;
95 commonMultiCameraCallback(odomMsg, userDataMsg, imageMsgs, depthMsgs, cameraInfoMsgs, depthCameraInfoMsgs, scanMsg, *scan3dMsg, odomInfoMsg, globalDescriptorMsgs, localKeyPoints, localPoints3d, localDescriptors);
97 void CommonDataSubscriber::rgbdXScanDescCallback(
98 const rtabmap_msgs::RGBDImagesConstPtr& imagesMsg,
99 const rtabmap_msgs::ScanDescriptorConstPtr& scanDescMsg)
103 nav_msgs::OdometryConstPtr odomMsg;
104 rtabmap_msgs::UserDataConstPtr userDataMsg;
105 rtabmap_msgs::OdomInfoConstPtr odomInfoMsg;
106 if(!scanDescMsg->global_descriptor.data.empty())
108 globalDescriptorMsgs.push_back(scanDescMsg->global_descriptor);
110 commonMultiCameraCallback(odomMsg, userDataMsg, imageMsgs, depthMsgs, cameraInfoMsgs, depthCameraInfoMsgs, scanDescMsg->scan, scanDescMsg->scan_cloud, odomInfoMsg, globalDescriptorMsgs, localKeyPoints, localPoints3d, localDescriptors);
112 void CommonDataSubscriber::rgbdXInfoCallback(
113 const rtabmap_msgs::RGBDImagesConstPtr& imagesMsg,
114 const rtabmap_msgs::OdomInfoConstPtr& odomInfoMsg)
118 nav_msgs::OdometryConstPtr odomMsg;
119 rtabmap_msgs::UserDataConstPtr userDataMsg;
120 sensor_msgs::LaserScan scanMsg;
121 sensor_msgs::PointCloud2 scan3dMsg;
122 commonMultiCameraCallback(odomMsg, userDataMsg, imageMsgs, depthMsgs, cameraInfoMsgs, depthCameraInfoMsgs, scanMsg, scan3dMsg, odomInfoMsg, globalDescriptorMsgs, localKeyPoints, localPoints3d, localDescriptors);
125 void CommonDataSubscriber::rgbdXOdomCallback(
126 const nav_msgs::OdometryConstPtr & odomMsg,
127 const rtabmap_msgs::RGBDImagesConstPtr& imagesMsg)
131 rtabmap_msgs::UserDataConstPtr userDataMsg;
132 sensor_msgs::LaserScan scanMsg;
133 sensor_msgs::PointCloud2 scan3dMsg;
134 rtabmap_msgs::OdomInfoConstPtr odomInfoMsg;
135 commonMultiCameraCallback(odomMsg, userDataMsg, imageMsgs, depthMsgs, cameraInfoMsgs, depthCameraInfoMsgs, scanMsg, scan3dMsg, odomInfoMsg, globalDescriptorMsgs, localKeyPoints, localPoints3d, localDescriptors);
137 void CommonDataSubscriber::rgbdXOdomScan2dCallback(
138 const nav_msgs::OdometryConstPtr & odomMsg,
139 const rtabmap_msgs::RGBDImagesConstPtr& imagesMsg,
140 const sensor_msgs::LaserScanConstPtr& scanMsg)
144 rtabmap_msgs::UserDataConstPtr userDataMsg;
145 sensor_msgs::PointCloud2 scan3dMsg;
146 rtabmap_msgs::OdomInfoConstPtr odomInfoMsg;
147 commonMultiCameraCallback(odomMsg, userDataMsg, imageMsgs, depthMsgs, cameraInfoMsgs, depthCameraInfoMsgs, *scanMsg, scan3dMsg, odomInfoMsg, globalDescriptorMsgs, localKeyPoints, localPoints3d, localDescriptors);
149 void CommonDataSubscriber::rgbdXOdomScan3dCallback(
150 const nav_msgs::OdometryConstPtr & odomMsg,
151 const rtabmap_msgs::RGBDImagesConstPtr& imagesMsg,
152 const sensor_msgs::PointCloud2ConstPtr& scan3dMsg)
156 rtabmap_msgs::UserDataConstPtr userDataMsg;
157 sensor_msgs::LaserScan scanMsg;
158 rtabmap_msgs::OdomInfoConstPtr odomInfoMsg;
159 commonMultiCameraCallback(odomMsg, userDataMsg, imageMsgs, depthMsgs, cameraInfoMsgs, depthCameraInfoMsgs, scanMsg, *scan3dMsg, odomInfoMsg, globalDescriptorMsgs, localKeyPoints, localPoints3d, localDescriptors);
161 void CommonDataSubscriber::rgbdXOdomScanDescCallback(
162 const nav_msgs::OdometryConstPtr & odomMsg,
163 const rtabmap_msgs::RGBDImagesConstPtr& imagesMsg,
164 const rtabmap_msgs::ScanDescriptorConstPtr& scanDescMsg)
168 rtabmap_msgs::UserDataConstPtr userDataMsg;
169 rtabmap_msgs::OdomInfoConstPtr odomInfoMsg;
170 if(!scanDescMsg->global_descriptor.data.empty())
172 globalDescriptorMsgs.push_back(scanDescMsg->global_descriptor);
174 commonMultiCameraCallback(odomMsg, userDataMsg, imageMsgs, depthMsgs, cameraInfoMsgs, depthCameraInfoMsgs, scanDescMsg->scan, scanDescMsg->scan_cloud, odomInfoMsg, globalDescriptorMsgs, localKeyPoints, localPoints3d, localDescriptors);
176 void CommonDataSubscriber::rgbdXOdomInfoCallback(
177 const nav_msgs::OdometryConstPtr & odomMsg,
178 const rtabmap_msgs::RGBDImagesConstPtr& imagesMsg,
179 const rtabmap_msgs::OdomInfoConstPtr& odomInfoMsg)
183 rtabmap_msgs::UserDataConstPtr userDataMsg;
184 sensor_msgs::LaserScan scanMsg;
185 sensor_msgs::PointCloud2 scan3dMsg;
186 commonMultiCameraCallback(odomMsg, userDataMsg, imageMsgs, depthMsgs, cameraInfoMsgs, depthCameraInfoMsgs, scanMsg, scan3dMsg, odomInfoMsg, globalDescriptorMsgs, localKeyPoints, localPoints3d, localDescriptors);
189 #ifdef RTABMAP_SYNC_USER_DATA
191 void CommonDataSubscriber::rgbdXDataCallback(
192 const rtabmap_msgs::UserDataConstPtr& userDataMsg,
193 const rtabmap_msgs::RGBDImagesConstPtr& imagesMsg)
197 nav_msgs::OdometryConstPtr odomMsg;
198 sensor_msgs::LaserScan scanMsg;
199 sensor_msgs::PointCloud2 scan3dMsg;
200 rtabmap_msgs::OdomInfoConstPtr odomInfoMsg;
201 commonMultiCameraCallback(odomMsg, userDataMsg, imageMsgs, depthMsgs, cameraInfoMsgs, depthCameraInfoMsgs, scanMsg, scan3dMsg, odomInfoMsg, globalDescriptorMsgs, localKeyPoints, localPoints3d, localDescriptors);
203 void CommonDataSubscriber::rgbdXDataScan2dCallback(
204 const rtabmap_msgs::UserDataConstPtr& userDataMsg,
205 const rtabmap_msgs::RGBDImagesConstPtr& imagesMsg,
206 const sensor_msgs::LaserScanConstPtr& scanMsg)
210 nav_msgs::OdometryConstPtr odomMsg;
211 sensor_msgs::PointCloud2 scan3dMsg;
212 rtabmap_msgs::OdomInfoConstPtr odomInfoMsg;
213 commonMultiCameraCallback(odomMsg, userDataMsg, imageMsgs, depthMsgs, cameraInfoMsgs, depthCameraInfoMsgs, *scanMsg, scan3dMsg, odomInfoMsg, globalDescriptorMsgs, localKeyPoints, localPoints3d, localDescriptors);
215 void CommonDataSubscriber::rgbdXDataScan3dCallback(
216 const rtabmap_msgs::UserDataConstPtr& userDataMsg,
217 const rtabmap_msgs::RGBDImagesConstPtr& imagesMsg,
218 const sensor_msgs::PointCloud2ConstPtr& scan3dMsg)
222 nav_msgs::OdometryConstPtr odomMsg;
223 sensor_msgs::LaserScan scanMsg;
224 rtabmap_msgs::OdomInfoConstPtr odomInfoMsg;
225 commonMultiCameraCallback(odomMsg, userDataMsg, imageMsgs, depthMsgs, cameraInfoMsgs, depthCameraInfoMsgs, scanMsg, *scan3dMsg, odomInfoMsg, globalDescriptorMsgs, localKeyPoints, localPoints3d, localDescriptors);
227 void CommonDataSubscriber::rgbdXDataScanDescCallback(
228 const rtabmap_msgs::UserDataConstPtr& userDataMsg,
229 const rtabmap_msgs::RGBDImagesConstPtr& imagesMsg,
230 const rtabmap_msgs::ScanDescriptorConstPtr& scanDescMsg)
234 nav_msgs::OdometryConstPtr odomMsg;
235 rtabmap_msgs::OdomInfoConstPtr odomInfoMsg;
236 if(!scanDescMsg->global_descriptor.data.empty())
238 globalDescriptorMsgs.push_back(scanDescMsg->global_descriptor);
240 commonMultiCameraCallback(odomMsg, userDataMsg, imageMsgs, depthMsgs, cameraInfoMsgs, depthCameraInfoMsgs, scanDescMsg->scan, scanDescMsg->scan_cloud, odomInfoMsg, globalDescriptorMsgs, localKeyPoints, localPoints3d, localDescriptors);
242 void CommonDataSubscriber::rgbdXDataInfoCallback(
243 const rtabmap_msgs::UserDataConstPtr& userDataMsg,
244 const rtabmap_msgs::RGBDImagesConstPtr& imagesMsg,
245 const rtabmap_msgs::OdomInfoConstPtr& odomInfoMsg)
249 nav_msgs::OdometryConstPtr odomMsg;
250 sensor_msgs::LaserScan scanMsg;
251 sensor_msgs::PointCloud2 scan3dMsg;
252 commonMultiCameraCallback(odomMsg, userDataMsg, imageMsgs, depthMsgs, cameraInfoMsgs, depthCameraInfoMsgs, scanMsg, scan3dMsg, odomInfoMsg, globalDescriptorMsgs, localKeyPoints, localPoints3d, localDescriptors);
256 void CommonDataSubscriber::rgbdXOdomDataCallback(
257 const nav_msgs::OdometryConstPtr& odomMsg,
258 const rtabmap_msgs::UserDataConstPtr& userDataMsg,
259 const rtabmap_msgs::RGBDImagesConstPtr& imagesMsg)
263 sensor_msgs::LaserScan scanMsg;
264 sensor_msgs::PointCloud2 scan3dMsg;
265 rtabmap_msgs::OdomInfoConstPtr odomInfoMsg;
266 commonMultiCameraCallback(odomMsg, userDataMsg, imageMsgs, depthMsgs, cameraInfoMsgs, depthCameraInfoMsgs, scanMsg, scan3dMsg, odomInfoMsg, globalDescriptorMsgs, localKeyPoints, localPoints3d, localDescriptors);
268 void CommonDataSubscriber::rgbdXOdomDataScan2dCallback(
269 const nav_msgs::OdometryConstPtr& odomMsg,
270 const rtabmap_msgs::UserDataConstPtr& userDataMsg,
271 const rtabmap_msgs::RGBDImagesConstPtr& imagesMsg,
272 const sensor_msgs::LaserScanConstPtr& scanMsg)
276 sensor_msgs::PointCloud2 scan3dMsg;
277 rtabmap_msgs::OdomInfoConstPtr odomInfoMsg;
278 commonMultiCameraCallback(odomMsg, userDataMsg, imageMsgs, depthMsgs, cameraInfoMsgs, depthCameraInfoMsgs, *scanMsg, scan3dMsg, odomInfoMsg, globalDescriptorMsgs, localKeyPoints, localPoints3d, localDescriptors);
280 void CommonDataSubscriber::rgbdXOdomDataScan3dCallback(
281 const nav_msgs::OdometryConstPtr& odomMsg,
282 const rtabmap_msgs::UserDataConstPtr& userDataMsg,
283 const rtabmap_msgs::RGBDImagesConstPtr& imagesMsg,
284 const sensor_msgs::PointCloud2ConstPtr& scan3dMsg)
288 sensor_msgs::LaserScan scanMsg;
289 rtabmap_msgs::OdomInfoConstPtr odomInfoMsg;
290 commonMultiCameraCallback(odomMsg, userDataMsg, imageMsgs, depthMsgs, cameraInfoMsgs, depthCameraInfoMsgs, scanMsg, *scan3dMsg, odomInfoMsg, globalDescriptorMsgs, localKeyPoints, localPoints3d, localDescriptors);
292 void CommonDataSubscriber::rgbdXOdomDataScanDescCallback(
293 const nav_msgs::OdometryConstPtr& odomMsg,
294 const rtabmap_msgs::UserDataConstPtr& userDataMsg,
295 const rtabmap_msgs::RGBDImagesConstPtr& imagesMsg,
296 const rtabmap_msgs::ScanDescriptorConstPtr& scanDescMsg)
300 rtabmap_msgs::OdomInfoConstPtr odomInfoMsg;
301 if(!scanDescMsg->global_descriptor.data.empty())
303 globalDescriptorMsgs.push_back(scanDescMsg->global_descriptor);
305 commonMultiCameraCallback(odomMsg, userDataMsg, imageMsgs, depthMsgs, cameraInfoMsgs, depthCameraInfoMsgs, scanDescMsg->scan, scanDescMsg->scan_cloud, odomInfoMsg, globalDescriptorMsgs, localKeyPoints, localPoints3d, localDescriptors);
307 void CommonDataSubscriber::rgbdXOdomDataInfoCallback(
308 const nav_msgs::OdometryConstPtr& odomMsg,
309 const rtabmap_msgs::UserDataConstPtr& userDataMsg,
310 const rtabmap_msgs::RGBDImagesConstPtr& imagesMsg,
311 const rtabmap_msgs::OdomInfoConstPtr& odomInfoMsg)
315 sensor_msgs::LaserScan scanMsg;
316 sensor_msgs::PointCloud2 scan3dMsg;
317 commonMultiCameraCallback(odomMsg, userDataMsg, imageMsgs, depthMsgs, cameraInfoMsgs, depthCameraInfoMsgs, scanMsg, scan3dMsg, odomInfoMsg, globalDescriptorMsgs, localKeyPoints, localPoints3d, localDescriptors);
325 bool subscribeUserData,
326 bool subscribeScan2d,
327 bool subscribeScan3d,
328 bool subscribeScanDesc,
329 bool subscribeOdomInfo)
334 #ifdef RTABMAP_SYNC_USER_DATA
335 if(subscribeOdom && subscribeUserData)
339 if(subscribeScanDesc)
343 if(subscribeOdomInfo)
346 ROS_WARN(
"subscribe_odom_info ignored...");
350 else if(subscribeScan2d)
354 if(subscribeOdomInfo)
357 ROS_WARN(
"subscribe_odom_info ignored...");
361 else if(subscribeScan3d)
365 if(subscribeOdomInfo)
368 ROS_WARN(
"subscribe_odom_info ignored...");
372 else if(subscribeOdomInfo)
388 if(subscribeScanDesc)
392 if(subscribeOdomInfo)
395 ROS_WARN(
"subscribe_odom_info ignored...");
399 else if(subscribeScan2d)
403 if(subscribeOdomInfo)
406 ROS_WARN(
"subscribe_odom_info ignored...");
410 else if(subscribeScan3d)
414 if(subscribeOdomInfo)
417 ROS_WARN(
"subscribe_odom_info ignored...");
421 else if(subscribeOdomInfo)
432 #ifdef RTABMAP_SYNC_USER_DATA
433 else if(subscribeUserData)
436 if(subscribeScanDesc)
440 if(subscribeOdomInfo)
443 ROS_WARN(
"subscribe_odom_info ignored...");
447 else if(subscribeScan2d)
451 if(subscribeOdomInfo)
454 ROS_WARN(
"subscribe_odom_info ignored...");
458 else if(subscribeScan3d)
462 if(subscribeOdomInfo)
465 ROS_WARN(
"subscribe_odom_info ignored...");
469 else if(subscribeOdomInfo)
483 if(subscribeScanDesc)
487 if(subscribeOdomInfo)
490 ROS_WARN(
"subscribe_odom_info ignored...");
494 else if(subscribeScan2d)
498 if(subscribeOdomInfo)
501 ROS_WARN(
"subscribe_odom_info ignored...");
505 else if(subscribeScan3d)
509 if(subscribeOdomInfo)
512 ROS_WARN(
"subscribe_odom_info ignored...");
516 else if(subscribeOdomInfo)
528 uFormat(
"\n%s subscribed to:\n %s",