CommonDataSubscriberRGBDX.cpp
Go to the documentation of this file.
1 /*
2 Copyright (c) 2010-2016, Mathieu Labbe - IntRoLab - Universite de Sherbrooke
3 All rights reserved.
4 
5 Redistribution and use in source and binary forms, with or without
6 modification, are permitted provided that the following conditions are met:
7  * Redistributions of source code must retain the above copyright
8  notice, this list of conditions and the following disclaimer.
9  * Redistributions in binary form must reproduce the above copyright
10  notice, this list of conditions and the following disclaimer in the
11  documentation and/or other materials provided with the distribution.
12  * Neither the name of the Universite de Sherbrooke nor the
13  names of its contributors may be used to endorse or promote products
14  derived from this software without specific prior written permission.
15 
16 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
17 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
18 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
19 DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY
20 DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
21 (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
22 LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
23 ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
24 (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
25 SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
26 */
27 
32 #include <cv_bridge/cv_bridge.h>
33 
34 namespace rtabmap_sync {
35 
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) \
47  { \
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)); \
56  } \
57  if(!depthMsgs[0].get()) \
58  depthMsgs.clear();
59 
60 // X RGBD
62  const rtabmap_msgs::RGBDImagesConstPtr& imagesMsg)
63 {
65 
66  nav_msgs::OdometryConstPtr odomMsg; // Null
67  rtabmap_msgs::UserDataConstPtr userDataMsg; // Null
68  sensor_msgs::LaserScan scanMsg; // Null
69  sensor_msgs::PointCloud2 scan3dMsg; // Null
70  rtabmap_msgs::OdomInfoConstPtr odomInfoMsg; // null
71  commonMultiCameraCallback(odomMsg, userDataMsg, imageMsgs, depthMsgs, cameraInfoMsgs, depthCameraInfoMsgs, scanMsg, scan3dMsg, odomInfoMsg, globalDescriptorMsgs, localKeyPoints, localPoints3d, localDescriptors);
72 }
73 void CommonDataSubscriber::rgbdXScan2dCallback(
74  const rtabmap_msgs::RGBDImagesConstPtr& imagesMsg,
75  const sensor_msgs::LaserScanConstPtr& scanMsg)
76 {
78 
79  nav_msgs::OdometryConstPtr odomMsg; // Null
80  rtabmap_msgs::UserDataConstPtr userDataMsg; // Null
81  sensor_msgs::PointCloud2 scan3dMsg; // Null
82  rtabmap_msgs::OdomInfoConstPtr odomInfoMsg; // null
83  commonMultiCameraCallback(odomMsg, userDataMsg, imageMsgs, depthMsgs, cameraInfoMsgs, depthCameraInfoMsgs, *scanMsg, scan3dMsg, odomInfoMsg, globalDescriptorMsgs, localKeyPoints, localPoints3d, localDescriptors);
84 }
85 void CommonDataSubscriber::rgbdXScan3dCallback(
86  const rtabmap_msgs::RGBDImagesConstPtr& imagesMsg,
87  const sensor_msgs::PointCloud2ConstPtr& scan3dMsg)
88 {
90 
91  nav_msgs::OdometryConstPtr odomMsg; // Null
92  rtabmap_msgs::UserDataConstPtr userDataMsg; // Null
93  sensor_msgs::LaserScan scanMsg; // Null
94  rtabmap_msgs::OdomInfoConstPtr odomInfoMsg; // null
95  commonMultiCameraCallback(odomMsg, userDataMsg, imageMsgs, depthMsgs, cameraInfoMsgs, depthCameraInfoMsgs, scanMsg, *scan3dMsg, odomInfoMsg, globalDescriptorMsgs, localKeyPoints, localPoints3d, localDescriptors);
96 }
97 void CommonDataSubscriber::rgbdXScanDescCallback(
98  const rtabmap_msgs::RGBDImagesConstPtr& imagesMsg,
99  const rtabmap_msgs::ScanDescriptorConstPtr& scanDescMsg)
100 {
102 
103  nav_msgs::OdometryConstPtr odomMsg; // Null
104  rtabmap_msgs::UserDataConstPtr userDataMsg; // Null
105  rtabmap_msgs::OdomInfoConstPtr odomInfoMsg; // null
106  if(!scanDescMsg->global_descriptor.data.empty())
107  {
108  globalDescriptorMsgs.push_back(scanDescMsg->global_descriptor);
109  }
110  commonMultiCameraCallback(odomMsg, userDataMsg, imageMsgs, depthMsgs, cameraInfoMsgs, depthCameraInfoMsgs, scanDescMsg->scan, scanDescMsg->scan_cloud, odomInfoMsg, globalDescriptorMsgs, localKeyPoints, localPoints3d, localDescriptors);
111 }
112 void CommonDataSubscriber::rgbdXInfoCallback(
113  const rtabmap_msgs::RGBDImagesConstPtr& imagesMsg,
114  const rtabmap_msgs::OdomInfoConstPtr& odomInfoMsg)
115 {
117 
118  nav_msgs::OdometryConstPtr odomMsg; // Null
119  rtabmap_msgs::UserDataConstPtr userDataMsg; // Null
120  sensor_msgs::LaserScan scanMsg; // Null
121  sensor_msgs::PointCloud2 scan3dMsg; // Null
122  commonMultiCameraCallback(odomMsg, userDataMsg, imageMsgs, depthMsgs, cameraInfoMsgs, depthCameraInfoMsgs, scanMsg, scan3dMsg, odomInfoMsg, globalDescriptorMsgs, localKeyPoints, localPoints3d, localDescriptors);
123 }
124 // X RGBD + Odom
125 void CommonDataSubscriber::rgbdXOdomCallback(
126  const nav_msgs::OdometryConstPtr & odomMsg,
127  const rtabmap_msgs::RGBDImagesConstPtr& imagesMsg)
128 {
130 
131  rtabmap_msgs::UserDataConstPtr userDataMsg; // Null
132  sensor_msgs::LaserScan scanMsg; // Null
133  sensor_msgs::PointCloud2 scan3dMsg; // Null
134  rtabmap_msgs::OdomInfoConstPtr odomInfoMsg; // null
135  commonMultiCameraCallback(odomMsg, userDataMsg, imageMsgs, depthMsgs, cameraInfoMsgs, depthCameraInfoMsgs, scanMsg, scan3dMsg, odomInfoMsg, globalDescriptorMsgs, localKeyPoints, localPoints3d, localDescriptors);
136 }
137 void CommonDataSubscriber::rgbdXOdomScan2dCallback(
138  const nav_msgs::OdometryConstPtr & odomMsg,
139  const rtabmap_msgs::RGBDImagesConstPtr& imagesMsg,
140  const sensor_msgs::LaserScanConstPtr& scanMsg)
141 {
143 
144  rtabmap_msgs::UserDataConstPtr userDataMsg; // Null
145  sensor_msgs::PointCloud2 scan3dMsg; // Null
146  rtabmap_msgs::OdomInfoConstPtr odomInfoMsg; // null
147  commonMultiCameraCallback(odomMsg, userDataMsg, imageMsgs, depthMsgs, cameraInfoMsgs, depthCameraInfoMsgs, *scanMsg, scan3dMsg, odomInfoMsg, globalDescriptorMsgs, localKeyPoints, localPoints3d, localDescriptors);
148 }
149 void CommonDataSubscriber::rgbdXOdomScan3dCallback(
150  const nav_msgs::OdometryConstPtr & odomMsg,
151  const rtabmap_msgs::RGBDImagesConstPtr& imagesMsg,
152  const sensor_msgs::PointCloud2ConstPtr& scan3dMsg)
153 {
155 
156  rtabmap_msgs::UserDataConstPtr userDataMsg; // Null
157  sensor_msgs::LaserScan scanMsg; // Null
158  rtabmap_msgs::OdomInfoConstPtr odomInfoMsg; // null
159  commonMultiCameraCallback(odomMsg, userDataMsg, imageMsgs, depthMsgs, cameraInfoMsgs, depthCameraInfoMsgs, scanMsg, *scan3dMsg, odomInfoMsg, globalDescriptorMsgs, localKeyPoints, localPoints3d, localDescriptors);
160 }
161 void CommonDataSubscriber::rgbdXOdomScanDescCallback(
162  const nav_msgs::OdometryConstPtr & odomMsg,
163  const rtabmap_msgs::RGBDImagesConstPtr& imagesMsg,
164  const rtabmap_msgs::ScanDescriptorConstPtr& scanDescMsg)
165 {
167 
168  rtabmap_msgs::UserDataConstPtr userDataMsg; // Null
169  rtabmap_msgs::OdomInfoConstPtr odomInfoMsg; // null
170  if(!scanDescMsg->global_descriptor.data.empty())
171  {
172  globalDescriptorMsgs.push_back(scanDescMsg->global_descriptor);
173  }
174  commonMultiCameraCallback(odomMsg, userDataMsg, imageMsgs, depthMsgs, cameraInfoMsgs, depthCameraInfoMsgs, scanDescMsg->scan, scanDescMsg->scan_cloud, odomInfoMsg, globalDescriptorMsgs, localKeyPoints, localPoints3d, localDescriptors);
175 }
176 void CommonDataSubscriber::rgbdXOdomInfoCallback(
177  const nav_msgs::OdometryConstPtr & odomMsg,
178  const rtabmap_msgs::RGBDImagesConstPtr& imagesMsg,
179  const rtabmap_msgs::OdomInfoConstPtr& odomInfoMsg)
180 {
182 
183  rtabmap_msgs::UserDataConstPtr userDataMsg; // Null
184  sensor_msgs::LaserScan scanMsg; // Null
185  sensor_msgs::PointCloud2 scan3dMsg; // Null
186  commonMultiCameraCallback(odomMsg, userDataMsg, imageMsgs, depthMsgs, cameraInfoMsgs, depthCameraInfoMsgs, scanMsg, scan3dMsg, odomInfoMsg, globalDescriptorMsgs, localKeyPoints, localPoints3d, localDescriptors);
187 }
188 
189 #ifdef RTABMAP_SYNC_USER_DATA
190 // X RGBD + User Data
191 void CommonDataSubscriber::rgbdXDataCallback(
192  const rtabmap_msgs::UserDataConstPtr& userDataMsg,
193  const rtabmap_msgs::RGBDImagesConstPtr& imagesMsg)
194 {
196 
197  nav_msgs::OdometryConstPtr odomMsg; // Null
198  sensor_msgs::LaserScan scanMsg; // Null
199  sensor_msgs::PointCloud2 scan3dMsg; // Null
200  rtabmap_msgs::OdomInfoConstPtr odomInfoMsg; // null
201  commonMultiCameraCallback(odomMsg, userDataMsg, imageMsgs, depthMsgs, cameraInfoMsgs, depthCameraInfoMsgs, scanMsg, scan3dMsg, odomInfoMsg, globalDescriptorMsgs, localKeyPoints, localPoints3d, localDescriptors);
202 }
203 void CommonDataSubscriber::rgbdXDataScan2dCallback(
204  const rtabmap_msgs::UserDataConstPtr& userDataMsg,
205  const rtabmap_msgs::RGBDImagesConstPtr& imagesMsg,
206  const sensor_msgs::LaserScanConstPtr& scanMsg)
207 {
209 
210  nav_msgs::OdometryConstPtr odomMsg; // Null
211  sensor_msgs::PointCloud2 scan3dMsg; // Null
212  rtabmap_msgs::OdomInfoConstPtr odomInfoMsg; // null
213  commonMultiCameraCallback(odomMsg, userDataMsg, imageMsgs, depthMsgs, cameraInfoMsgs, depthCameraInfoMsgs, *scanMsg, scan3dMsg, odomInfoMsg, globalDescriptorMsgs, localKeyPoints, localPoints3d, localDescriptors);
214 }
215 void CommonDataSubscriber::rgbdXDataScan3dCallback(
216  const rtabmap_msgs::UserDataConstPtr& userDataMsg,
217  const rtabmap_msgs::RGBDImagesConstPtr& imagesMsg,
218  const sensor_msgs::PointCloud2ConstPtr& scan3dMsg)
219 {
221 
222  nav_msgs::OdometryConstPtr odomMsg; // Null
223  sensor_msgs::LaserScan scanMsg; // Null
224  rtabmap_msgs::OdomInfoConstPtr odomInfoMsg; // null
225  commonMultiCameraCallback(odomMsg, userDataMsg, imageMsgs, depthMsgs, cameraInfoMsgs, depthCameraInfoMsgs, scanMsg, *scan3dMsg, odomInfoMsg, globalDescriptorMsgs, localKeyPoints, localPoints3d, localDescriptors);
226 }
227 void CommonDataSubscriber::rgbdXDataScanDescCallback(
228  const rtabmap_msgs::UserDataConstPtr& userDataMsg,
229  const rtabmap_msgs::RGBDImagesConstPtr& imagesMsg,
230  const rtabmap_msgs::ScanDescriptorConstPtr& scanDescMsg)
231 {
233 
234  nav_msgs::OdometryConstPtr odomMsg; // Null
235  rtabmap_msgs::OdomInfoConstPtr odomInfoMsg; // null
236  if(!scanDescMsg->global_descriptor.data.empty())
237  {
238  globalDescriptorMsgs.push_back(scanDescMsg->global_descriptor);
239  }
240  commonMultiCameraCallback(odomMsg, userDataMsg, imageMsgs, depthMsgs, cameraInfoMsgs, depthCameraInfoMsgs, scanDescMsg->scan, scanDescMsg->scan_cloud, odomInfoMsg, globalDescriptorMsgs, localKeyPoints, localPoints3d, localDescriptors);
241 }
242 void CommonDataSubscriber::rgbdXDataInfoCallback(
243  const rtabmap_msgs::UserDataConstPtr& userDataMsg,
244  const rtabmap_msgs::RGBDImagesConstPtr& imagesMsg,
245  const rtabmap_msgs::OdomInfoConstPtr& odomInfoMsg)
246 {
248 
249  nav_msgs::OdometryConstPtr odomMsg; // Null
250  sensor_msgs::LaserScan scanMsg; // Null
251  sensor_msgs::PointCloud2 scan3dMsg; // Null
252  commonMultiCameraCallback(odomMsg, userDataMsg, imageMsgs, depthMsgs, cameraInfoMsgs, depthCameraInfoMsgs, scanMsg, scan3dMsg, odomInfoMsg, globalDescriptorMsgs, localKeyPoints, localPoints3d, localDescriptors);
253 }
254 
255 // X RGBD + Odom + User Data
256 void CommonDataSubscriber::rgbdXOdomDataCallback(
257  const nav_msgs::OdometryConstPtr& odomMsg,
258  const rtabmap_msgs::UserDataConstPtr& userDataMsg,
259  const rtabmap_msgs::RGBDImagesConstPtr& imagesMsg)
260 {
262 
263  sensor_msgs::LaserScan scanMsg; // Null
264  sensor_msgs::PointCloud2 scan3dMsg; // Null
265  rtabmap_msgs::OdomInfoConstPtr odomInfoMsg; // null
266  commonMultiCameraCallback(odomMsg, userDataMsg, imageMsgs, depthMsgs, cameraInfoMsgs, depthCameraInfoMsgs, scanMsg, scan3dMsg, odomInfoMsg, globalDescriptorMsgs, localKeyPoints, localPoints3d, localDescriptors);
267 }
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)
273 {
275 
276  sensor_msgs::PointCloud2 scan3dMsg; // Null
277  rtabmap_msgs::OdomInfoConstPtr odomInfoMsg; // null
278  commonMultiCameraCallback(odomMsg, userDataMsg, imageMsgs, depthMsgs, cameraInfoMsgs, depthCameraInfoMsgs, *scanMsg, scan3dMsg, odomInfoMsg, globalDescriptorMsgs, localKeyPoints, localPoints3d, localDescriptors);
279 }
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)
285 {
287 
288  sensor_msgs::LaserScan scanMsg; // Null
289  rtabmap_msgs::OdomInfoConstPtr odomInfoMsg; // null
290  commonMultiCameraCallback(odomMsg, userDataMsg, imageMsgs, depthMsgs, cameraInfoMsgs, depthCameraInfoMsgs, scanMsg, *scan3dMsg, odomInfoMsg, globalDescriptorMsgs, localKeyPoints, localPoints3d, localDescriptors);
291 }
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)
297 {
299 
300  rtabmap_msgs::OdomInfoConstPtr odomInfoMsg; // null
301  if(!scanDescMsg->global_descriptor.data.empty())
302  {
303  globalDescriptorMsgs.push_back(scanDescMsg->global_descriptor);
304  }
305  commonMultiCameraCallback(odomMsg, userDataMsg, imageMsgs, depthMsgs, cameraInfoMsgs, depthCameraInfoMsgs, scanDescMsg->scan, scanDescMsg->scan_cloud, odomInfoMsg, globalDescriptorMsgs, localKeyPoints, localPoints3d, localDescriptors);
306 }
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)
312 {
314 
315  sensor_msgs::LaserScan scanMsg; // Null
316  sensor_msgs::PointCloud2 scan3dMsg; // Null
317  commonMultiCameraCallback(odomMsg, userDataMsg, imageMsgs, depthMsgs, cameraInfoMsgs, depthCameraInfoMsgs, scanMsg, scan3dMsg, odomInfoMsg, globalDescriptorMsgs, localKeyPoints, localPoints3d, localDescriptors);
318 }
319 #endif
320 
322  ros::NodeHandle & nh,
323  ros::NodeHandle & pnh,
324  bool subscribeOdom,
325  bool subscribeUserData,
326  bool subscribeScan2d,
327  bool subscribeScan3d,
328  bool subscribeScanDesc,
329  bool subscribeOdomInfo)
330 {
331  ROS_INFO("Setup rgbdX callback");
332 
333  rgbdXSub_.subscribe(nh, "rgbd_images", topicQueueSize_);
334 #ifdef RTABMAP_SYNC_USER_DATA
335  if(subscribeOdom && subscribeUserData)
336  {
337  odomSub_.subscribe(nh, "odom", topicQueueSize_);
338  userDataSub_.subscribe(nh, "user_data", topicQueueSize_);
339  if(subscribeScanDesc)
340  {
342  scanDescSub_.subscribe(nh, "scan_descriptor", topicQueueSize_);
343  if(subscribeOdomInfo)
344  {
345  subscribedToOdomInfo_ = false;
346  ROS_WARN("subscribe_odom_info ignored...");
347  }
349  }
350  else if(subscribeScan2d)
351  {
352  subscribedToScan2d_ = true;
353  scanSub_.subscribe(nh, "scan", topicQueueSize_);
354  if(subscribeOdomInfo)
355  {
356  subscribedToOdomInfo_ = false;
357  ROS_WARN("subscribe_odom_info ignored...");
358  }
360  }
361  else if(subscribeScan3d)
362  {
363  subscribedToScan3d_ = true;
364  scan3dSub_.subscribe(nh, "scan_cloud", topicQueueSize_);
365  if(subscribeOdomInfo)
366  {
367  subscribedToOdomInfo_ = false;
368  ROS_WARN("subscribe_odom_info ignored...");
369  }
371  }
372  else if(subscribeOdomInfo)
373  {
374  subscribedToOdomInfo_ = true;
375  odomInfoSub_.subscribe(nh, "odom_info", topicQueueSize_);
377  }
378  else
379  {
381  }
382  }
383  else
384 #endif
385  if(subscribeOdom)
386  {
387  odomSub_.subscribe(nh, "odom", topicQueueSize_);
388  if(subscribeScanDesc)
389  {
391  scanDescSub_.subscribe(nh, "scan_descriptor", topicQueueSize_);
392  if(subscribeOdomInfo)
393  {
394  subscribedToOdomInfo_ = false;
395  ROS_WARN("subscribe_odom_info ignored...");
396  }
398  }
399  else if(subscribeScan2d)
400  {
401  subscribedToScan2d_ = true;
402  scanSub_.subscribe(nh, "scan", topicQueueSize_);
403  if(subscribeOdomInfo)
404  {
405  subscribedToOdomInfo_ = false;
406  ROS_WARN("subscribe_odom_info ignored...");
407  }
409  }
410  else if(subscribeScan3d)
411  {
412  subscribedToScan3d_ = true;
413  scan3dSub_.subscribe(nh, "scan_cloud", topicQueueSize_);
414  if(subscribeOdomInfo)
415  {
416  subscribedToOdomInfo_ = false;
417  ROS_WARN("subscribe_odom_info ignored...");
418  }
420  }
421  else if(subscribeOdomInfo)
422  {
423  subscribedToOdomInfo_ = true;
424  odomInfoSub_.subscribe(nh, "odom_info", topicQueueSize_);
426  }
427  else
428  {
430  }
431  }
432 #ifdef RTABMAP_SYNC_USER_DATA
433  else if(subscribeUserData)
434  {
435  userDataSub_.subscribe(nh, "user_data", topicQueueSize_);
436  if(subscribeScanDesc)
437  {
439  scanDescSub_.subscribe(nh, "scan_descriptor", topicQueueSize_);
440  if(subscribeOdomInfo)
441  {
442  subscribedToOdomInfo_ = false;
443  ROS_WARN("subscribe_odom_info ignored...");
444  }
446  }
447  else if(subscribeScan2d)
448  {
449  subscribedToScan2d_ = true;
450  scanSub_.subscribe(nh, "scan", topicQueueSize_);
451  if(subscribeOdomInfo)
452  {
453  subscribedToOdomInfo_ = false;
454  ROS_WARN("subscribe_odom_info ignored...");
455  }
457  }
458  else if(subscribeScan3d)
459  {
460  subscribedToScan3d_ = true;
461  scan3dSub_.subscribe(nh, "scan_cloud", topicQueueSize_);
462  if(subscribeOdomInfo)
463  {
464  subscribedToOdomInfo_ = false;
465  ROS_WARN("subscribe_odom_info ignored...");
466  }
468  }
469  else if(subscribeOdomInfo)
470  {
471  subscribedToOdomInfo_ = true;
472  odomInfoSub_.subscribe(nh, "odom_info", topicQueueSize_);
474  }
475  else
476  {
478  }
479  }
480 #endif
481  else
482  {
483  if(subscribeScanDesc)
484  {
486  scanDescSub_.subscribe(nh, "scan_descriptor", topicQueueSize_);
487  if(subscribeOdomInfo)
488  {
489  subscribedToOdomInfo_ = false;
490  ROS_WARN("subscribe_odom_info ignored...");
491  }
493  }
494  else if(subscribeScan2d)
495  {
496  subscribedToScan2d_ = true;
497  scanSub_.subscribe(nh, "scan", topicQueueSize_);
498  if(subscribeOdomInfo)
499  {
500  subscribedToOdomInfo_ = false;
501  ROS_WARN("subscribe_odom_info ignored...");
502  }
504  }
505  else if(subscribeScan3d)
506  {
507  subscribedToScan3d_ = true;
508  scan3dSub_.subscribe(nh, "scan_cloud", topicQueueSize_);
509  if(subscribeOdomInfo)
510  {
511  subscribedToOdomInfo_ = false;
512  ROS_WARN("subscribe_odom_info ignored...");
513  }
515  }
516  else if(subscribeOdomInfo)
517  {
518  subscribedToOdomInfo_ = true;
519  odomInfoSub_.subscribe(nh, "odom_info", topicQueueSize_);
521  }
522  else
523  {
526 
528  uFormat("\n%s subscribed to:\n %s",
530  rgbdXSubOnly_.getTopic().c_str());
531  }
532  }
533 }
534 
535 } /* namespace rtabmap_sync */
SYNC_DECL2
#define SYNC_DECL2(CLASS, PREFIX, APPROX, QUEUE_SIZE, SUB0, SUB1)
Definition: CommonDataSubscriberDefines.h:108
rtabmap_sync::CommonDataSubscriber::rgbdXCallback
void rgbdXCallback(const rtabmap_msgs::RGBDImagesConstPtr &)
Definition: CommonDataSubscriberRGBDX.cpp:61
rtabmap_sync
Definition: CommonDataSubscriber.h:59
uFormat
std::string uFormat(const char *fmt,...)
Compression.h
ros::Subscriber::getTopic
std::string getTopic() const
SYNC_DECL3
#define SYNC_DECL3(CLASS, PREFIX, APPROX, QUEUE_SIZE, SUB0, SUB1, SUB2)
Definition: CommonDataSubscriberDefines.h:127
rtabmap_sync::CommonDataSubscriber::rgbdXSubOnly_
ros::Subscriber rgbdXSubOnly_
Definition: CommonDataSubscriber.h:270
rtabmap_sync::CommonDataSubscriber::scan3dSub_
message_filters::Subscriber< sensor_msgs::PointCloud2 > scan3dSub_
Definition: CommonDataSubscriber.h:286
message_filters::Subscriber::unsubscribe
void unsubscribe()
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
CommonDataSubscriber.h
rtabmap_sync::CommonDataSubscriber::syncQueueSize_
int syncQueueSize_
Definition: CommonDataSubscriber.h:246
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
IMAGE_CONVERSION
#define IMAGE_CONVERSION()
Definition: CommonDataSubscriberRGBDX.cpp:36
rtabmap_sync::CommonDataSubscriber::subscribedToScan3d_
bool subscribedToScan3d_
Definition: CommonDataSubscriber.h:257
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
ROS_WARN
#define ROS_WARN(...)
ros::NodeHandle::subscribe
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
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
message_filters::Subscriber::subscribe
void subscribe()
ros::this_node::getName
const ROSCPP_DECL std::string & getName()
rtabmap_sync::CommonDataSubscriber::approxSync_
bool approxSync_
Definition: CommonDataSubscriber.h:249
rtabmap_sync::CommonDataSubscriber::odomSub_
message_filters::Subscriber< nav_msgs::Odometry > odomSub_
Definition: CommonDataSubscriber.h:283
c_str
const char * c_str(Args &&...args)
cv_bridge.h
SYNC_DECL4
#define SYNC_DECL4(CLASS, PREFIX, APPROX, QUEUE_SIZE, SUB0, SUB1, SUB2, SUB3)
Definition: CommonDataSubscriberDefines.h:147
rtabmap_sync::CommonDataSubscriber::subscribedToOdomInfo_
bool subscribedToOdomInfo_
Definition: CommonDataSubscriber.h:259
rtabmap_sync::CommonDataSubscriber::subscribedToScan2d_
bool subscribedToScan2d_
Definition: CommonDataSubscriber.h:256
ROS_INFO
#define ROS_INFO(...)
UConversion.h
MsgConversion.h
rtabmap_sync::CommonDataSubscriber::userDataSub_
message_filters::Subscriber< rtabmap_msgs::UserData > userDataSub_
Definition: CommonDataSubscriber.h:284
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
Definition: CommonDataSubscriber.h:61
rtabmap_sync::CommonDataSubscriber::rgbdXSub_
message_filters::Subscriber< rtabmap_msgs::RGBDImages > rgbdXSub_
Definition: CommonDataSubscriber.h:271
ros::NodeHandle


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