CommonDataSubscriberDepth.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 
32 // RGB + Depth
33 void CommonDataSubscriber::depthCallback(
34  const sensor_msgs::ImageConstPtr& imageMsg,
35  const sensor_msgs::ImageConstPtr& depthMsg,
36  const sensor_msgs::CameraInfoConstPtr& cameraInfoMsg)
37 {
38  rtabmap_ros::UserDataConstPtr userDataMsg; // Null
39  nav_msgs::OdometryConstPtr odomMsg; // Null
40  sensor_msgs::LaserScan scanMsg; // Null
41  sensor_msgs::PointCloud2 scan3dMsg; // Null
42  rtabmap_ros::OdomInfoConstPtr odomInfoMsg; // null
43  commonSingleCameraCallback(odomMsg, userDataMsg, cv_bridge::toCvShare(imageMsg), cv_bridge::toCvShare(depthMsg), *cameraInfoMsg, *cameraInfoMsg, scanMsg, scan3dMsg, odomInfoMsg);
44 }
45 void CommonDataSubscriber::depthScan2dCallback(
46  const sensor_msgs::ImageConstPtr& imageMsg,
47  const sensor_msgs::ImageConstPtr& depthMsg,
48  const sensor_msgs::CameraInfoConstPtr& cameraInfoMsg,
49  const sensor_msgs::LaserScanConstPtr& scanMsg)
50 {
51  rtabmap_ros::UserDataConstPtr userDataMsg; // Null
52  nav_msgs::OdometryConstPtr odomMsg; // Null
53  sensor_msgs::PointCloud2 scan3dMsg; // Null
54  rtabmap_ros::OdomInfoConstPtr odomInfoMsg; // null
55  commonSingleCameraCallback(odomMsg, userDataMsg, cv_bridge::toCvShare(imageMsg), cv_bridge::toCvShare(depthMsg), *cameraInfoMsg, *cameraInfoMsg, *scanMsg, scan3dMsg, odomInfoMsg);
56 }
57 void CommonDataSubscriber::depthScan3dCallback(
58  const sensor_msgs::ImageConstPtr& imageMsg,
59  const sensor_msgs::ImageConstPtr& depthMsg,
60  const sensor_msgs::CameraInfoConstPtr& cameraInfoMsg,
61  const sensor_msgs::PointCloud2ConstPtr& scanMsg)
62 {
63  rtabmap_ros::UserDataConstPtr userDataMsg; // Null
64  nav_msgs::OdometryConstPtr odomMsg; // Null
65  sensor_msgs::LaserScan scan2dMsg; // Null
66  rtabmap_ros::OdomInfoConstPtr odomInfoMsg; // null
67  commonSingleCameraCallback(odomMsg, userDataMsg, cv_bridge::toCvShare(imageMsg), cv_bridge::toCvShare(depthMsg), *cameraInfoMsg, *cameraInfoMsg, scan2dMsg, *scanMsg, odomInfoMsg);
68 }
69 void CommonDataSubscriber::depthScanDescCallback(
70  const sensor_msgs::ImageConstPtr& imageMsg,
71  const sensor_msgs::ImageConstPtr& depthMsg,
72  const sensor_msgs::CameraInfoConstPtr& cameraInfoMsg,
73  const rtabmap_ros::ScanDescriptorConstPtr& scanMsg)
74 {
75  rtabmap_ros::UserDataConstPtr userDataMsg; // Null
76  nav_msgs::OdometryConstPtr odomMsg; // Null
77  rtabmap_ros::OdomInfoConstPtr odomInfoMsg; // null
78  std::vector<rtabmap_ros::GlobalDescriptor> globalDescriptor;
79  if(!scanMsg->global_descriptor.data.empty())
80  {
81  globalDescriptor.push_back(scanMsg->global_descriptor);
82  }
83  commonSingleCameraCallback(odomMsg, userDataMsg, cv_bridge::toCvShare(imageMsg), cv_bridge::toCvShare(depthMsg), *cameraInfoMsg, *cameraInfoMsg, scanMsg->scan, scanMsg->scan_cloud, odomInfoMsg, globalDescriptor);
84 }
85 void CommonDataSubscriber::depthInfoCallback(
86  const sensor_msgs::ImageConstPtr& imageMsg,
87  const sensor_msgs::ImageConstPtr& depthMsg,
88  const sensor_msgs::CameraInfoConstPtr& cameraInfoMsg,
89  const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg)
90 {
91  rtabmap_ros::UserDataConstPtr userDataMsg; // Null
92  nav_msgs::OdometryConstPtr odomMsg; // Null
93  sensor_msgs::LaserScan scan2dMsg; // Null
94  sensor_msgs::PointCloud2 scan3dMsg; // Null
95  commonSingleCameraCallback(odomMsg, userDataMsg, cv_bridge::toCvShare(imageMsg), cv_bridge::toCvShare(depthMsg), *cameraInfoMsg, *cameraInfoMsg, scan2dMsg, scan3dMsg, odomInfoMsg);
96 }
97 void CommonDataSubscriber::depthScan2dInfoCallback(
98  const sensor_msgs::ImageConstPtr& imageMsg,
99  const sensor_msgs::ImageConstPtr& depthMsg,
100  const sensor_msgs::CameraInfoConstPtr& cameraInfoMsg,
101  const sensor_msgs::LaserScanConstPtr& scanMsg,
102  const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg)
103 {
104  rtabmap_ros::UserDataConstPtr userDataMsg; // Null
105  nav_msgs::OdometryConstPtr odomMsg; // Null
106  sensor_msgs::PointCloud2 scan3dMsg; // Null
107  commonSingleCameraCallback(odomMsg, userDataMsg, cv_bridge::toCvShare(imageMsg), cv_bridge::toCvShare(depthMsg), *cameraInfoMsg, *cameraInfoMsg, *scanMsg, scan3dMsg, odomInfoMsg);
108 }
109 void CommonDataSubscriber::depthScan3dInfoCallback(
110  const sensor_msgs::ImageConstPtr& imageMsg,
111  const sensor_msgs::ImageConstPtr& depthMsg,
112  const sensor_msgs::CameraInfoConstPtr& cameraInfoMsg,
113  const sensor_msgs::PointCloud2ConstPtr& scanMsg,
114  const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg)
115 {
116  rtabmap_ros::UserDataConstPtr userDataMsg; // Null
117  nav_msgs::OdometryConstPtr odomMsg; // Null
118  sensor_msgs::LaserScan scan2dMsg; // Null
119  commonSingleCameraCallback(odomMsg, userDataMsg, cv_bridge::toCvShare(imageMsg), cv_bridge::toCvShare(depthMsg), *cameraInfoMsg, *cameraInfoMsg, scan2dMsg, *scanMsg, odomInfoMsg);
120 }
121 void CommonDataSubscriber::depthScanDescInfoCallback(
122  const sensor_msgs::ImageConstPtr& imageMsg,
123  const sensor_msgs::ImageConstPtr& depthMsg,
124  const sensor_msgs::CameraInfoConstPtr& cameraInfoMsg,
125  const rtabmap_ros::ScanDescriptorConstPtr& scanMsg,
126  const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg)
127 {
128  rtabmap_ros::UserDataConstPtr userDataMsg; // Null
129  nav_msgs::OdometryConstPtr odomMsg; // Null
130  std::vector<rtabmap_ros::GlobalDescriptor> globalDescriptor;
131  if(!scanMsg->global_descriptor.data.empty())
132  {
133  globalDescriptor.push_back(scanMsg->global_descriptor);
134  }
135  commonSingleCameraCallback(odomMsg, userDataMsg, cv_bridge::toCvShare(imageMsg), cv_bridge::toCvShare(depthMsg), *cameraInfoMsg, *cameraInfoMsg, scanMsg->scan, scanMsg->scan_cloud, odomInfoMsg, globalDescriptor);
136 }
137 
138 // RGB + Depth + Odom
139 void CommonDataSubscriber::depthOdomCallback(
140  const nav_msgs::OdometryConstPtr & odomMsg,
141  const sensor_msgs::ImageConstPtr& imageMsg,
142  const sensor_msgs::ImageConstPtr& depthMsg,
143  const sensor_msgs::CameraInfoConstPtr& cameraInfoMsg)
144 {
145  rtabmap_ros::UserDataConstPtr userDataMsg; // Null
146  sensor_msgs::LaserScan scanMsg; // Null
147  sensor_msgs::PointCloud2 scan3dMsg; // null
148  rtabmap_ros::OdomInfoConstPtr odomInfoMsg; // null
149  commonSingleCameraCallback(odomMsg, userDataMsg, cv_bridge::toCvShare(imageMsg), cv_bridge::toCvShare(depthMsg), *cameraInfoMsg, *cameraInfoMsg, scanMsg, scan3dMsg, odomInfoMsg);
150 }
151 void CommonDataSubscriber::depthOdomScan2dCallback(
152  const nav_msgs::OdometryConstPtr & odomMsg,
153  const sensor_msgs::ImageConstPtr& imageMsg,
154  const sensor_msgs::ImageConstPtr& depthMsg,
155  const sensor_msgs::CameraInfoConstPtr& cameraInfoMsg,
156  const sensor_msgs::LaserScanConstPtr& scanMsg)
157 {
158  rtabmap_ros::UserDataConstPtr userDataMsg; // Null
159  sensor_msgs::PointCloud2 scan3dMsg; // Null
160  rtabmap_ros::OdomInfoConstPtr odomInfoMsg; // null
161  commonSingleCameraCallback(odomMsg, userDataMsg, cv_bridge::toCvShare(imageMsg), cv_bridge::toCvShare(depthMsg), *cameraInfoMsg, *cameraInfoMsg, *scanMsg, scan3dMsg, odomInfoMsg);
162 }
163 void CommonDataSubscriber::depthOdomScan3dCallback(
164  const nav_msgs::OdometryConstPtr & odomMsg,
165  const sensor_msgs::ImageConstPtr& imageMsg,
166  const sensor_msgs::ImageConstPtr& depthMsg,
167  const sensor_msgs::CameraInfoConstPtr& cameraInfoMsg,
168  const sensor_msgs::PointCloud2ConstPtr& scanMsg)
169 {
170  rtabmap_ros::UserDataConstPtr userDataMsg; // Null
171  sensor_msgs::LaserScan scan2dMsg; // Null
172  rtabmap_ros::OdomInfoConstPtr odomInfoMsg; // null
173  commonSingleCameraCallback(odomMsg, userDataMsg, cv_bridge::toCvShare(imageMsg), cv_bridge::toCvShare(depthMsg), *cameraInfoMsg, *cameraInfoMsg, scan2dMsg, *scanMsg, odomInfoMsg);
174 }
175 void CommonDataSubscriber::depthOdomScanDescCallback(
176  const nav_msgs::OdometryConstPtr & odomMsg,
177  const sensor_msgs::ImageConstPtr& imageMsg,
178  const sensor_msgs::ImageConstPtr& depthMsg,
179  const sensor_msgs::CameraInfoConstPtr& cameraInfoMsg,
180  const rtabmap_ros::ScanDescriptorConstPtr& scanMsg)
181 {
182  rtabmap_ros::UserDataConstPtr userDataMsg; // Null
183  rtabmap_ros::OdomInfoConstPtr odomInfoMsg; // null
184  std::vector<rtabmap_ros::GlobalDescriptor> globalDescriptor;
185  if(!scanMsg->global_descriptor.data.empty())
186  {
187  globalDescriptor.push_back(scanMsg->global_descriptor);
188  }
189  commonSingleCameraCallback(odomMsg, userDataMsg, cv_bridge::toCvShare(imageMsg), cv_bridge::toCvShare(depthMsg), *cameraInfoMsg, *cameraInfoMsg, scanMsg->scan, scanMsg->scan_cloud, odomInfoMsg, globalDescriptor);
190 }
191 void CommonDataSubscriber::depthOdomInfoCallback(
192  const nav_msgs::OdometryConstPtr & odomMsg,
193  const sensor_msgs::ImageConstPtr& imageMsg,
194  const sensor_msgs::ImageConstPtr& depthMsg,
195  const sensor_msgs::CameraInfoConstPtr& cameraInfoMsg,
196  const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg)
197 {
198  rtabmap_ros::UserDataConstPtr userDataMsg; // Null
199  sensor_msgs::LaserScan scan2dMsg; // Null
200  sensor_msgs::PointCloud2 scan3dMsg; // Null
201  commonSingleCameraCallback(odomMsg, userDataMsg, cv_bridge::toCvShare(imageMsg), cv_bridge::toCvShare(depthMsg), *cameraInfoMsg, *cameraInfoMsg, scan2dMsg, scan3dMsg, odomInfoMsg);
202 }
203 void CommonDataSubscriber::depthOdomScan2dInfoCallback(
204  const nav_msgs::OdometryConstPtr & odomMsg,
205  const sensor_msgs::ImageConstPtr& imageMsg,
206  const sensor_msgs::ImageConstPtr& depthMsg,
207  const sensor_msgs::CameraInfoConstPtr& cameraInfoMsg,
208  const sensor_msgs::LaserScanConstPtr& scanMsg,
209  const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg)
210 {
211  rtabmap_ros::UserDataConstPtr userDataMsg; // Null
212  sensor_msgs::PointCloud2 scan3dMsg; // Null
213  commonSingleCameraCallback(odomMsg, userDataMsg, cv_bridge::toCvShare(imageMsg), cv_bridge::toCvShare(depthMsg), *cameraInfoMsg, *cameraInfoMsg, *scanMsg, scan3dMsg, odomInfoMsg);
214 }
215 void CommonDataSubscriber::depthOdomScan3dInfoCallback(
216  const nav_msgs::OdometryConstPtr & odomMsg,
217  const sensor_msgs::ImageConstPtr& imageMsg,
218  const sensor_msgs::ImageConstPtr& depthMsg,
219  const sensor_msgs::CameraInfoConstPtr& cameraInfoMsg,
220  const sensor_msgs::PointCloud2ConstPtr& scanMsg,
221  const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg)
222 {
223  rtabmap_ros::UserDataConstPtr userDataMsg; // Null
224  sensor_msgs::LaserScan scan2dMsg; // Null
225  commonSingleCameraCallback(odomMsg, userDataMsg, cv_bridge::toCvShare(imageMsg), cv_bridge::toCvShare(depthMsg), *cameraInfoMsg, *cameraInfoMsg, scan2dMsg, *scanMsg, odomInfoMsg);
226 }
227 void CommonDataSubscriber::depthOdomScanDescInfoCallback(
228  const nav_msgs::OdometryConstPtr & odomMsg,
229  const sensor_msgs::ImageConstPtr& imageMsg,
230  const sensor_msgs::ImageConstPtr& depthMsg,
231  const sensor_msgs::CameraInfoConstPtr& cameraInfoMsg,
232  const rtabmap_ros::ScanDescriptorConstPtr& scanMsg,
233  const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg)
234 {
235  rtabmap_ros::UserDataConstPtr userDataMsg; // Null
236  std::vector<rtabmap_ros::GlobalDescriptor> globalDescriptor;
237  if(!scanMsg->global_descriptor.data.empty())
238  {
239  globalDescriptor.push_back(scanMsg->global_descriptor);
240  }
241  commonSingleCameraCallback(odomMsg, userDataMsg, cv_bridge::toCvShare(imageMsg), cv_bridge::toCvShare(depthMsg), *cameraInfoMsg, *cameraInfoMsg, scanMsg->scan, scanMsg->scan_cloud, odomInfoMsg, globalDescriptor);
242 }
243 
244 #ifdef RTABMAP_SYNC_USER_DATA
245 // RGB + Depth + User Data
246 void CommonDataSubscriber::depthDataCallback(
247  const rtabmap_ros::UserDataConstPtr & userDataMsg,
248  const sensor_msgs::ImageConstPtr& imageMsg,
249  const sensor_msgs::ImageConstPtr& depthMsg,
250  const sensor_msgs::CameraInfoConstPtr& cameraInfoMsg)
251 {
252  nav_msgs::OdometryConstPtr odomMsg; // Null
253  sensor_msgs::LaserScan scanMsg; // Null
254  sensor_msgs::PointCloud2 scan3dMsg; // null
255  rtabmap_ros::OdomInfoConstPtr odomInfoMsg; // null
256  commonSingleCameraCallback(odomMsg, userDataMsg, cv_bridge::toCvShare(imageMsg), cv_bridge::toCvShare(depthMsg), *cameraInfoMsg, *cameraInfoMsg, scanMsg, scan3dMsg, odomInfoMsg);
257 }
258 void CommonDataSubscriber::depthDataScan2dCallback(
259  const rtabmap_ros::UserDataConstPtr & userDataMsg,
260  const sensor_msgs::ImageConstPtr& imageMsg,
261  const sensor_msgs::ImageConstPtr& depthMsg,
262  const sensor_msgs::CameraInfoConstPtr& cameraInfoMsg,
263  const sensor_msgs::LaserScanConstPtr& scanMsg)
264 {
265  nav_msgs::OdometryConstPtr odomMsg; // null
266  sensor_msgs::PointCloud2 scan3dMsg; // Null
267  rtabmap_ros::OdomInfoConstPtr odomInfoMsg; // null
268  commonSingleCameraCallback(odomMsg, userDataMsg, cv_bridge::toCvShare(imageMsg), cv_bridge::toCvShare(depthMsg), *cameraInfoMsg, *cameraInfoMsg, *scanMsg, scan3dMsg, odomInfoMsg);
269 }
270 void CommonDataSubscriber::depthDataScan3dCallback(
271  const rtabmap_ros::UserDataConstPtr & userDataMsg,
272  const sensor_msgs::ImageConstPtr& imageMsg,
273  const sensor_msgs::ImageConstPtr& depthMsg,
274  const sensor_msgs::CameraInfoConstPtr& cameraInfoMsg,
275  const sensor_msgs::PointCloud2ConstPtr& scanMsg)
276 {
277  nav_msgs::OdometryConstPtr odomMsg; // null
278  sensor_msgs::LaserScan scan2dMsg; // Null
279  rtabmap_ros::OdomInfoConstPtr odomInfoMsg; // null
280  commonSingleCameraCallback(odomMsg, userDataMsg, cv_bridge::toCvShare(imageMsg), cv_bridge::toCvShare(depthMsg), *cameraInfoMsg, *cameraInfoMsg, scan2dMsg, *scanMsg, odomInfoMsg);
281 }
282 void CommonDataSubscriber::depthDataScanDescCallback(
283  const rtabmap_ros::UserDataConstPtr & userDataMsg,
284  const sensor_msgs::ImageConstPtr& imageMsg,
285  const sensor_msgs::ImageConstPtr& depthMsg,
286  const sensor_msgs::CameraInfoConstPtr& cameraInfoMsg,
287  const rtabmap_ros::ScanDescriptorConstPtr& scanMsg)
288 {
289  nav_msgs::OdometryConstPtr odomMsg; // null
290  rtabmap_ros::OdomInfoConstPtr odomInfoMsg; // null
291  std::vector<rtabmap_ros::GlobalDescriptor> globalDescriptor;
292  if(!scanMsg->global_descriptor.data.empty())
293  {
294  globalDescriptor.push_back(scanMsg->global_descriptor);
295  }
296  commonSingleCameraCallback(odomMsg, userDataMsg, cv_bridge::toCvShare(imageMsg), cv_bridge::toCvShare(depthMsg), *cameraInfoMsg, *cameraInfoMsg, scanMsg->scan, scanMsg->scan_cloud, odomInfoMsg, globalDescriptor);
297 }
298 void CommonDataSubscriber::depthDataInfoCallback(
299  const rtabmap_ros::UserDataConstPtr & userDataMsg,
300  const sensor_msgs::ImageConstPtr& imageMsg,
301  const sensor_msgs::ImageConstPtr& depthMsg,
302  const sensor_msgs::CameraInfoConstPtr& cameraInfoMsg,
303  const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg)
304 {
305  nav_msgs::OdometryConstPtr odomMsg; // null
306  sensor_msgs::LaserScan scan2dMsg; // Null
307  sensor_msgs::PointCloud2 scan3dMsg; // Null
308  commonSingleCameraCallback(odomMsg, userDataMsg, cv_bridge::toCvShare(imageMsg), cv_bridge::toCvShare(depthMsg), *cameraInfoMsg, *cameraInfoMsg, scan2dMsg, scan3dMsg, odomInfoMsg);
309 }
310 void CommonDataSubscriber::depthDataScan2dInfoCallback(
311  const rtabmap_ros::UserDataConstPtr & userDataMsg,
312  const sensor_msgs::ImageConstPtr& imageMsg,
313  const sensor_msgs::ImageConstPtr& depthMsg,
314  const sensor_msgs::CameraInfoConstPtr& cameraInfoMsg,
315  const sensor_msgs::LaserScanConstPtr& scanMsg,
316  const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg)
317 {
318  nav_msgs::OdometryConstPtr odomMsg; // null
319  sensor_msgs::PointCloud2 scan3dMsg; // Null
320  commonSingleCameraCallback(odomMsg, userDataMsg, cv_bridge::toCvShare(imageMsg), cv_bridge::toCvShare(depthMsg), *cameraInfoMsg, *cameraInfoMsg, *scanMsg, scan3dMsg, odomInfoMsg);
321 }
322 void CommonDataSubscriber::depthDataScan3dInfoCallback(
323  const rtabmap_ros::UserDataConstPtr & userDataMsg,
324  const sensor_msgs::ImageConstPtr& imageMsg,
325  const sensor_msgs::ImageConstPtr& depthMsg,
326  const sensor_msgs::CameraInfoConstPtr& cameraInfoMsg,
327  const sensor_msgs::PointCloud2ConstPtr& scanMsg,
328  const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg)
329 {
330  nav_msgs::OdometryConstPtr odomMsg; // null
331  sensor_msgs::LaserScan scan2dMsg; // Null
332  commonSingleCameraCallback(odomMsg, userDataMsg, cv_bridge::toCvShare(imageMsg), cv_bridge::toCvShare(depthMsg), *cameraInfoMsg, *cameraInfoMsg, scan2dMsg, *scanMsg, odomInfoMsg);
333 }
334 void CommonDataSubscriber::depthDataScanDescInfoCallback(
335  const rtabmap_ros::UserDataConstPtr & userDataMsg,
336  const sensor_msgs::ImageConstPtr& imageMsg,
337  const sensor_msgs::ImageConstPtr& depthMsg,
338  const sensor_msgs::CameraInfoConstPtr& cameraInfoMsg,
339  const rtabmap_ros::ScanDescriptorConstPtr& scanMsg,
340  const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg)
341 {
342  nav_msgs::OdometryConstPtr odomMsg; // null
343  std::vector<rtabmap_ros::GlobalDescriptor> globalDescriptor;
344  if(!scanMsg->global_descriptor.data.empty())
345  {
346  globalDescriptor.push_back(scanMsg->global_descriptor);
347  }
348  commonSingleCameraCallback(odomMsg, userDataMsg, cv_bridge::toCvShare(imageMsg), cv_bridge::toCvShare(depthMsg), *cameraInfoMsg, *cameraInfoMsg, scanMsg->scan, scanMsg->scan_cloud, odomInfoMsg, globalDescriptor);
349 }
350 
351 // RGB + Depth + Odom + User Data
352 void CommonDataSubscriber::depthOdomDataCallback(
353  const nav_msgs::OdometryConstPtr & odomMsg,
354  const rtabmap_ros::UserDataConstPtr & userDataMsg,
355  const sensor_msgs::ImageConstPtr& imageMsg,
356  const sensor_msgs::ImageConstPtr& depthMsg,
357  const sensor_msgs::CameraInfoConstPtr& cameraInfoMsg)
358 {
359  sensor_msgs::LaserScan scanMsg; // Null
360  sensor_msgs::PointCloud2 scan3dMsg; // null
361  rtabmap_ros::OdomInfoConstPtr odomInfoMsg; // null
362  commonSingleCameraCallback(odomMsg, userDataMsg, cv_bridge::toCvShare(imageMsg), cv_bridge::toCvShare(depthMsg), *cameraInfoMsg, *cameraInfoMsg, scanMsg, scan3dMsg, odomInfoMsg);
363 }
364 void CommonDataSubscriber::depthOdomDataScan2dCallback(
365  const nav_msgs::OdometryConstPtr & odomMsg,
366  const rtabmap_ros::UserDataConstPtr & userDataMsg,
367  const sensor_msgs::ImageConstPtr& imageMsg,
368  const sensor_msgs::ImageConstPtr& depthMsg,
369  const sensor_msgs::CameraInfoConstPtr& cameraInfoMsg,
370  const sensor_msgs::LaserScanConstPtr& scanMsg)
371 {
372  sensor_msgs::PointCloud2 scan3dMsg; // Null
373  rtabmap_ros::OdomInfoConstPtr odomInfoMsg; // null
374  commonSingleCameraCallback(odomMsg, userDataMsg, cv_bridge::toCvShare(imageMsg), cv_bridge::toCvShare(depthMsg), *cameraInfoMsg, *cameraInfoMsg, *scanMsg, scan3dMsg, odomInfoMsg);
375 }
376 void CommonDataSubscriber::depthOdomDataScan3dCallback(
377  const nav_msgs::OdometryConstPtr & odomMsg,
378  const rtabmap_ros::UserDataConstPtr & userDataMsg,
379  const sensor_msgs::ImageConstPtr& imageMsg,
380  const sensor_msgs::ImageConstPtr& depthMsg,
381  const sensor_msgs::CameraInfoConstPtr& cameraInfoMsg,
382  const sensor_msgs::PointCloud2ConstPtr& scanMsg)
383 {
384  sensor_msgs::LaserScan scan2dMsg; // Null
385  rtabmap_ros::OdomInfoConstPtr odomInfoMsg; // null
386  commonSingleCameraCallback(odomMsg, userDataMsg, cv_bridge::toCvShare(imageMsg), cv_bridge::toCvShare(depthMsg), *cameraInfoMsg, *cameraInfoMsg, scan2dMsg, *scanMsg, odomInfoMsg);
387 }
388 void CommonDataSubscriber::depthOdomDataScanDescCallback(
389  const nav_msgs::OdometryConstPtr & odomMsg,
390  const rtabmap_ros::UserDataConstPtr & userDataMsg,
391  const sensor_msgs::ImageConstPtr& imageMsg,
392  const sensor_msgs::ImageConstPtr& depthMsg,
393  const sensor_msgs::CameraInfoConstPtr& cameraInfoMsg,
394  const rtabmap_ros::ScanDescriptorConstPtr& scanMsg)
395 {
396  rtabmap_ros::OdomInfoConstPtr odomInfoMsg; // null
397  std::vector<rtabmap_ros::GlobalDescriptor> globalDescriptor;
398  if(!scanMsg->global_descriptor.data.empty())
399  {
400  globalDescriptor.push_back(scanMsg->global_descriptor);
401  }
402  commonSingleCameraCallback(odomMsg, userDataMsg, cv_bridge::toCvShare(imageMsg), cv_bridge::toCvShare(depthMsg), *cameraInfoMsg, *cameraInfoMsg, scanMsg->scan, scanMsg->scan_cloud, odomInfoMsg, globalDescriptor);
403 }
404 void CommonDataSubscriber::depthOdomDataInfoCallback(
405  const nav_msgs::OdometryConstPtr & odomMsg,
406  const rtabmap_ros::UserDataConstPtr & userDataMsg,
407  const sensor_msgs::ImageConstPtr& imageMsg,
408  const sensor_msgs::ImageConstPtr& depthMsg,
409  const sensor_msgs::CameraInfoConstPtr& cameraInfoMsg,
410  const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg)
411 {
412  sensor_msgs::LaserScan scan2dMsg; // Null
413  sensor_msgs::PointCloud2 scan3dMsg; // Null
414  commonSingleCameraCallback(odomMsg, userDataMsg, cv_bridge::toCvShare(imageMsg), cv_bridge::toCvShare(depthMsg), *cameraInfoMsg, *cameraInfoMsg, scan2dMsg, scan3dMsg, odomInfoMsg);
415 }
416 void CommonDataSubscriber::depthOdomDataScan2dInfoCallback(
417  const nav_msgs::OdometryConstPtr & odomMsg,
418  const rtabmap_ros::UserDataConstPtr & userDataMsg,
419  const sensor_msgs::ImageConstPtr& imageMsg,
420  const sensor_msgs::ImageConstPtr& depthMsg,
421  const sensor_msgs::CameraInfoConstPtr& cameraInfoMsg,
422  const sensor_msgs::LaserScanConstPtr& scanMsg,
423  const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg)
424 {
425  sensor_msgs::PointCloud2 scan3dMsg; // Null
426  commonSingleCameraCallback(odomMsg, userDataMsg, cv_bridge::toCvShare(imageMsg), cv_bridge::toCvShare(depthMsg), *cameraInfoMsg, *cameraInfoMsg, *scanMsg, scan3dMsg, odomInfoMsg);
427 }
428 void CommonDataSubscriber::depthOdomDataScan3dInfoCallback(
429  const nav_msgs::OdometryConstPtr & odomMsg,
430  const rtabmap_ros::UserDataConstPtr & userDataMsg,
431  const sensor_msgs::ImageConstPtr& imageMsg,
432  const sensor_msgs::ImageConstPtr& depthMsg,
433  const sensor_msgs::CameraInfoConstPtr& cameraInfoMsg,
434  const sensor_msgs::PointCloud2ConstPtr& scanMsg,
435  const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg)
436 {
437  sensor_msgs::LaserScan scan2dMsg; // Null
438  commonSingleCameraCallback(odomMsg, userDataMsg, cv_bridge::toCvShare(imageMsg), cv_bridge::toCvShare(depthMsg), *cameraInfoMsg, *cameraInfoMsg, scan2dMsg, *scanMsg, odomInfoMsg);
439 }
440 void CommonDataSubscriber::depthOdomDataScanDescInfoCallback(
441  const nav_msgs::OdometryConstPtr & odomMsg,
442  const rtabmap_ros::UserDataConstPtr & userDataMsg,
443  const sensor_msgs::ImageConstPtr& imageMsg,
444  const sensor_msgs::ImageConstPtr& depthMsg,
445  const sensor_msgs::CameraInfoConstPtr& cameraInfoMsg,
446  const rtabmap_ros::ScanDescriptorConstPtr& scanMsg,
447  const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg)
448 {
449  std::vector<rtabmap_ros::GlobalDescriptor> globalDescriptor;
450  if(!scanMsg->global_descriptor.data.empty())
451  {
452  globalDescriptor.push_back(scanMsg->global_descriptor);
453  }
454  commonSingleCameraCallback(odomMsg, userDataMsg, cv_bridge::toCvShare(imageMsg), cv_bridge::toCvShare(depthMsg), *cameraInfoMsg, *cameraInfoMsg, scanMsg->scan, scanMsg->scan_cloud, odomInfoMsg, globalDescriptor);
455 }
456 #endif
457 
459  ros::NodeHandle & nh,
460  ros::NodeHandle & pnh,
461  bool subscribeOdom,
462  bool subscribeUserData,
463  bool subscribeScan2d,
464  bool subscribeScan3d,
465  bool subscribeScanDesc,
466  bool subscribeOdomInfo,
467  int queueSize,
468  bool approxSync)
469 {
470  ROS_INFO("Setup depth callback");
471 
472  std::string rgbPrefix = "rgb";
473  std::string depthPrefix = "depth";
474  ros::NodeHandle rgb_nh(nh, rgbPrefix);
475  ros::NodeHandle depth_nh(nh, depthPrefix);
476  ros::NodeHandle rgb_pnh(pnh, rgbPrefix);
477  ros::NodeHandle depth_pnh(pnh, depthPrefix);
478  image_transport::ImageTransport rgb_it(rgb_nh);
479  image_transport::ImageTransport depth_it(depth_nh);
480  image_transport::TransportHints hintsRgb("raw", ros::TransportHints(), rgb_pnh);
481  image_transport::TransportHints hintsDepth("raw", ros::TransportHints(), depth_pnh);
482 
483  imageSub_.subscribe(rgb_it, rgb_nh.resolveName("image"), queueSize, hintsRgb);
484  imageDepthSub_.subscribe(depth_it, depth_nh.resolveName("image"), queueSize, hintsDepth);
485  cameraInfoSub_.subscribe(rgb_nh, "camera_info", queueSize);
486 
487 #ifdef RTABMAP_SYNC_USER_DATA
488  if(subscribeOdom && subscribeUserData)
489  {
490  odomSub_.subscribe(nh, "odom", queueSize);
491  userDataSub_.subscribe(nh, "user_data", queueSize);
492 
493  if(subscribeScanDesc)
494  {
496  scanDescSub_.subscribe(nh, "scan_descriptor", queueSize);
497  if(subscribeOdomInfo)
498  {
499  subscribedToOdomInfo_ = true;
500  odomInfoSub_.subscribe(nh, "odom_info", queueSize);
501  SYNC_DECL7(CommonDataSubscriber, depthOdomDataScanDescInfo, approxSync, queueSize, odomSub_, userDataSub_, imageSub_, imageDepthSub_, cameraInfoSub_, scanDescSub_, odomInfoSub_);
502  }
503  else
504  {
505  SYNC_DECL6(CommonDataSubscriber, depthOdomDataScanDesc, approxSync, queueSize, odomSub_, userDataSub_, imageSub_, imageDepthSub_, cameraInfoSub_, scanDescSub_);
506  }
507  }
508  else if(subscribeScan2d)
509  {
510  subscribedToScan2d_ = true;
511  scanSub_.subscribe(nh, "scan", queueSize);
512  if(subscribeOdomInfo)
513  {
514  subscribedToOdomInfo_ = true;
515  odomInfoSub_.subscribe(nh, "odom_info", queueSize);
516  SYNC_DECL7(CommonDataSubscriber, depthOdomDataScan2dInfo, approxSync, queueSize, odomSub_, userDataSub_, imageSub_, imageDepthSub_, cameraInfoSub_, scanSub_, odomInfoSub_);
517  }
518  else
519  {
520  SYNC_DECL6(CommonDataSubscriber, depthOdomDataScan2d, approxSync, queueSize, odomSub_, userDataSub_, imageSub_, imageDepthSub_, cameraInfoSub_, scanSub_);
521  }
522  }
523  else if(subscribeScan3d)
524  {
525  subscribedToScan3d_ = true;
526  scan3dSub_.subscribe(nh, "scan_cloud", queueSize);
527  if(subscribeOdomInfo)
528  {
529  subscribedToOdomInfo_ = true;
530  odomInfoSub_.subscribe(nh, "odom_info", queueSize);
532  }
533  else
534  {
535  SYNC_DECL6(CommonDataSubscriber, depthOdomDataScan3d, approxSync, queueSize, odomSub_, userDataSub_, imageSub_, imageDepthSub_, cameraInfoSub_, scan3dSub_);
536  }
537  }
538  else if(subscribeOdomInfo)
539  {
540  subscribedToOdomInfo_ = true;
541  odomInfoSub_.subscribe(nh, "odom_info", queueSize);
543  }
544  else
545  {
546  SYNC_DECL5(CommonDataSubscriber, depthOdomData, approxSync, queueSize, odomSub_, userDataSub_, imageSub_, imageDepthSub_, cameraInfoSub_);
547  }
548  }
549  else
550 #endif
551  if(subscribeOdom)
552  {
553  odomSub_.subscribe(nh, "odom", queueSize);
554 
555  if(subscribeScanDesc)
556  {
558  scanDescSub_.subscribe(nh, "scan_descriptor", queueSize);
559  if(subscribeOdomInfo)
560  {
561  subscribedToOdomInfo_ = true;
562  odomInfoSub_.subscribe(nh, "odom_info", queueSize);
563  SYNC_DECL6(CommonDataSubscriber, depthOdomScanDescInfo, approxSync, queueSize, odomSub_, imageSub_, imageDepthSub_, cameraInfoSub_, scanDescSub_, odomInfoSub_);
564  }
565  else
566  {
567  SYNC_DECL5(CommonDataSubscriber, depthOdomScanDesc, approxSync, queueSize, odomSub_, imageSub_, imageDepthSub_, cameraInfoSub_, scanDescSub_);
568  }
569  }
570  else if(subscribeScan2d)
571  {
572  subscribedToScan2d_ = true;
573  scanSub_.subscribe(nh, "scan", queueSize);
574  if(subscribeOdomInfo)
575  {
576  subscribedToOdomInfo_ = true;
577  odomInfoSub_.subscribe(nh, "odom_info", queueSize);
578  SYNC_DECL6(CommonDataSubscriber, depthOdomScan2dInfo, approxSync, queueSize, odomSub_, imageSub_, imageDepthSub_, cameraInfoSub_, scanSub_, odomInfoSub_);
579  }
580  else
581  {
582  SYNC_DECL5(CommonDataSubscriber, depthOdomScan2d, approxSync, queueSize, odomSub_, imageSub_, imageDepthSub_, cameraInfoSub_, scanSub_);
583  }
584  }
585  else if(subscribeScan3d)
586  {
587  subscribedToScan3d_ = true;
588  scan3dSub_.subscribe(nh, "scan_cloud", queueSize);
589  if(subscribeOdomInfo)
590  {
591  subscribedToOdomInfo_ = true;
592  odomInfoSub_.subscribe(nh, "odom_info", queueSize);
593  SYNC_DECL6(CommonDataSubscriber, depthOdomScan3dInfo, approxSync, queueSize, odomSub_, imageSub_, imageDepthSub_, cameraInfoSub_, scan3dSub_, odomInfoSub_);
594  }
595  else
596  {
597  SYNC_DECL5(CommonDataSubscriber, depthOdomScan3d, approxSync, queueSize, odomSub_, imageSub_, imageDepthSub_, cameraInfoSub_, scan3dSub_);
598  }
599  }
600  else if(subscribeOdomInfo)
601  {
602  subscribedToOdomInfo_ = true;
603  odomInfoSub_.subscribe(nh, "odom_info", queueSize);
604  SYNC_DECL5(CommonDataSubscriber, depthOdomInfo, approxSync, queueSize, odomSub_, imageSub_, imageDepthSub_, cameraInfoSub_, odomInfoSub_);
605  }
606  else
607  {
608  SYNC_DECL4(CommonDataSubscriber, depthOdom, approxSync, queueSize, odomSub_, imageSub_, imageDepthSub_, cameraInfoSub_);
609  }
610  }
611 #ifdef RTABMAP_SYNC_USER_DATA
612  else if(subscribeUserData)
613  {
614  userDataSub_.subscribe(nh, "user_data", queueSize);
615 
616  if(subscribeScanDesc)
617  {
619  scanDescSub_.subscribe(nh, "scan_descriptor", queueSize);
620 
621  if(subscribeOdomInfo)
622  {
623  subscribedToOdomInfo_ = true;
624  odomInfoSub_.subscribe(nh, "odom_info", queueSize);
626  }
627  else
628  {
629  SYNC_DECL5(CommonDataSubscriber, depthDataScanDesc, approxSync, queueSize, userDataSub_, imageSub_, imageDepthSub_, cameraInfoSub_, scanDescSub_);
630  }
631  }
632  else if(subscribeScan2d)
633  {
634  subscribedToScan2d_ = true;
635  scanSub_.subscribe(nh, "scan", queueSize);
636 
637  if(subscribeOdomInfo)
638  {
639  subscribedToOdomInfo_ = true;
640  odomInfoSub_.subscribe(nh, "odom_info", queueSize);
641  SYNC_DECL6(CommonDataSubscriber, depthDataScan2dInfo, approxSync, queueSize, userDataSub_, imageSub_, imageDepthSub_, cameraInfoSub_, scanSub_, odomInfoSub_);
642  }
643  else
644  {
645  SYNC_DECL5(CommonDataSubscriber, depthDataScan2d, approxSync, queueSize, userDataSub_, imageSub_, imageDepthSub_, cameraInfoSub_, scanSub_);
646  }
647  }
648  else if(subscribeScan3d)
649  {
650  subscribedToScan3d_ = true;
651  scan3dSub_.subscribe(nh, "scan_cloud", queueSize);
652  if(subscribeOdomInfo)
653  {
654  subscribedToOdomInfo_ = true;
655  odomInfoSub_.subscribe(nh, "odom_info", queueSize);
657  }
658  else
659  {
660  SYNC_DECL5(CommonDataSubscriber, depthDataScan3d, approxSync, queueSize, userDataSub_, imageSub_, imageDepthSub_, cameraInfoSub_, scan3dSub_);
661  }
662  }
663  else if(subscribeOdomInfo)
664  {
665  subscribedToOdomInfo_ = true;
666  odomInfoSub_.subscribe(nh, "odom_info", queueSize);
668  }
669  else
670  {
672  }
673  }
674 #endif
675  else
676  {
677  if(subscribeScanDesc)
678  {
680  scanDescSub_.subscribe(nh, "scan_descriptor", queueSize);
681  if(subscribeOdomInfo)
682  {
683  subscribedToOdomInfo_ = true;
684  odomInfoSub_.subscribe(nh, "odom_info", queueSize);
685  SYNC_DECL5(CommonDataSubscriber, depthScanDescInfo, approxSync, queueSize, imageSub_, imageDepthSub_, cameraInfoSub_, scanDescSub_, odomInfoSub_);
686  }
687  else
688  {
689  SYNC_DECL4(CommonDataSubscriber, depthScanDesc, approxSync, queueSize, imageSub_, imageDepthSub_, cameraInfoSub_, scanDescSub_);
690  }
691  }
692  else if(subscribeScan2d)
693  {
694  subscribedToScan2d_ = true;
695  scanSub_.subscribe(nh, "scan", queueSize);
696  if(subscribeOdomInfo)
697  {
698  subscribedToOdomInfo_ = true;
699  odomInfoSub_.subscribe(nh, "odom_info", queueSize);
700  SYNC_DECL5(CommonDataSubscriber, depthScan2dInfo, approxSync, queueSize, imageSub_, imageDepthSub_, cameraInfoSub_, scanSub_, odomInfoSub_);
701  }
702  else
703  {
704  SYNC_DECL4(CommonDataSubscriber, depthScan2d, approxSync, queueSize, imageSub_, imageDepthSub_, cameraInfoSub_, scanSub_);
705  }
706  }
707  else if(subscribeScan3d)
708  {
709  subscribedToScan3d_ = true;
710  scan3dSub_.subscribe(nh, "scan_cloud", queueSize);
711  if(subscribeOdomInfo)
712  {
713  subscribedToOdomInfo_ = true;
714  odomInfoSub_.subscribe(nh, "odom_info", queueSize);
715  SYNC_DECL5(CommonDataSubscriber, depthScan3dInfo, approxSync, queueSize, imageSub_, imageDepthSub_, cameraInfoSub_, scan3dSub_, odomInfoSub_);
716  }
717  else
718  {
719  SYNC_DECL4(CommonDataSubscriber, depthScan3d, approxSync, queueSize, imageSub_, imageDepthSub_, cameraInfoSub_, scan3dSub_);
720  }
721  }
722  else if(subscribeOdomInfo)
723  {
724  subscribedToOdomInfo_ = true;
725  odomInfoSub_.subscribe(nh, "odom_info", queueSize);
727  }
728  else
729  {
730  SYNC_DECL3(CommonDataSubscriber, depth, approxSync, queueSize, imageSub_, imageDepthSub_, cameraInfoSub_);
731  }
732  }
733 }
734 
735 } /* namespace rtabmap_ros */
CvImageConstPtr toCvShare(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
#define SYNC_DECL3(CLASS, PREFIX, APPROX, QUEUE_SIZE, SUB0, SUB1, SUB2)
message_filters::Subscriber< rtabmap_ros::UserData > userDataSub_
message_filters::Subscriber< rtabmap_ros::OdomInfo > odomInfoSub_
image_transport::SubscriberFilter imageDepthSub_
#define SYNC_DECL5(CLASS, PREFIX, APPROX, QUEUE_SIZE, SUB0, SUB1, SUB2, SUB3, SUB4)
#define ROS_INFO(...)
image_transport::SubscriberFilter imageSub_
message_filters::Subscriber< sensor_msgs::LaserScan > scanSub_
message_filters::Subscriber< rtabmap_ros::ScanDescriptor > scanDescSub_
message_filters::Subscriber< nav_msgs::Odometry > odomSub_
std::string resolveName(const std::string &name, bool remap=true) const
void subscribe(ImageTransport &it, const std::string &base_topic, uint32_t queue_size, const TransportHints &transport_hints=TransportHints())
#define SYNC_DECL6(CLASS, PREFIX, APPROX, QUEUE_SIZE, SUB0, SUB1, SUB2, SUB3, SUB4, SUB5)
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)
#define SYNC_DECL7(CLASS, PREFIX, APPROX, QUEUE_SIZE, SUB0, SUB1, SUB2, SUB3, SUB4, SUB5, SUB6)
message_filters::Subscriber< sensor_msgs::CameraInfo > cameraInfoSub_
#define SYNC_DECL4(CLASS, PREFIX, APPROX, QUEUE_SIZE, SUB0, SUB1, SUB2, SUB3)
void setupDepthCallbacks(ros::NodeHandle &nh, ros::NodeHandle &pnh, bool subscribeOdom, bool subscribeUserData, bool subscribeScan2d, bool subscribeScan3d, bool subscribeScanDesc, bool subscribeOdomInfo, int queueSize, bool approxSync)
void commonSingleCameraCallback(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::LaserScan &scanMsg, const sensor_msgs::PointCloud2 &scan3dMsg, const rtabmap_ros::OdomInfoConstPtr &odomInfoMsg, const std::vector< rtabmap_ros::GlobalDescriptor > &globalDescriptorMsgs=std::vector< rtabmap_ros::GlobalDescriptor >(), const std::vector< rtabmap_ros::KeyPoint > &localKeyPoints=std::vector< rtabmap_ros::KeyPoint >(), const std::vector< rtabmap_ros::Point3f > &localPoints3d=std::vector< rtabmap_ros::Point3f >(), const cv::Mat &localDescriptors=cv::Mat())


rtabmap_ros
Author(s): Mathieu Labbe
autogenerated on Tue Jan 24 2023 04:04:40