CommonDataSubscriber.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 
29 
30 namespace rtabmap_ros {
31 
33  queueSize_(10),
34  approxSync_(true),
35  warningThread_(0),
36  callbackCalled_(false),
37  subscribedToDepth_(!gui),
38  subscribedToStereo_(false),
39  subscribedToRGBD_(false),
40  subscribedToScan2d_(false),
41  subscribedToScan3d_(false),
42  subscribedToOdomInfo_(false),
43 
44  // RGB + Depth
45  SYNC_INIT(depth),
46  SYNC_INIT(depthScan2d),
47  SYNC_INIT(depthScan3d),
48  SYNC_INIT(depthInfo),
49  SYNC_INIT(depthScan2dInfo),
50  SYNC_INIT(depthScan3dInfo),
51 
52  // RGB + Depth + Odom
53  SYNC_INIT(depthOdom),
54  SYNC_INIT(depthOdomScan2d),
55  SYNC_INIT(depthOdomScan3d),
56  SYNC_INIT(depthOdomInfo),
57  SYNC_INIT(depthOdomScan2dInfo),
58  SYNC_INIT(depthOdomScan3dInfo),
59 
60  // RGB + Depth + User Data
61  SYNC_INIT(depthData),
62  SYNC_INIT(depthDataScan2d),
63  SYNC_INIT(depthDataScan3d),
64  SYNC_INIT(depthDataInfo),
65  SYNC_INIT(depthDataScan2dInfo),
66  SYNC_INIT(depthDataScan3dInfo),
67 
68  // RGB + Depth + Odom + User Data
69  SYNC_INIT(depthOdomData),
70  SYNC_INIT(depthOdomDataScan2d),
71  SYNC_INIT(depthOdomDataScan3d),
72  SYNC_INIT(depthOdomDataInfo),
73  SYNC_INIT(depthOdomDataScan2dInfo),
74  SYNC_INIT(depthOdomDataScan3dInfo),
75 
76  // Stereo
77  SYNC_INIT(stereo),
78  SYNC_INIT(stereoInfo),
79 
80  // Stereo + Odom
81  SYNC_INIT(stereoOdom),
82  SYNC_INIT(stereoOdomInfo),
83 
84  // 1 RGBD
85  SYNC_INIT(rgbdScan2d),
86  SYNC_INIT(rgbdScan3d),
87  SYNC_INIT(rgbdInfo),
88  SYNC_INIT(rgbdScan2dInfo),
89  SYNC_INIT(rgbdScan3dInfo),
90 
91  // 1 RGBD + Odom
92  SYNC_INIT(rgbdOdom),
93  SYNC_INIT(rgbdOdomScan2d),
94  SYNC_INIT(rgbdOdomScan3d),
95  SYNC_INIT(rgbdOdomInfo),
96  SYNC_INIT(rgbdOdomScan2dInfo),
97  SYNC_INIT(rgbdOdomScan3dInfo),
98 
99  // 1 RGBD + User Data
100  SYNC_INIT(rgbdData),
101  SYNC_INIT(rgbdDataScan2d),
102  SYNC_INIT(rgbdDataScan3d),
103  SYNC_INIT(rgbdDataInfo),
104  SYNC_INIT(rgbdDataScan2dInfo),
105  SYNC_INIT(rgbdDataScan3dInfo),
106 
107  // 1 RGBD + Odom + User Data
108  SYNC_INIT(rgbdOdomData),
109  SYNC_INIT(rgbdOdomDataScan2d),
110  SYNC_INIT(rgbdOdomDataScan3d),
111  SYNC_INIT(rgbdOdomDataInfo),
112  SYNC_INIT(rgbdOdomDataScan2dInfo),
113  SYNC_INIT(rgbdOdomDataScan3dInfo),
114 
115  // 2 RGBD
116  SYNC_INIT(rgbd2),
117  SYNC_INIT(rgbd2Scan2d),
118  SYNC_INIT(rgbd2Scan3d),
119  SYNC_INIT(rgbd2Info),
120  SYNC_INIT(rgbd2Scan2dInfo),
121  SYNC_INIT(rgbd2Scan3dInfo),
122 
123  // 2 RGBD + Odom
124  SYNC_INIT(rgbd2Odom),
125  SYNC_INIT(rgbd2OdomScan2d),
126  SYNC_INIT(rgbd2OdomScan3d),
127  SYNC_INIT(rgbd2OdomInfo),
128  SYNC_INIT(rgbd2OdomScan2dInfo),
129  SYNC_INIT(rgbd2OdomScan3dInfo),
130 
131  // 2 RGBD + User Data
132  SYNC_INIT(rgbd2Data),
133  SYNC_INIT(rgbd2DataScan2d),
134  SYNC_INIT(rgbd2DataScan3d),
135  SYNC_INIT(rgbd2DataInfo),
136  SYNC_INIT(rgbd2DataScan2dInfo),
137  SYNC_INIT(rgbd2DataScan3dInfo),
138 
139  // 2 RGBD + Odom + User Data
140  SYNC_INIT(rgbd2OdomData),
141  SYNC_INIT(rgbd2OdomDataScan2d),
142  SYNC_INIT(rgbd2OdomDataScan3d),
143  SYNC_INIT(rgbd2OdomDataInfo),
144  SYNC_INIT(rgbd2OdomDataScan2dInfo),
145  SYNC_INIT(rgbd2OdomDataScan3dInfo),
146 
147  // 3 RGBD
148  SYNC_INIT(rgbd3),
149  SYNC_INIT(rgbd3Scan2d),
150  SYNC_INIT(rgbd3Scan3d),
151  SYNC_INIT(rgbd3Info),
152  SYNC_INIT(rgbd3Scan2dInfo),
153  SYNC_INIT(rgbd3Scan3dInfo),
154 
155  // 3 RGBD + Odom
156  SYNC_INIT(rgbd3Odom),
157  SYNC_INIT(rgbd3OdomScan2d),
158  SYNC_INIT(rgbd3OdomScan3d),
159  SYNC_INIT(rgbd3OdomInfo),
160  SYNC_INIT(rgbd3OdomScan2dInfo),
161  SYNC_INIT(rgbd3OdomScan3dInfo),
162 
163  // 3 RGBD + User Data
164  SYNC_INIT(rgbd3Data),
165  SYNC_INIT(rgbd3DataScan2d),
166  SYNC_INIT(rgbd3DataScan3d),
167  SYNC_INIT(rgbd3DataInfo),
168  SYNC_INIT(rgbd3DataScan2dInfo),
169  SYNC_INIT(rgbd3DataScan3dInfo),
170 
171  // 3 RGBD + Odom + User Data
172  SYNC_INIT(rgbd3OdomData),
173  SYNC_INIT(rgbd3OdomDataScan2d),
174  SYNC_INIT(rgbd3OdomDataScan3d),
175  SYNC_INIT(rgbd3OdomDataInfo),
176  SYNC_INIT(rgbd3OdomDataScan2dInfo),
177  SYNC_INIT(rgbd3OdomDataScan3dInfo),
178 
179  // 4 RGBD
180  SYNC_INIT(rgbd4),
181  SYNC_INIT(rgbd4Scan2d),
182  SYNC_INIT(rgbd4Scan3d),
183  SYNC_INIT(rgbd4Info),
184  SYNC_INIT(rgbd4Scan2dInfo),
185  SYNC_INIT(rgbd4Scan3dInfo),
186 
187  // 4 RGBD + Odom
188  SYNC_INIT(rgbd4Odom),
189  SYNC_INIT(rgbd4OdomScan2d),
190  SYNC_INIT(rgbd4OdomScan3d),
191  SYNC_INIT(rgbd4OdomInfo),
192  SYNC_INIT(rgbd4OdomScan2dInfo),
193  SYNC_INIT(rgbd4OdomScan3dInfo),
194 
195  // 4 RGBD + User Data
196  SYNC_INIT(rgbd4Data),
197  SYNC_INIT(rgbd4DataScan2d),
198  SYNC_INIT(rgbd4DataScan3d),
199  SYNC_INIT(rgbd4DataInfo),
200  SYNC_INIT(rgbd4DataScan2dInfo),
201  SYNC_INIT(rgbd4DataScan3dInfo),
202 
203  // 4 RGBD + Odom + User Data
204  SYNC_INIT(rgbd4OdomData),
205  SYNC_INIT(rgbd4OdomDataScan2d),
206  SYNC_INIT(rgbd4OdomDataScan3d),
207  SYNC_INIT(rgbd4OdomDataInfo),
208  SYNC_INIT(rgbd4OdomDataScan2dInfo),
209  SYNC_INIT(rgbd4OdomDataScan3dInfo)
210 
211 {
212 }
213 
214 void CommonDataSubscriber::setupCallbacks(ros::NodeHandle & nh, ros::NodeHandle & pnh, const std::string & name)
215 {
216  bool subscribeScan2d = false;
217  bool subscribeScan3d = false;
218  bool subscribeOdomInfo = false;
219  bool subscribeUserData = false;
220  int rgbdCameras = 1;
221  name_ = name;
222 
223  // ROS related parameters (private)
224  pnh.param("subscribe_depth", subscribedToDepth_, subscribedToDepth_);
225  if(pnh.getParam("subscribe_laserScan", subscribeScan2d) && subscribeScan2d)
226  {
227  ROS_WARN("rtabmap: \"subscribe_laserScan\" parameter is deprecated, use \"subscribe_scan\" instead. The scan topic is still subscribed.");
228  }
229  pnh.param("subscribe_scan", subscribeScan2d, subscribeScan2d);
230  pnh.param("subscribe_scan_cloud", subscribeScan3d, subscribeScan3d);
231  pnh.param("subscribe_stereo", subscribedToStereo_, subscribedToStereo_);
232  pnh.param("subscribe_rgbd", subscribedToRGBD_, subscribedToRGBD_);
233  pnh.param("subscribe_odom_info", subscribeOdomInfo, subscribeOdomInfo);
234  pnh.param("subscribe_user_data", subscribeUserData, subscribeUserData);
236  {
237  ROS_WARN("rtabmap: Parameters subscribe_depth and subscribe_stereo cannot be true at the same time. Parameter subscribe_depth is set to false.");
238  subscribedToDepth_ = false;
239  }
241  {
242  ROS_WARN("rtabmap: Parameters subscribe_depth and subscribe_rgbd cannot be true at the same time. Parameter subscribe_depth is set to false.");
243  subscribedToDepth_ = false;
244  }
246  {
247  ROS_WARN("rtabmap: Parameters subscribe_stereo and subscribe_rgbd cannot be true at the same time. Parameter subscribe_stereo is set to false.");
248  subscribedToStereo_ = false;
249  }
250  if(subscribeScan2d && subscribeScan3d)
251  {
252  ROS_WARN("rtabmap: Parameters subscribe_scan and subscribe_scan_cloud cannot be true at the same time. Parameter subscribe_scan_cloud is set to false.");
253  subscribeScan3d = false;
254  }
255  if(subscribeScan2d || subscribeScan3d)
256  {
258  {
259  ROS_WARN("When subscribing to laser scan, you should subscribe to depth, stereo or rgbd too. Subscribing to depth by default...");
260  subscribedToDepth_ = true;
261  }
262  }
264  {
265  approxSync_ = false; // default for stereo: exact sync
266  }
267 
268  std::string odomFrameId;
269  pnh.getParam("odom_frame_id", odomFrameId);
270  pnh.param("rgbd_cameras", rgbdCameras, rgbdCameras);
271  if(pnh.hasParam("depth_cameras"))
272  {
273  ROS_ERROR("\"depth_cameras\" parameter doesn't exist anymore. It is replaced by \"rgbd_cameras\" used when \"subscribe_rgbd\" is true.");
274  }
275  pnh.param("queue_size", queueSize_, queueSize_);
276  if(pnh.hasParam("stereo_approx_sync") && !pnh.hasParam("approx_sync"))
277  {
278  ROS_WARN("Parameter \"stereo_approx_sync\" has been renamed "
279  "to \"approx_sync\"! Your value is still copied to "
280  "corresponding parameter.");
281  pnh.param("stereo_approx_sync", approxSync_, approxSync_);
282  }
283  else
284  {
285  pnh.param("approx_sync", approxSync_, approxSync_);
286  }
287 
288  if(rgbdCameras <= 0 && subscribedToRGBD_)
289  {
290  rgbdCameras = 1;
291  }
292 
293  ROS_INFO("%s: queue_size = %d", name.c_str(), queueSize_);
294  ROS_INFO("%s: rgbd_cameras = %d", name.c_str(), rgbdCameras);
295  ROS_INFO("%s: approx_sync = %s", name.c_str(), approxSync_?"true":"false");
296 
297  bool subscribeOdom = odomFrameId.empty();
299  {
301  nh,
302  pnh,
303  subscribeOdom,
304  subscribeUserData,
305  subscribeScan2d,
306  subscribeScan3d,
307  subscribeOdomInfo,
308  queueSize_,
309  approxSync_);
310  }
311  else if(subscribedToStereo_)
312  {
314  nh,
315  pnh,
316  subscribeOdom,
317  subscribeOdomInfo,
318  queueSize_,
319  approxSync_);
320  }
321  else if(subscribedToRGBD_)
322  {
323  if(rgbdCameras == 4)
324  {
326  nh,
327  pnh,
328  subscribeOdom,
329  subscribeUserData,
330  subscribeScan2d,
331  subscribeScan3d,
332  subscribeOdomInfo,
333  queueSize_,
334  approxSync_);
335  }
336  else if(rgbdCameras == 3)
337  {
339  nh,
340  pnh,
341  subscribeOdom,
342  subscribeUserData,
343  subscribeScan2d,
344  subscribeScan3d,
345  subscribeOdomInfo,
346  queueSize_,
347  approxSync_);
348  }
349  else if(rgbdCameras == 2)
350  {
352  nh,
353  pnh,
354  subscribeOdom,
355  subscribeUserData,
356  subscribeScan2d,
357  subscribeScan3d,
358  subscribeOdomInfo,
359  queueSize_,
360  approxSync_);
361  }
362  else
363  {
365  nh,
366  pnh,
367  subscribeOdom,
368  subscribeUserData,
369  subscribeScan2d,
370  subscribeScan3d,
371  subscribeOdomInfo,
372  queueSize_,
373  approxSync_);
374  }
375  }
377  {
378  warningThread_ = new boost::thread(boost::bind(&CommonDataSubscriber::warningLoop, this));
379  ROS_INFO("%s", subscribedTopicsMsg_.c_str());
380  }
381 }
382 
384 {
385  if(warningThread_)
386  {
387  callbackCalled();
388  warningThread_->join();
389  delete warningThread_;
390  }
391 
392  // RGB + Depth
393  SYNC_DEL(depth);
394  SYNC_DEL(depthScan2d);
395  SYNC_DEL(depthScan3d);
396  SYNC_DEL(depthInfo);
397  SYNC_DEL(depthScan2dInfo);
398  SYNC_DEL(depthScan3dInfo);
399 
400  // RGB + Depth + Odom
401  SYNC_DEL(depthOdom);
402  SYNC_DEL(depthOdomScan2d);
403  SYNC_DEL(depthOdomScan3d);
404  SYNC_DEL(depthOdomInfo);
405  SYNC_DEL(depthOdomScan2dInfo);
406  SYNC_DEL(depthOdomScan3dInfo);
407 
408  // RGB + Depth + User Data
409  SYNC_DEL(depthData);
410  SYNC_DEL(depthDataScan2d);
411  SYNC_DEL(depthDataScan3d);
412  SYNC_DEL(depthDataInfo);
413  SYNC_DEL(depthDataScan2dInfo);
414  SYNC_DEL(depthDataScan3dInfo);
415 
416  // RGB + Depth + Odom + User Data
417  SYNC_DEL(depthOdomData);
418  SYNC_DEL(depthOdomDataScan2d);
419  SYNC_DEL(depthOdomDataScan3d);
420  SYNC_DEL(depthOdomDataInfo);
421  SYNC_DEL(depthOdomDataScan2dInfo);
422  SYNC_DEL(depthOdomDataScan3dInfo);
423 
424  // Stereo
425  SYNC_DEL(stereo);
426  SYNC_DEL(stereoInfo);
427 
428  // Stereo + Odom
429  SYNC_DEL(stereoOdom);
430  SYNC_DEL(stereoOdomInfo);
431 
432  // 1 RGBD
433  SYNC_DEL(rgbdScan2d);
434  SYNC_DEL(rgbdScan3d);
435  SYNC_DEL(rgbdInfo);
436  SYNC_DEL(rgbdScan2dInfo);
437  SYNC_DEL(rgbdScan3dInfo);
438 
439  // 1 RGBD + Odom
440  SYNC_DEL(rgbdOdom);
441  SYNC_DEL(rgbdOdomScan2d);
442  SYNC_DEL(rgbdOdomScan3d);
443  SYNC_DEL(rgbdOdomInfo);
444  SYNC_DEL(rgbdOdomScan2dInfo);
445  SYNC_DEL(rgbdOdomScan3dInfo);
446 
447  // 1 RGBD + User Data
448  SYNC_DEL(rgbdData);
449  SYNC_DEL(rgbdDataScan2d);
450  SYNC_DEL(rgbdDataScan3d);
451  SYNC_DEL(rgbdDataInfo);
452  SYNC_DEL(rgbdDataScan2dInfo);
453  SYNC_DEL(rgbdDataScan3dInfo);
454 
455  // 1 RGBD + Odom + User Data
456  SYNC_DEL(rgbdOdomData);
457  SYNC_DEL(rgbdOdomDataScan2d);
458  SYNC_DEL(rgbdOdomDataScan3d);
459  SYNC_DEL(rgbdOdomDataInfo);
460  SYNC_DEL(rgbdOdomDataScan2dInfo);
461  SYNC_DEL(rgbdOdomDataScan3dInfo);
462 
463  // 2 RGBD
464  SYNC_DEL(rgbd2);
465  SYNC_DEL(rgbd2Scan2d);
466  SYNC_DEL(rgbd2Scan3d);
467  SYNC_DEL(rgbd2Info);
468  SYNC_DEL(rgbd2Scan2dInfo);
469  SYNC_DEL(rgbd2Scan3dInfo);
470 
471  // 2 RGBD + Odom
472  SYNC_DEL(rgbd2Odom);
473  SYNC_DEL(rgbd2OdomScan2d);
474  SYNC_DEL(rgbd2OdomScan3d);
475  SYNC_DEL(rgbd2OdomInfo);
476  SYNC_DEL(rgbd2OdomScan2dInfo);
477  SYNC_DEL(rgbd2OdomScan3dInfo);
478 
479  // 2 RGBD + User Data
480  SYNC_DEL(rgbd2Data);
481  SYNC_DEL(rgbd2DataScan2d);
482  SYNC_DEL(rgbd2DataScan3d);
483  SYNC_DEL(rgbd2DataInfo);
484  SYNC_DEL(rgbd2DataScan2dInfo);
485  SYNC_DEL(rgbd2DataScan3dInfo);
486 
487  // 2 RGBD + Odom + User Data
488  SYNC_DEL(rgbd2OdomData);
489  SYNC_DEL(rgbd2OdomDataScan2d);
490  SYNC_DEL(rgbd2OdomDataScan3d);
491  SYNC_DEL(rgbd2OdomDataInfo);
492  SYNC_DEL(rgbd2OdomDataScan2dInfo);
493  SYNC_DEL(rgbd2OdomDataScan3dInfo);
494 
495  // 3 RGBD
496  SYNC_DEL(rgbd3);
497  SYNC_DEL(rgbd3Scan2d);
498  SYNC_DEL(rgbd3Scan3d);
499  SYNC_DEL(rgbd3Info);
500  SYNC_DEL(rgbd3Scan2dInfo);
501  SYNC_DEL(rgbd3Scan3dInfo);
502 
503  // 3 RGBD + Odom
504  SYNC_DEL(rgbd3Odom);
505  SYNC_DEL(rgbd3OdomScan2d);
506  SYNC_DEL(rgbd3OdomScan3d);
507  SYNC_DEL(rgbd3OdomInfo);
508  SYNC_DEL(rgbd3OdomScan2dInfo);
509  SYNC_DEL(rgbd3OdomScan3dInfo);
510 
511  // 3 RGBD + User Data
512  SYNC_DEL(rgbd3Data);
513  SYNC_DEL(rgbd3DataScan2d);
514  SYNC_DEL(rgbd3DataScan3d);
515  SYNC_DEL(rgbd3DataInfo);
516  SYNC_DEL(rgbd3DataScan2dInfo);
517  SYNC_DEL(rgbd3DataScan3dInfo);
518 
519  // 3 RGBD + Odom + User Data
520  SYNC_DEL(rgbd3OdomData);
521  SYNC_DEL(rgbd3OdomDataScan2d);
522  SYNC_DEL(rgbd3OdomDataScan3d);
523  SYNC_DEL(rgbd3OdomDataInfo);
524  SYNC_DEL(rgbd3OdomDataScan2dInfo);
525  SYNC_DEL(rgbd3OdomDataScan3dInfo);
526 
527  // 4 RGBD
528  SYNC_DEL(rgbd4);
529  SYNC_DEL(rgbd4Scan2d);
530  SYNC_DEL(rgbd4Scan3d);
531  SYNC_DEL(rgbd4Info);
532  SYNC_DEL(rgbd4Scan2dInfo);
533  SYNC_DEL(rgbd4Scan3dInfo);
534 
535  // 4 RGBD + Odom
536  SYNC_DEL(rgbd4Odom);
537  SYNC_DEL(rgbd4OdomScan2d);
538  SYNC_DEL(rgbd4OdomScan3d);
539  SYNC_DEL(rgbd4OdomInfo);
540  SYNC_DEL(rgbd4OdomScan2dInfo);
541  SYNC_DEL(rgbd4OdomScan3dInfo);
542 
543  // 4 RGBD + User Data
544  SYNC_DEL(rgbd4Data);
545  SYNC_DEL(rgbd4DataScan2d);
546  SYNC_DEL(rgbd4DataScan3d);
547  SYNC_DEL(rgbd4DataInfo);
548  SYNC_DEL(rgbd4DataScan2dInfo);
549  SYNC_DEL(rgbd4DataScan3dInfo);
550 
551  // 4 RGBD + Odom + User Data
552  SYNC_DEL(rgbd4OdomData);
553  SYNC_DEL(rgbd4OdomDataScan2d);
554  SYNC_DEL(rgbd4OdomDataScan3d);
555  SYNC_DEL(rgbd4OdomDataInfo);
556  SYNC_DEL(rgbd4OdomDataScan2dInfo);
557  SYNC_DEL(rgbd4OdomDataScan3dInfo);
558 
559  for(unsigned int i=0; i<rgbdSubs_.size(); ++i)
560  {
561  delete rgbdSubs_[i];
562  }
563  rgbdSubs_.clear();
564 }
565 
567 {
568  ros::Duration r(5.0);
569  while(!callbackCalled_)
570  {
571  r.sleep();
572  if(!callbackCalled_)
573  {
574  ROS_WARN("%s: Did not receive data since 5 seconds! Make sure the input topics are "
575  "published (\"$ rostopic hz my_topic\") and the timestamps in their "
576  "header are set. If topics are coming from different computers, make sure "
577  "the clocks of the computers are synchronized (\"ntpdate\"). %s%s",
578  name_.c_str(),
579  approxSync_?
580  uFormat("If topics are not published at the same rate, you could increase \"queue_size\" parameter (current=%d).", queueSize_).c_str():
581  "Parameter \"approx_sync\" is false, which means that input topics should have all the exact timestamp for the callback to be called.",
582  subscribedTopicsMsg_.c_str());
583  }
584  }
585 }
586 
588  const nav_msgs::OdometryConstPtr & odomMsg,
589  const rtabmap_ros::UserDataConstPtr & userDataMsg,
590  const cv_bridge::CvImageConstPtr & imageMsg,
591  const cv_bridge::CvImageConstPtr & depthMsg,
592  const sensor_msgs::CameraInfo & rgbCameraInfoMsg,
593  const sensor_msgs::CameraInfo & depthCameraInfoMsg,
594  const sensor_msgs::LaserScanConstPtr& scanMsg,
595  const sensor_msgs::PointCloud2ConstPtr& scan3dMsg,
596  const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg)
597 {
598  callbackCalled();
599 
600  if(depthMsg.get() == 0 ||
601  depthMsg->encoding.compare(sensor_msgs::image_encodings::TYPE_16UC1) == 0 ||
602  depthMsg->encoding.compare(sensor_msgs::image_encodings::TYPE_32FC1) == 0 ||
603  depthMsg->encoding.compare(sensor_msgs::image_encodings::MONO16) == 0)
604  {
605  std::vector<cv_bridge::CvImageConstPtr> imageMsgs;
606  std::vector<cv_bridge::CvImageConstPtr> depthMsgs;
607  std::vector<sensor_msgs::CameraInfo> cameraInfoMsgs;
608  if(imageMsg.get())
609  {
610  imageMsgs.push_back(imageMsg);
611  }
612  if(depthMsg.get())
613  {
614  depthMsgs.push_back(depthMsg);
615  }
616  cameraInfoMsgs.push_back(rgbCameraInfoMsg);
617  commonDepthCallback(odomMsg, userDataMsg, imageMsgs, depthMsgs, cameraInfoMsgs, scanMsg, scan3dMsg, odomInfoMsg);
618  }
619  else // assuming stereo
620  {
621  commonStereoCallback(odomMsg, userDataMsg, imageMsg, depthMsg, rgbCameraInfoMsg, depthCameraInfoMsg, scanMsg, scan3dMsg, odomInfoMsg);
622  }
623 
624 
625 }
626 
627 } /* namespace rtabmap_ros */
std::string uFormat(const char *fmt,...)
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::LaserScanConstPtr &scanMsg, const sensor_msgs::PointCloud2ConstPtr &scan3dMsg, const rtabmap_ros::OdomInfoConstPtr &odomInfoMsg)
void setupRGBD2Callbacks(ros::NodeHandle &nh, ros::NodeHandle &pnh, bool subscribeOdom, bool subscribeUserData, bool subscribeScan2d, bool subscribeScan3d, bool subscribeOdomInfo, int queueSize, bool approxSync)
#define SYNC_DEL(PREFIX)
bool sleep() 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::LaserScanConstPtr &scanMsg, const sensor_msgs::PointCloud2ConstPtr &scan3dMsg, const rtabmap_ros::OdomInfoConstPtr &odomInfoMsg)=0
#define ROS_WARN(...)
void setupRGBD3Callbacks(ros::NodeHandle &nh, ros::NodeHandle &pnh, bool subscribeOdom, bool subscribeUserData, bool subscribeScan2d, bool subscribeScan3d, bool subscribeOdomInfo, int queueSize, bool approxSync)
void setupRGBD4Callbacks(ros::NodeHandle &nh, ros::NodeHandle &pnh, bool subscribeOdom, bool subscribeUserData, bool subscribeScan2d, bool subscribeScan3d, bool subscribeOdomInfo, int queueSize, bool approxSync)
void setupRGBDCallbacks(ros::NodeHandle &nh, ros::NodeHandle &pnh, bool subscribeOdom, bool subscribeUserData, bool subscribeScan2d, bool subscribeScan3d, bool subscribeOdomInfo, int queueSize, bool approxSync)
#define true
void setupCallbacks(ros::NodeHandle &nh, ros::NodeHandle &pnh, const std::string &name)
#define ROS_INFO(...)
bool param(const std::string &param_name, T &param_val, const T &default_val) const
const std::string TYPE_32FC1
const std::string TYPE_16UC1
const std::string MONO16
#define false
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::LaserScanConstPtr &scanMsg, const sensor_msgs::PointCloud2ConstPtr &scan3dMsg, const rtabmap_ros::OdomInfoConstPtr &odomInfoMsg)=0
bool getParam(const std::string &key, std::string &s) const
bool hasParam(const std::string &key) const
void setupStereoCallbacks(ros::NodeHandle &nh, ros::NodeHandle &pnh, bool subscribeOdom, bool subscribeOdomInfo, int queueSize, bool approxSync)
r
std::vector< message_filters::Subscriber< rtabmap_ros::RGBDImage > * > rgbdSubs_
#define ROS_ERROR(...)
void setupDepthCallbacks(ros::NodeHandle &nh, ros::NodeHandle &pnh, bool subscribeOdom, bool subscribeUserData, bool subscribeScan2d, bool subscribeScan3d, bool subscribeOdomInfo, int queueSize, bool approxSync)
#define SYNC_INIT(PREFIX)


rtabmap_ros
Author(s): Mathieu Labbe
autogenerated on Fri Jun 7 2019 21:55:03