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


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