CommonDataSubscriberScan.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  const sensor_msgs::LaserScanConstPtr& scanMsg)
34 {
36  rtabmap_ros::UserDataConstPtr userDataMsg; // Null
37  nav_msgs::OdometryConstPtr odomMsg; // Null
38  sensor_msgs::PointCloud2 scan3dMsg; // Null
39  rtabmap_ros::OdomInfoConstPtr odomInfoMsg; // null
40  commonLaserScanCallback(odomMsg, userDataMsg, *scanMsg, scan3dMsg, odomInfoMsg);
41 }
43  const sensor_msgs::PointCloud2ConstPtr& scanMsg)
44 {
46  rtabmap_ros::UserDataConstPtr userDataMsg; // Null
47  nav_msgs::OdometryConstPtr odomMsg; // Null
48  sensor_msgs::LaserScan scan2dMsg; // Null
49  rtabmap_ros::OdomInfoConstPtr odomInfoMsg; // null
50  commonLaserScanCallback(odomMsg, userDataMsg, scan2dMsg, *scanMsg, odomInfoMsg);
51 }
53  const rtabmap_ros::ScanDescriptorConstPtr& scanMsg)
54 {
56  rtabmap_ros::UserDataConstPtr userDataMsg; // Null
57  nav_msgs::OdometryConstPtr odomMsg; // Null
58  rtabmap_ros::OdomInfoConstPtr odomInfoMsg; // null
59  commonLaserScanCallback(odomMsg, userDataMsg, scanMsg->scan, scanMsg->scan_cloud, odomInfoMsg, scanMsg->global_descriptor);
60 }
61 void CommonDataSubscriber::scan2dInfoCallback(
62  const sensor_msgs::LaserScanConstPtr& scanMsg,
63  const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg)
64 {
66  rtabmap_ros::UserDataConstPtr userDataMsg; // Null
67  nav_msgs::OdometryConstPtr odomMsg; // Null
68  sensor_msgs::PointCloud2 scan3dMsg; // Null
69  commonLaserScanCallback(odomMsg, userDataMsg, *scanMsg, scan3dMsg, odomInfoMsg);
70 }
71 void CommonDataSubscriber::scan3dInfoCallback(
72  const sensor_msgs::PointCloud2ConstPtr& scanMsg,
73  const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg)
74 {
76  rtabmap_ros::UserDataConstPtr userDataMsg; // Null
77  nav_msgs::OdometryConstPtr odomMsg; // Null
78  sensor_msgs::LaserScan scan2dMsg; // Null
79  commonLaserScanCallback(odomMsg, userDataMsg, scan2dMsg, *scanMsg, odomInfoMsg);
80 }
81 void CommonDataSubscriber::scanDescInfoCallback(
82  const rtabmap_ros::ScanDescriptorConstPtr& scanMsg,
83  const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg)
84 {
86  rtabmap_ros::UserDataConstPtr userDataMsg; // Null
87  nav_msgs::OdometryConstPtr odomMsg; // Null
88  commonLaserScanCallback(odomMsg, userDataMsg, scanMsg->scan, scanMsg->scan_cloud, odomInfoMsg, scanMsg->global_descriptor);
89 }
90 
91 void CommonDataSubscriber::odomScan2dCallback(
92  const nav_msgs::OdometryConstPtr & odomMsg,
93  const sensor_msgs::LaserScanConstPtr& scanMsg)
94 {
96  rtabmap_ros::UserDataConstPtr userDataMsg; // Null
97  sensor_msgs::PointCloud2 scan3dMsg; // Null
98  rtabmap_ros::OdomInfoConstPtr odomInfoMsg; // null
99  commonLaserScanCallback(odomMsg, userDataMsg, *scanMsg, scan3dMsg, odomInfoMsg);
100 }
101 void CommonDataSubscriber::odomScan3dCallback(
102  const nav_msgs::OdometryConstPtr & odomMsg,
103  const sensor_msgs::PointCloud2ConstPtr& scanMsg)
104 {
105  callbackCalled();
106  rtabmap_ros::UserDataConstPtr userDataMsg; // Null
107  sensor_msgs::LaserScan scan2dMsg; // Null
108  rtabmap_ros::OdomInfoConstPtr odomInfoMsg; // null
109  commonLaserScanCallback(odomMsg, userDataMsg, scan2dMsg, *scanMsg, odomInfoMsg);
110 }
111 void CommonDataSubscriber::odomScanDescCallback(
112  const nav_msgs::OdometryConstPtr & odomMsg,
113  const rtabmap_ros::ScanDescriptorConstPtr& scanMsg)
114 {
115  callbackCalled();
116  rtabmap_ros::UserDataConstPtr userDataMsg; // Null
117  rtabmap_ros::OdomInfoConstPtr odomInfoMsg; // null
118  commonLaserScanCallback(odomMsg, userDataMsg, scanMsg->scan, scanMsg->scan_cloud, odomInfoMsg, scanMsg->global_descriptor);
119 }
120 void CommonDataSubscriber::odomScan2dInfoCallback(
121  const nav_msgs::OdometryConstPtr & odomMsg,
122  const sensor_msgs::LaserScanConstPtr& scanMsg,
123  const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg)
124 {
125  callbackCalled();
126  rtabmap_ros::UserDataConstPtr userDataMsg; // Null
127  sensor_msgs::PointCloud2 scan3dMsg; // Null
128  commonLaserScanCallback(odomMsg, userDataMsg, *scanMsg, scan3dMsg, odomInfoMsg);
129 }
130 void CommonDataSubscriber::odomScan3dInfoCallback(
131  const nav_msgs::OdometryConstPtr & odomMsg,
132  const sensor_msgs::PointCloud2ConstPtr& scanMsg,
133  const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg)
134 {
135  callbackCalled();
136  rtabmap_ros::UserDataConstPtr userDataMsg; // Null
137  sensor_msgs::LaserScan scan2dMsg; // Null
138  commonLaserScanCallback(odomMsg, userDataMsg, scan2dMsg, *scanMsg, odomInfoMsg);
139 }
140 void CommonDataSubscriber::odomScanDescInfoCallback(
141  const nav_msgs::OdometryConstPtr & odomMsg,
142  const rtabmap_ros::ScanDescriptorConstPtr& scanMsg,
143  const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg)
144 {
145  callbackCalled();
146  rtabmap_ros::UserDataConstPtr userDataMsg; // Null
147  commonLaserScanCallback(odomMsg, userDataMsg, scanMsg->scan, scanMsg->scan_cloud, odomInfoMsg, scanMsg->global_descriptor);
148 }
149 
150 #ifdef RTABMAP_SYNC_USER_DATA
151 void CommonDataSubscriber::dataScan2dCallback(
152  const rtabmap_ros::UserDataConstPtr & userDataMsg,
153  const sensor_msgs::LaserScanConstPtr& scanMsg)
154 {
155  callbackCalled();
156  nav_msgs::OdometryConstPtr odomMsg; // null
157  sensor_msgs::PointCloud2 scan3dMsg; // Null
158  rtabmap_ros::OdomInfoConstPtr odomInfoMsg; // null
159  commonLaserScanCallback(odomMsg, userDataMsg, *scanMsg, scan3dMsg, odomInfoMsg);
160 }
161 void CommonDataSubscriber::dataScan3dCallback(
162  const rtabmap_ros::UserDataConstPtr & userDataMsg,
163  const sensor_msgs::PointCloud2ConstPtr& scanMsg)
164 {
165  callbackCalled();
166  nav_msgs::OdometryConstPtr odomMsg; // null
167  sensor_msgs::LaserScan scan2dMsg; // Null
168  rtabmap_ros::OdomInfoConstPtr odomInfoMsg; // null
169  commonLaserScanCallback(odomMsg, userDataMsg, scan2dMsg, *scanMsg, odomInfoMsg);
170 }
171 void CommonDataSubscriber::dataScanDescCallback(
172  const rtabmap_ros::UserDataConstPtr & userDataMsg,
173  const rtabmap_ros::ScanDescriptorConstPtr& scanMsg)
174 {
175  callbackCalled();
176  nav_msgs::OdometryConstPtr odomMsg; // null
177  rtabmap_ros::OdomInfoConstPtr odomInfoMsg; // null
178  commonLaserScanCallback(odomMsg, userDataMsg, scanMsg->scan, scanMsg->scan_cloud, odomInfoMsg, scanMsg->global_descriptor);
179 }
180 void CommonDataSubscriber::dataScan2dInfoCallback(
181  const rtabmap_ros::UserDataConstPtr & userDataMsg,
182  const sensor_msgs::LaserScanConstPtr& scanMsg,
183  const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg)
184 {
185  callbackCalled();
186  nav_msgs::OdometryConstPtr odomMsg; // null
187  sensor_msgs::PointCloud2 scan3dMsg; // Null
188  commonLaserScanCallback(odomMsg, userDataMsg, *scanMsg, scan3dMsg, odomInfoMsg);
189 }
190 void CommonDataSubscriber::dataScan3dInfoCallback(
191  const rtabmap_ros::UserDataConstPtr & userDataMsg,
192  const sensor_msgs::PointCloud2ConstPtr& scanMsg,
193  const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg)
194 {
195  callbackCalled();
196  nav_msgs::OdometryConstPtr odomMsg; // null
197  sensor_msgs::LaserScan scan2dMsg; // Null
198  commonLaserScanCallback(odomMsg, userDataMsg, scan2dMsg, *scanMsg, odomInfoMsg);
199 }
200 void CommonDataSubscriber::dataScanDescInfoCallback(
201  const rtabmap_ros::UserDataConstPtr & userDataMsg,
202  const rtabmap_ros::ScanDescriptorConstPtr& scanMsg,
203  const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg)
204 {
205  callbackCalled();
206  nav_msgs::OdometryConstPtr odomMsg; // null
207  commonLaserScanCallback(odomMsg, userDataMsg, scanMsg->scan, scanMsg->scan_cloud, odomInfoMsg, scanMsg->global_descriptor);
208 }
209 
210 void CommonDataSubscriber::odomDataScan2dCallback(
211  const nav_msgs::OdometryConstPtr & odomMsg,
212  const rtabmap_ros::UserDataConstPtr & userDataMsg,
213  const sensor_msgs::LaserScanConstPtr& scanMsg)
214 {
215  callbackCalled();
216  sensor_msgs::PointCloud2 scan3dMsg; // Null
217  rtabmap_ros::OdomInfoConstPtr odomInfoMsg; // null
218  commonLaserScanCallback(odomMsg, userDataMsg, *scanMsg, scan3dMsg, odomInfoMsg);
219 }
220 void CommonDataSubscriber::odomDataScan3dCallback(
221  const nav_msgs::OdometryConstPtr & odomMsg,
222  const rtabmap_ros::UserDataConstPtr & userDataMsg,
223  const sensor_msgs::PointCloud2ConstPtr& scanMsg)
224 {
225  callbackCalled();
226  sensor_msgs::LaserScan scan2dMsg; // Null
227  rtabmap_ros::OdomInfoConstPtr odomInfoMsg; // null
228  commonLaserScanCallback(odomMsg, userDataMsg, scan2dMsg, *scanMsg, odomInfoMsg);
229 }
230 void CommonDataSubscriber::odomDataScanDescCallback(
231  const nav_msgs::OdometryConstPtr & odomMsg,
232  const rtabmap_ros::UserDataConstPtr & userDataMsg,
233  const rtabmap_ros::ScanDescriptorConstPtr& scanMsg)
234 {
235  callbackCalled();
236  rtabmap_ros::OdomInfoConstPtr odomInfoMsg; // null
237  commonLaserScanCallback(odomMsg, userDataMsg, scanMsg->scan, scanMsg->scan_cloud, odomInfoMsg, scanMsg->global_descriptor);
238 }
239 void CommonDataSubscriber::odomDataScan2dInfoCallback(
240  const nav_msgs::OdometryConstPtr & odomMsg,
241  const rtabmap_ros::UserDataConstPtr & userDataMsg,
242  const sensor_msgs::LaserScanConstPtr& scanMsg,
243  const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg)
244 {
245  callbackCalled();
246  sensor_msgs::PointCloud2 scan3dMsg; // Null
247  commonLaserScanCallback(odomMsg, userDataMsg, *scanMsg, scan3dMsg, odomInfoMsg);
248 }
249 void CommonDataSubscriber::odomDataScan3dInfoCallback(
250  const nav_msgs::OdometryConstPtr & odomMsg,
251  const rtabmap_ros::UserDataConstPtr & userDataMsg,
252  const sensor_msgs::PointCloud2ConstPtr& scanMsg,
253  const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg)
254 {
255  callbackCalled();
256  sensor_msgs::LaserScan scan2dMsg; // Null
257  commonLaserScanCallback(odomMsg, userDataMsg, scan2dMsg, *scanMsg, odomInfoMsg);
258 }
259 void CommonDataSubscriber::odomDataScanDescInfoCallback(
260  const nav_msgs::OdometryConstPtr & odomMsg,
261  const rtabmap_ros::UserDataConstPtr & userDataMsg,
262  const rtabmap_ros::ScanDescriptorConstPtr& scanMsg,
263  const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg)
264 {
265  callbackCalled();
266  commonLaserScanCallback(odomMsg, userDataMsg, scanMsg->scan, scanMsg->scan_cloud, odomInfoMsg, scanMsg->global_descriptor);
267 }
268 #endif
269 
271  ros::NodeHandle & nh,
272  ros::NodeHandle & pnh,
273  bool scan2dTopic,
274  bool scanDescTopic,
275  bool subscribeOdom,
276  bool subscribeUserData,
277  bool subscribeOdomInfo,
278  int queueSize,
279  bool approxSync)
280 {
281  ROS_INFO("Setup scan callback");
282 
283  if(subscribeOdom || subscribeUserData || subscribeOdomInfo)
284  {
285  if(scanDescTopic)
286  {
288  scanDescSub_.subscribe(nh, "scan_descriptor", queueSize);
289  }
290  else if(scan2dTopic)
291  {
292  subscribedToScan2d_ = true;
293  scanSub_.subscribe(nh, "scan", queueSize);
294  }
295  else
296  {
297  subscribedToScan3d_ = true;
298  scan3dSub_.subscribe(nh, "scan_cloud", queueSize);
299  }
300 
301 #ifdef RTABMAP_SYNC_USER_DATA
302  if(subscribeOdom && subscribeUserData)
303  {
304  odomSub_.subscribe(nh, "odom", queueSize);
305  userDataSub_.subscribe(nh, "user_data", queueSize);
306 
307  if(scanDescTopic)
308  {
309  if(subscribeOdomInfo)
310  {
311  subscribedToOdomInfo_ = true;
312  odomInfoSub_.subscribe(nh, "odom_info", queueSize);
313  SYNC_DECL4(odomDataScanDescInfo, approxSync, queueSize, odomSub_, userDataSub_, scanDescSub_, odomInfoSub_);
314  }
315  else
316  {
317  SYNC_DECL3(odomDataScanDesc, approxSync, queueSize, odomSub_, userDataSub_, scanDescSub_);
318  }
319  }
320  else if(scan2dTopic)
321  {
322  if(subscribeOdomInfo)
323  {
324  subscribedToOdomInfo_ = true;
325  odomInfoSub_.subscribe(nh, "odom_info", queueSize);
326  SYNC_DECL4(odomDataScan2dInfo, approxSync, queueSize, odomSub_, userDataSub_, scanSub_, odomInfoSub_);
327  }
328  else
329  {
330  SYNC_DECL3(odomDataScan2d, approxSync, queueSize, odomSub_, userDataSub_, scanSub_);
331  }
332  }
333  else
334  {
335  if(subscribeOdomInfo)
336  {
337  subscribedToOdomInfo_ = true;
338  odomInfoSub_.subscribe(nh, "odom_info", queueSize);
339  SYNC_DECL4(odomDataScan3dInfo, approxSync, queueSize, odomSub_, userDataSub_, scan3dSub_, odomInfoSub_);
340  }
341  else
342  {
343  SYNC_DECL3(odomDataScan3d, approxSync, queueSize, odomSub_, userDataSub_, scan3dSub_);
344  }
345  }
346  }
347  else
348 #endif
349  if(subscribeOdom)
350  {
351  odomSub_.subscribe(nh, "odom", queueSize);
352 
353  if(scanDescTopic)
354  {
355  if(subscribeOdomInfo)
356  {
357  subscribedToOdomInfo_ = true;
358  odomInfoSub_.subscribe(nh, "odom_info", queueSize);
359  SYNC_DECL3(odomScanDescInfo, approxSync, queueSize, odomSub_, scanDescSub_, odomInfoSub_);
360  }
361  else
362  {
363  SYNC_DECL2(odomScanDesc, approxSync, queueSize, odomSub_, scanDescSub_);
364  }
365  }
366  else if(scan2dTopic)
367  {
368  if(subscribeOdomInfo)
369  {
370  subscribedToOdomInfo_ = true;
371  odomInfoSub_.subscribe(nh, "odom_info", queueSize);
372  SYNC_DECL3(odomScan2dInfo, approxSync, queueSize, odomSub_, scanSub_, odomInfoSub_);
373  }
374  else
375  {
376  SYNC_DECL2(odomScan2d, approxSync, queueSize, odomSub_, scanSub_);
377  }
378  }
379  else
380  {
381  if(subscribeOdomInfo)
382  {
383  subscribedToOdomInfo_ = true;
384  odomInfoSub_.subscribe(nh, "odom_info", queueSize);
385  SYNC_DECL3(odomScan3dInfo, approxSync, queueSize, odomSub_, scan3dSub_, odomInfoSub_);
386  }
387  else
388  {
389  SYNC_DECL2(odomScan3d, approxSync, queueSize, odomSub_, scan3dSub_);
390  }
391  }
392  }
393 #ifdef RTABMAP_SYNC_USER_DATA
394  else if(subscribeUserData)
395  {
396  userDataSub_.subscribe(nh, "user_data", queueSize);
397 
398  if(scanDescTopic)
399  {
400  if(subscribeOdomInfo)
401  {
402  subscribedToOdomInfo_ = true;
403  odomInfoSub_.subscribe(nh, "odom_info", queueSize);
404  SYNC_DECL3(dataScanDescInfo, approxSync, queueSize, userDataSub_, scanDescSub_, odomInfoSub_);
405  }
406  else
407  {
408  SYNC_DECL2(dataScanDesc, approxSync, queueSize, userDataSub_, scanDescSub_);
409  }
410  }
411  else if(scan2dTopic)
412  {
413  if(subscribeOdomInfo)
414  {
415  subscribedToOdomInfo_ = true;
416  odomInfoSub_.subscribe(nh, "odom_info", queueSize);
417  SYNC_DECL3(dataScan2dInfo, approxSync, queueSize, userDataSub_, scanSub_, odomInfoSub_);
418  }
419  else
420  {
421  SYNC_DECL2(dataScan2d, approxSync, queueSize, userDataSub_, scanSub_);
422  }
423  }
424  else
425  {
426  if(subscribeOdomInfo)
427  {
428  subscribedToOdomInfo_ = true;
429  odomInfoSub_.subscribe(nh, "odom_info", queueSize);
430  SYNC_DECL3(dataScan3dInfo, approxSync, queueSize, userDataSub_, scan3dSub_, odomInfoSub_);
431  }
432  else
433  {
434  SYNC_DECL2(dataScan3d, approxSync, queueSize, userDataSub_, scan3dSub_);
435  }
436  }
437  }
438 #endif
439  else if(subscribeOdomInfo)
440  {
441  subscribedToOdomInfo_ = true;
442  odomInfoSub_.subscribe(nh, "odom_info", queueSize);
443  if(scanDescTopic)
444  {
445  SYNC_DECL2(scanDescInfo, approxSync, queueSize, scanDescSub_, odomInfoSub_);
446  }
447  else if(scan2dTopic)
448  {
449  SYNC_DECL2(scan2dInfo, approxSync, queueSize, scanSub_, odomInfoSub_);
450  }
451  else
452  {
453  SYNC_DECL2(scan3dInfo, approxSync, queueSize, scan3dSub_, odomInfoSub_);
454  }
455  }
456  }
457  else
458  {
459  if(scanDescTopic)
460  {
462  scanDescSubOnly_ = nh.subscribe("scan_descriptor", queueSize, &CommonDataSubscriber::scanDescCallback, this);
464  uFormat("\n%s subscribed to:\n %s",
465  ros::this_node::getName().c_str(),
466  scanDescSubOnly_.getTopic().c_str());
467  }
468  else if(scan2dTopic)
469  {
470  subscribedToScan2d_ = true;
471  scan2dSubOnly_ = nh.subscribe("scan", queueSize, &CommonDataSubscriber::scan2dCallback, this);
473  uFormat("\n%s subscribed to:\n %s",
474  ros::this_node::getName().c_str(),
475  scan2dSubOnly_.getTopic().c_str());
476  }
477  else
478  {
479  subscribedToScan3d_ = true;
480  scan3dSubOnly_ = nh.subscribe("scan_cloud", queueSize, &CommonDataSubscriber::scan3dCallback, this);
482  uFormat("\n%s subscribed to:\n %s",
483  ros::this_node::getName().c_str(),
484  scan3dSubOnly_.getTopic().c_str());
485  }
486  }
487 }
488 
489 } /* namespace rtabmap_ros */
std::string uFormat(const char *fmt,...)
void scanDescCallback(const rtabmap_ros::ScanDescriptorConstPtr &)
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
ROSCPP_DECL const std::string & getName()
#define SYNC_DECL3(PREFIX, APPROX, QUEUE_SIZE, SUB0, SUB1, SUB2)
message_filters::Subscriber< rtabmap_ros::UserData > userDataSub_
message_filters::Subscriber< rtabmap_ros::OdomInfo > odomInfoSub_
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 setupScanCallbacks(ros::NodeHandle &nh, ros::NodeHandle &pnh, bool subscribeScan2d, bool subscribeScanDesc, bool subscribeOdom, bool subscribeUserData, bool subscribeOdomInfo, int queueSize, bool approxSync)
void scan3dCallback(const sensor_msgs::PointCloud2ConstPtr &)
#define ROS_INFO(...)
void scan2dCallback(const sensor_msgs::LaserScanConstPtr &)
std::string getTopic() const
#define SYNC_DECL2(PREFIX, APPROX, QUEUE_SIZE, SUB0, SUB1)
message_filters::Subscriber< sensor_msgs::LaserScan > scanSub_
message_filters::Subscriber< rtabmap_ros::ScanDescriptor > scanDescSub_
#define SYNC_DECL4(PREFIX, APPROX, QUEUE_SIZE, SUB0, SUB1, SUB2, SUB3)
message_filters::Subscriber< nav_msgs::Odometry > odomSub_
message_filters::Subscriber< sensor_msgs::PointCloud2 > scan3dSub_
void subscribe(ros::NodeHandle &nh, const std::string &topic, uint32_t queue_size, const ros::TransportHints &transport_hints=ros::TransportHints(), ros::CallbackQueueInterface *callback_queue=0)


rtabmap_ros
Author(s): Mathieu Labbe
autogenerated on Mon Dec 14 2020 03:42:18