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_sync {
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_msgs::UserDataConstPtr userDataMsg; // Null
39  nav_msgs::OdometryConstPtr odomMsg; // Null
40  sensor_msgs::LaserScan scanMsg; // Null
41  sensor_msgs::PointCloud2 scan3dMsg; // Null
42  rtabmap_msgs::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_msgs::UserDataConstPtr userDataMsg; // Null
52  nav_msgs::OdometryConstPtr odomMsg; // Null
53  sensor_msgs::PointCloud2 scan3dMsg; // Null
54  rtabmap_msgs::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_msgs::UserDataConstPtr userDataMsg; // Null
64  nav_msgs::OdometryConstPtr odomMsg; // Null
65  sensor_msgs::LaserScan scan2dMsg; // Null
66  rtabmap_msgs::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_msgs::ScanDescriptorConstPtr& scanMsg)
74 {
75  rtabmap_msgs::UserDataConstPtr userDataMsg; // Null
76  nav_msgs::OdometryConstPtr odomMsg; // Null
77  rtabmap_msgs::OdomInfoConstPtr odomInfoMsg; // null
78  std::vector<rtabmap_msgs::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_msgs::OdomInfoConstPtr& odomInfoMsg)
90 {
91  rtabmap_msgs::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_msgs::OdomInfoConstPtr& odomInfoMsg)
103 {
104  rtabmap_msgs::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_msgs::OdomInfoConstPtr& odomInfoMsg)
115 {
116  rtabmap_msgs::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_msgs::ScanDescriptorConstPtr& scanMsg,
126  const rtabmap_msgs::OdomInfoConstPtr& odomInfoMsg)
127 {
128  rtabmap_msgs::UserDataConstPtr userDataMsg; // Null
129  nav_msgs::OdometryConstPtr odomMsg; // Null
130  std::vector<rtabmap_msgs::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_msgs::UserDataConstPtr userDataMsg; // Null
146  sensor_msgs::LaserScan scanMsg; // Null
147  sensor_msgs::PointCloud2 scan3dMsg; // null
148  rtabmap_msgs::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_msgs::UserDataConstPtr userDataMsg; // Null
159  sensor_msgs::PointCloud2 scan3dMsg; // Null
160  rtabmap_msgs::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_msgs::UserDataConstPtr userDataMsg; // Null
171  sensor_msgs::LaserScan scan2dMsg; // Null
172  rtabmap_msgs::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_msgs::ScanDescriptorConstPtr& scanMsg)
181 {
182  rtabmap_msgs::UserDataConstPtr userDataMsg; // Null
183  rtabmap_msgs::OdomInfoConstPtr odomInfoMsg; // null
184  std::vector<rtabmap_msgs::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_msgs::OdomInfoConstPtr& odomInfoMsg)
197 {
198  rtabmap_msgs::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_msgs::OdomInfoConstPtr& odomInfoMsg)
210 {
211  rtabmap_msgs::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_msgs::OdomInfoConstPtr& odomInfoMsg)
222 {
223  rtabmap_msgs::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_msgs::ScanDescriptorConstPtr& scanMsg,
233  const rtabmap_msgs::OdomInfoConstPtr& odomInfoMsg)
234 {
235  rtabmap_msgs::UserDataConstPtr userDataMsg; // Null
236  std::vector<rtabmap_msgs::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_msgs::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_msgs::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_msgs::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_msgs::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_msgs::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_msgs::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_msgs::UserDataConstPtr & userDataMsg,
284  const sensor_msgs::ImageConstPtr& imageMsg,
285  const sensor_msgs::ImageConstPtr& depthMsg,
286  const sensor_msgs::CameraInfoConstPtr& cameraInfoMsg,
287  const rtabmap_msgs::ScanDescriptorConstPtr& scanMsg)
288 {
289  nav_msgs::OdometryConstPtr odomMsg; // null
290  rtabmap_msgs::OdomInfoConstPtr odomInfoMsg; // null
291  std::vector<rtabmap_msgs::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_msgs::UserDataConstPtr & userDataMsg,
300  const sensor_msgs::ImageConstPtr& imageMsg,
301  const sensor_msgs::ImageConstPtr& depthMsg,
302  const sensor_msgs::CameraInfoConstPtr& cameraInfoMsg,
303  const rtabmap_msgs::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_msgs::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_msgs::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_msgs::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_msgs::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_msgs::UserDataConstPtr & userDataMsg,
336  const sensor_msgs::ImageConstPtr& imageMsg,
337  const sensor_msgs::ImageConstPtr& depthMsg,
338  const sensor_msgs::CameraInfoConstPtr& cameraInfoMsg,
339  const rtabmap_msgs::ScanDescriptorConstPtr& scanMsg,
340  const rtabmap_msgs::OdomInfoConstPtr& odomInfoMsg)
341 {
342  nav_msgs::OdometryConstPtr odomMsg; // null
343  std::vector<rtabmap_msgs::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_msgs::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_msgs::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_msgs::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_msgs::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_msgs::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_msgs::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_msgs::UserDataConstPtr & userDataMsg,
391  const sensor_msgs::ImageConstPtr& imageMsg,
392  const sensor_msgs::ImageConstPtr& depthMsg,
393  const sensor_msgs::CameraInfoConstPtr& cameraInfoMsg,
394  const rtabmap_msgs::ScanDescriptorConstPtr& scanMsg)
395 {
396  rtabmap_msgs::OdomInfoConstPtr odomInfoMsg; // null
397  std::vector<rtabmap_msgs::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_msgs::UserDataConstPtr & userDataMsg,
407  const sensor_msgs::ImageConstPtr& imageMsg,
408  const sensor_msgs::ImageConstPtr& depthMsg,
409  const sensor_msgs::CameraInfoConstPtr& cameraInfoMsg,
410  const rtabmap_msgs::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_msgs::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_msgs::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_msgs::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_msgs::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_msgs::UserDataConstPtr & userDataMsg,
443  const sensor_msgs::ImageConstPtr& imageMsg,
444  const sensor_msgs::ImageConstPtr& depthMsg,
445  const sensor_msgs::CameraInfoConstPtr& cameraInfoMsg,
446  const rtabmap_msgs::ScanDescriptorConstPtr& scanMsg,
447  const rtabmap_msgs::OdomInfoConstPtr& odomInfoMsg)
448 {
449  std::vector<rtabmap_msgs::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 {
468  ROS_INFO("Setup depth callback");
469 
470  std::string rgbPrefix = "rgb";
471  std::string depthPrefix = "depth";
472  ros::NodeHandle rgb_nh(nh, rgbPrefix);
473  ros::NodeHandle depth_nh(nh, depthPrefix);
474  ros::NodeHandle rgb_pnh(pnh, rgbPrefix);
475  ros::NodeHandle depth_pnh(pnh, depthPrefix);
476  image_transport::ImageTransport rgb_it(rgb_nh);
477  image_transport::ImageTransport depth_it(depth_nh);
478  image_transport::TransportHints hintsRgb("raw", ros::TransportHints(), rgb_pnh);
479  image_transport::TransportHints hintsDepth("raw", ros::TransportHints(), depth_pnh);
480 
481  imageSub_.subscribe(rgb_it, rgb_nh.resolveName("image"), topicQueueSize_, hintsRgb);
482  imageDepthSub_.subscribe(depth_it, depth_nh.resolveName("image"), topicQueueSize_, hintsDepth);
483  cameraInfoSub_.subscribe(rgb_nh, "camera_info", topicQueueSize_);
484 
485 #ifdef RTABMAP_SYNC_USER_DATA
486  if(subscribeOdom && subscribeUserData)
487  {
488  odomSub_.subscribe(nh, "odom", topicQueueSize_);
489  userDataSub_.subscribe(nh, "user_data", topicQueueSize_);
490 
491  if(subscribeScanDesc)
492  {
494  scanDescSub_.subscribe(nh, "scan_descriptor", topicQueueSize_);
495  if(subscribeOdomInfo)
496  {
497  subscribedToOdomInfo_ = true;
498  odomInfoSub_.subscribe(nh, "odom_info", topicQueueSize_);
500  }
501  else
502  {
504  }
505  }
506  else if(subscribeScan2d)
507  {
508  subscribedToScan2d_ = true;
509  scanSub_.subscribe(nh, "scan", topicQueueSize_);
510  if(subscribeOdomInfo)
511  {
512  subscribedToOdomInfo_ = true;
513  odomInfoSub_.subscribe(nh, "odom_info", topicQueueSize_);
515  }
516  else
517  {
519  }
520  }
521  else if(subscribeScan3d)
522  {
523  subscribedToScan3d_ = true;
524  scan3dSub_.subscribe(nh, "scan_cloud", topicQueueSize_);
525  if(subscribeOdomInfo)
526  {
527  subscribedToOdomInfo_ = true;
528  odomInfoSub_.subscribe(nh, "odom_info", topicQueueSize_);
530  }
531  else
532  {
534  }
535  }
536  else if(subscribeOdomInfo)
537  {
538  subscribedToOdomInfo_ = true;
539  odomInfoSub_.subscribe(nh, "odom_info", topicQueueSize_);
541  }
542  else
543  {
545  }
546  }
547  else
548 #endif
549  if(subscribeOdom)
550  {
551  odomSub_.subscribe(nh, "odom", topicQueueSize_);
552 
553  if(subscribeScanDesc)
554  {
556  scanDescSub_.subscribe(nh, "scan_descriptor", topicQueueSize_);
557  if(subscribeOdomInfo)
558  {
559  subscribedToOdomInfo_ = true;
560  odomInfoSub_.subscribe(nh, "odom_info", topicQueueSize_);
562  }
563  else
564  {
566  }
567  }
568  else if(subscribeScan2d)
569  {
570  subscribedToScan2d_ = true;
571  scanSub_.subscribe(nh, "scan", topicQueueSize_);
572  if(subscribeOdomInfo)
573  {
574  subscribedToOdomInfo_ = true;
575  odomInfoSub_.subscribe(nh, "odom_info", topicQueueSize_);
577  }
578  else
579  {
581  }
582  }
583  else if(subscribeScan3d)
584  {
585  subscribedToScan3d_ = true;
586  scan3dSub_.subscribe(nh, "scan_cloud", topicQueueSize_);
587  if(subscribeOdomInfo)
588  {
589  subscribedToOdomInfo_ = true;
590  odomInfoSub_.subscribe(nh, "odom_info", topicQueueSize_);
592  }
593  else
594  {
596  }
597  }
598  else if(subscribeOdomInfo)
599  {
600  subscribedToOdomInfo_ = true;
601  odomInfoSub_.subscribe(nh, "odom_info", topicQueueSize_);
603  }
604  else
605  {
607  }
608  }
609 #ifdef RTABMAP_SYNC_USER_DATA
610  else if(subscribeUserData)
611  {
612  userDataSub_.subscribe(nh, "user_data", topicQueueSize_);
613 
614  if(subscribeScanDesc)
615  {
617  scanDescSub_.subscribe(nh, "scan_descriptor", topicQueueSize_);
618 
619  if(subscribeOdomInfo)
620  {
621  subscribedToOdomInfo_ = true;
622  odomInfoSub_.subscribe(nh, "odom_info", topicQueueSize_);
624  }
625  else
626  {
628  }
629  }
630  else if(subscribeScan2d)
631  {
632  subscribedToScan2d_ = true;
633  scanSub_.subscribe(nh, "scan", topicQueueSize_);
634 
635  if(subscribeOdomInfo)
636  {
637  subscribedToOdomInfo_ = true;
638  odomInfoSub_.subscribe(nh, "odom_info", topicQueueSize_);
640  }
641  else
642  {
644  }
645  }
646  else if(subscribeScan3d)
647  {
648  subscribedToScan3d_ = true;
649  scan3dSub_.subscribe(nh, "scan_cloud", topicQueueSize_);
650  if(subscribeOdomInfo)
651  {
652  subscribedToOdomInfo_ = true;
653  odomInfoSub_.subscribe(nh, "odom_info", topicQueueSize_);
655  }
656  else
657  {
659  }
660  }
661  else if(subscribeOdomInfo)
662  {
663  subscribedToOdomInfo_ = true;
664  odomInfoSub_.subscribe(nh, "odom_info", topicQueueSize_);
666  }
667  else
668  {
670  }
671  }
672 #endif
673  else
674  {
675  if(subscribeScanDesc)
676  {
678  scanDescSub_.subscribe(nh, "scan_descriptor", topicQueueSize_);
679  if(subscribeOdomInfo)
680  {
681  subscribedToOdomInfo_ = true;
682  odomInfoSub_.subscribe(nh, "odom_info", topicQueueSize_);
684  }
685  else
686  {
688  }
689  }
690  else if(subscribeScan2d)
691  {
692  subscribedToScan2d_ = true;
693  scanSub_.subscribe(nh, "scan", topicQueueSize_);
694  if(subscribeOdomInfo)
695  {
696  subscribedToOdomInfo_ = true;
697  odomInfoSub_.subscribe(nh, "odom_info", topicQueueSize_);
699  }
700  else
701  {
703  }
704  }
705  else if(subscribeScan3d)
706  {
707  subscribedToScan3d_ = true;
708  scan3dSub_.subscribe(nh, "scan_cloud", topicQueueSize_);
709  if(subscribeOdomInfo)
710  {
711  subscribedToOdomInfo_ = true;
712  odomInfoSub_.subscribe(nh, "odom_info", topicQueueSize_);
714  }
715  else
716  {
718  }
719  }
720  else if(subscribeOdomInfo)
721  {
722  subscribedToOdomInfo_ = true;
723  odomInfoSub_.subscribe(nh, "odom_info", topicQueueSize_);
725  }
726  else
727  {
729  }
730  }
731 }
732 
733 } /* namespace rtabmap_sync */
SYNC_DECL6
#define SYNC_DECL6(CLASS, PREFIX, APPROX, QUEUE_SIZE, SUB0, SUB1, SUB2, SUB3, SUB4, SUB5)
Definition: CommonDataSubscriberDefines.h:190
image_transport::ImageTransport
rtabmap_sync
Definition: CommonDataSubscriber.h:59
rtabmap_sync::CommonDataSubscriber::imageDepthSub_
image_transport::SubscriberFilter imageDepthSub_
Definition: CommonDataSubscriber.h:264
SYNC_DECL3
#define SYNC_DECL3(CLASS, PREFIX, APPROX, QUEUE_SIZE, SUB0, SUB1, SUB2)
Definition: CommonDataSubscriberDefines.h:127
ros::TransportHints
image_transport::SubscriberFilter::subscribe
void subscribe(ImageTransport &it, const std::string &base_topic, uint32_t queue_size, const TransportHints &transport_hints=TransportHints())
rtabmap_sync::CommonDataSubscriber::commonSingleCameraCallback
void commonSingleCameraCallback(const nav_msgs::OdometryConstPtr &odomMsg, const rtabmap_msgs::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_msgs::OdomInfoConstPtr &odomInfoMsg, const std::vector< rtabmap_msgs::GlobalDescriptor > &globalDescriptorMsgs=std::vector< rtabmap_msgs::GlobalDescriptor >(), const std::vector< rtabmap_msgs::KeyPoint > &localKeyPoints=std::vector< rtabmap_msgs::KeyPoint >(), const std::vector< rtabmap_msgs::Point3f > &localPoints3d=std::vector< rtabmap_msgs::Point3f >(), const cv::Mat &localDescriptors=cv::Mat())
Definition: CommonDataSubscriber.cpp:1048
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
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
ros::NodeHandle::resolveName
std::string resolveName(const std::string &name, bool remap=true) const
rtabmap_sync::CommonDataSubscriber::setupDepthCallbacks
void setupDepthCallbacks(ros::NodeHandle &nh, ros::NodeHandle &pnh, bool subscribeOdom, bool subscribeUserData, bool subscribeScan2d, bool subscribeScan3d, bool subscribeScanDesc, bool subscribeOdomInfo)
Definition: CommonDataSubscriberDepth.cpp:458
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
rtabmap_sync::CommonDataSubscriber::imageSub_
image_transport::SubscriberFilter imageSub_
Definition: CommonDataSubscriber.h:263
SYNC_DECL5
#define SYNC_DECL5(CLASS, PREFIX, APPROX, QUEUE_SIZE, SUB0, SUB1, SUB2, SUB3, SUB4)
Definition: CommonDataSubscriberDefines.h:168
message_filters::Subscriber::subscribe
void subscribe()
rtabmap_sync::CommonDataSubscriber::approxSync_
bool approxSync_
Definition: CommonDataSubscriber.h:249
rtabmap_sync::CommonDataSubscriber::odomSub_
message_filters::Subscriber< nav_msgs::Odometry > odomSub_
Definition: CommonDataSubscriber.h:283
SYNC_DECL4
#define SYNC_DECL4(CLASS, PREFIX, APPROX, QUEUE_SIZE, SUB0, SUB1, SUB2, SUB3)
Definition: CommonDataSubscriberDefines.h:147
rtabmap_sync::CommonDataSubscriber::subscribedToOdomInfo_
bool subscribedToOdomInfo_
Definition: CommonDataSubscriber.h:259
rtabmap_sync::CommonDataSubscriber::subscribedToScan2d_
bool subscribedToScan2d_
Definition: CommonDataSubscriber.h:256
image_transport::TransportHints
cv_bridge::toCvShare
CvImageConstPtr toCvShare(const sensor_msgs::Image &source, const boost::shared_ptr< void const > &tracked_object, const std::string &encoding=std::string())
ROS_INFO
#define ROS_INFO(...)
rtabmap_sync::CommonDataSubscriber::userDataSub_
message_filters::Subscriber< rtabmap_msgs::UserData > userDataSub_
Definition: CommonDataSubscriber.h:284
rtabmap_sync::CommonDataSubscriber::cameraInfoSub_
message_filters::Subscriber< sensor_msgs::CameraInfo > cameraInfoSub_
Definition: CommonDataSubscriber.h:265
rtabmap_sync::CommonDataSubscriber
Definition: CommonDataSubscriber.h:61
ros::NodeHandle
SYNC_DECL7
#define SYNC_DECL7(CLASS, PREFIX, APPROX, QUEUE_SIZE, SUB0, SUB1, SUB2, SUB3, SUB4, SUB5, SUB6)
Definition: CommonDataSubscriberDefines.h:213


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