CommonDataSubscriberRGB.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
33 void CommonDataSubscriber::rgbCallback(
34  const sensor_msgs::ImageConstPtr& imageMsg,
35  const sensor_msgs::CameraInfoConstPtr& cameraInfoMsg)
36 {
37  rtabmap_msgs::UserDataConstPtr userDataMsg; // Null
38  nav_msgs::OdometryConstPtr odomMsg; // Null
39  sensor_msgs::LaserScan scanMsg; // Null
40  sensor_msgs::PointCloud2 scan3dMsg; // Null
41  rtabmap_msgs::OdomInfoConstPtr odomInfoMsg; // null
42  cv_bridge::CvImageConstPtr depthMsg;// Null
43  commonSingleCameraCallback(odomMsg, userDataMsg, cv_bridge::toCvShare(imageMsg), depthMsg, *cameraInfoMsg, *cameraInfoMsg, scanMsg, scan3dMsg, odomInfoMsg);
44 }
45 void CommonDataSubscriber::rgbScan2dCallback(
46  const sensor_msgs::ImageConstPtr& imageMsg,
47  const sensor_msgs::CameraInfoConstPtr& cameraInfoMsg,
48  const sensor_msgs::LaserScanConstPtr& scanMsg)
49 {
50  rtabmap_msgs::UserDataConstPtr userDataMsg; // Null
51  nav_msgs::OdometryConstPtr odomMsg; // Null
52  sensor_msgs::PointCloud2 scan3dMsg; // Null
53  rtabmap_msgs::OdomInfoConstPtr odomInfoMsg; // null
54  cv_bridge::CvImageConstPtr depthMsg;// Null
55  commonSingleCameraCallback(odomMsg, userDataMsg, cv_bridge::toCvShare(imageMsg), depthMsg, *cameraInfoMsg, *cameraInfoMsg, *scanMsg, scan3dMsg, odomInfoMsg);
56 }
57 void CommonDataSubscriber::rgbScan3dCallback(
58  const sensor_msgs::ImageConstPtr& imageMsg,
59  const sensor_msgs::CameraInfoConstPtr& cameraInfoMsg,
60  const sensor_msgs::PointCloud2ConstPtr& scanMsg)
61 {
62  rtabmap_msgs::UserDataConstPtr userDataMsg; // Null
63  nav_msgs::OdometryConstPtr odomMsg; // Null
64  sensor_msgs::LaserScan scan2dMsg; // Null
65  rtabmap_msgs::OdomInfoConstPtr odomInfoMsg; // null
66  cv_bridge::CvImageConstPtr depthMsg;// Null
67  commonSingleCameraCallback(odomMsg, userDataMsg, cv_bridge::toCvShare(imageMsg), depthMsg, *cameraInfoMsg, *cameraInfoMsg, scan2dMsg, *scanMsg, odomInfoMsg);
68 }
69 void CommonDataSubscriber::rgbScanDescCallback(
70  const sensor_msgs::ImageConstPtr& imageMsg,
71  const sensor_msgs::CameraInfoConstPtr& cameraInfoMsg,
72  const rtabmap_msgs::ScanDescriptorConstPtr& scanMsg)
73 {
74  rtabmap_msgs::UserDataConstPtr userDataMsg; // Null
75  nav_msgs::OdometryConstPtr odomMsg; // Null
76  rtabmap_msgs::OdomInfoConstPtr odomInfoMsg; // null
77  cv_bridge::CvImageConstPtr depthMsg;// 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), depthMsg, *cameraInfoMsg, *cameraInfoMsg, scanMsg->scan, scanMsg->scan_cloud, odomInfoMsg, globalDescriptor);
84 }
85 void CommonDataSubscriber::rgbInfoCallback(
86  const sensor_msgs::ImageConstPtr& imageMsg,
87  const sensor_msgs::CameraInfoConstPtr& cameraInfoMsg,
88  const rtabmap_msgs::OdomInfoConstPtr& odomInfoMsg)
89 {
90  rtabmap_msgs::UserDataConstPtr userDataMsg; // Null
91  nav_msgs::OdometryConstPtr odomMsg; // Null
92  sensor_msgs::LaserScan scan2dMsg; // Null
93  sensor_msgs::PointCloud2 scan3dMsg; // Null
94  cv_bridge::CvImageConstPtr depthMsg;// Null
95  commonSingleCameraCallback(odomMsg, userDataMsg, cv_bridge::toCvShare(imageMsg), depthMsg, *cameraInfoMsg, *cameraInfoMsg, scan2dMsg, scan3dMsg, odomInfoMsg);
96 }
97 void CommonDataSubscriber::rgbScan2dInfoCallback(
98  const sensor_msgs::ImageConstPtr& imageMsg,
99  const sensor_msgs::CameraInfoConstPtr& cameraInfoMsg,
100  const sensor_msgs::LaserScanConstPtr& scanMsg,
101  const rtabmap_msgs::OdomInfoConstPtr& odomInfoMsg)
102 {
103  rtabmap_msgs::UserDataConstPtr userDataMsg; // Null
104  nav_msgs::OdometryConstPtr odomMsg; // Null
105  sensor_msgs::PointCloud2 scan3dMsg; // Null
106  cv_bridge::CvImageConstPtr depthMsg;// Null
107  commonSingleCameraCallback(odomMsg, userDataMsg, cv_bridge::toCvShare(imageMsg), depthMsg, *cameraInfoMsg, *cameraInfoMsg, *scanMsg, scan3dMsg, odomInfoMsg);
108 }
109 void CommonDataSubscriber::rgbScan3dInfoCallback(
110  const sensor_msgs::ImageConstPtr& imageMsg,
111  const sensor_msgs::CameraInfoConstPtr& cameraInfoMsg,
112  const sensor_msgs::PointCloud2ConstPtr& scanMsg,
113  const rtabmap_msgs::OdomInfoConstPtr& odomInfoMsg)
114 {
115  rtabmap_msgs::UserDataConstPtr userDataMsg; // Null
116  nav_msgs::OdometryConstPtr odomMsg; // Null
117  sensor_msgs::LaserScan scan2dMsg; // Null
118  cv_bridge::CvImageConstPtr depthMsg;// Null
119  commonSingleCameraCallback(odomMsg, userDataMsg, cv_bridge::toCvShare(imageMsg), depthMsg, *cameraInfoMsg, *cameraInfoMsg, scan2dMsg, *scanMsg, odomInfoMsg);
120 }
121 void CommonDataSubscriber::rgbScanDescInfoCallback(
122  const sensor_msgs::ImageConstPtr& imageMsg,
123  const sensor_msgs::CameraInfoConstPtr& cameraInfoMsg,
124  const rtabmap_msgs::ScanDescriptorConstPtr& scanMsg,
125  const rtabmap_msgs::OdomInfoConstPtr& odomInfoMsg)
126 {
127  rtabmap_msgs::UserDataConstPtr userDataMsg; // Null
128  nav_msgs::OdometryConstPtr odomMsg; // Null
129  cv_bridge::CvImageConstPtr depthMsg;// 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), depthMsg, *cameraInfoMsg, *cameraInfoMsg, scanMsg->scan, scanMsg->scan_cloud, odomInfoMsg, globalDescriptor);
136 }
137 
138 // RGB + Odom
139 void CommonDataSubscriber::rgbOdomCallback(
140  const nav_msgs::OdometryConstPtr & odomMsg,
141  const sensor_msgs::ImageConstPtr& imageMsg,
142  const sensor_msgs::CameraInfoConstPtr& cameraInfoMsg)
143 {
144  rtabmap_msgs::UserDataConstPtr userDataMsg; // Null
145  sensor_msgs::LaserScan scanMsg; // Null
146  sensor_msgs::PointCloud2 scan3dMsg; // null
147  rtabmap_msgs::OdomInfoConstPtr odomInfoMsg; // null
148  cv_bridge::CvImageConstPtr depthMsg;// Null
149  commonSingleCameraCallback(odomMsg, userDataMsg, cv_bridge::toCvShare(imageMsg), depthMsg, *cameraInfoMsg, *cameraInfoMsg, scanMsg, scan3dMsg, odomInfoMsg);
150 }
151 void CommonDataSubscriber::rgbOdomScan2dCallback(
152  const nav_msgs::OdometryConstPtr & odomMsg,
153  const sensor_msgs::ImageConstPtr& imageMsg,
154  const sensor_msgs::CameraInfoConstPtr& cameraInfoMsg,
155  const sensor_msgs::LaserScanConstPtr& scanMsg)
156 {
157  rtabmap_msgs::UserDataConstPtr userDataMsg; // Null
158  sensor_msgs::PointCloud2 scan3dMsg; // Null
159  rtabmap_msgs::OdomInfoConstPtr odomInfoMsg; // null
160  cv_bridge::CvImageConstPtr depthMsg;// Null
161  commonSingleCameraCallback(odomMsg, userDataMsg, cv_bridge::toCvShare(imageMsg), depthMsg, *cameraInfoMsg, *cameraInfoMsg, *scanMsg, scan3dMsg, odomInfoMsg);
162 }
163 void CommonDataSubscriber::rgbOdomScan3dCallback(
164  const nav_msgs::OdometryConstPtr & odomMsg,
165  const sensor_msgs::ImageConstPtr& imageMsg,
166  const sensor_msgs::CameraInfoConstPtr& cameraInfoMsg,
167  const sensor_msgs::PointCloud2ConstPtr& scanMsg)
168 {
169  rtabmap_msgs::UserDataConstPtr userDataMsg; // Null
170  sensor_msgs::LaserScan scan2dMsg; // Null
171  rtabmap_msgs::OdomInfoConstPtr odomInfoMsg; // null
172  cv_bridge::CvImageConstPtr depthMsg;// Null
173  commonSingleCameraCallback(odomMsg, userDataMsg, cv_bridge::toCvShare(imageMsg), depthMsg, *cameraInfoMsg, *cameraInfoMsg, scan2dMsg, *scanMsg, odomInfoMsg);
174 }
175 void CommonDataSubscriber::rgbOdomScanDescCallback(
176  const nav_msgs::OdometryConstPtr & odomMsg,
177  const sensor_msgs::ImageConstPtr& imageMsg,
178  const sensor_msgs::CameraInfoConstPtr& cameraInfoMsg,
179  const rtabmap_msgs::ScanDescriptorConstPtr& scanMsg)
180 {
181  rtabmap_msgs::UserDataConstPtr userDataMsg; // Null
182  rtabmap_msgs::OdomInfoConstPtr odomInfoMsg; // null
183  cv_bridge::CvImageConstPtr depthMsg;// 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), depthMsg, *cameraInfoMsg, *cameraInfoMsg, scanMsg->scan, scanMsg->scan_cloud, odomInfoMsg, globalDescriptor);
190 }
191 void CommonDataSubscriber::rgbOdomInfoCallback(
192  const nav_msgs::OdometryConstPtr & odomMsg,
193  const sensor_msgs::ImageConstPtr& imageMsg,
194  const sensor_msgs::CameraInfoConstPtr& cameraInfoMsg,
195  const rtabmap_msgs::OdomInfoConstPtr& odomInfoMsg)
196 {
197  rtabmap_msgs::UserDataConstPtr userDataMsg; // Null
198  sensor_msgs::LaserScan scan2dMsg; // Null
199  sensor_msgs::PointCloud2 scan3dMsg; // Null
200  cv_bridge::CvImageConstPtr depthMsg;// Null
201  commonSingleCameraCallback(odomMsg, userDataMsg, cv_bridge::toCvShare(imageMsg), depthMsg, *cameraInfoMsg, *cameraInfoMsg, scan2dMsg, scan3dMsg, odomInfoMsg);
202 }
203 void CommonDataSubscriber::rgbOdomScan2dInfoCallback(
204  const nav_msgs::OdometryConstPtr & odomMsg,
205  const sensor_msgs::ImageConstPtr& imageMsg,
206  const sensor_msgs::CameraInfoConstPtr& cameraInfoMsg,
207  const sensor_msgs::LaserScanConstPtr& scanMsg,
208  const rtabmap_msgs::OdomInfoConstPtr& odomInfoMsg)
209 {
210  rtabmap_msgs::UserDataConstPtr userDataMsg; // Null
211  sensor_msgs::PointCloud2 scan3dMsg; // Null
212  cv_bridge::CvImageConstPtr depthMsg;// Null
213  commonSingleCameraCallback(odomMsg, userDataMsg, cv_bridge::toCvShare(imageMsg), depthMsg, *cameraInfoMsg, *cameraInfoMsg, *scanMsg, scan3dMsg, odomInfoMsg);
214 }
215 void CommonDataSubscriber::rgbOdomScan3dInfoCallback(
216  const nav_msgs::OdometryConstPtr & odomMsg,
217  const sensor_msgs::ImageConstPtr& imageMsg,
218  const sensor_msgs::CameraInfoConstPtr& cameraInfoMsg,
219  const sensor_msgs::PointCloud2ConstPtr& scanMsg,
220  const rtabmap_msgs::OdomInfoConstPtr& odomInfoMsg)
221 {
222  rtabmap_msgs::UserDataConstPtr userDataMsg; // Null
223  sensor_msgs::LaserScan scan2dMsg; // Null
224  cv_bridge::CvImageConstPtr depthMsg;// Null
225  commonSingleCameraCallback(odomMsg, userDataMsg, cv_bridge::toCvShare(imageMsg), depthMsg, *cameraInfoMsg, *cameraInfoMsg, scan2dMsg, *scanMsg, odomInfoMsg);
226 }
227 void CommonDataSubscriber::rgbOdomScanDescInfoCallback(
228  const nav_msgs::OdometryConstPtr & odomMsg,
229  const sensor_msgs::ImageConstPtr& imageMsg,
230  const sensor_msgs::CameraInfoConstPtr& cameraInfoMsg,
231  const rtabmap_msgs::ScanDescriptorConstPtr& scanMsg,
232  const rtabmap_msgs::OdomInfoConstPtr& odomInfoMsg)
233 {
234  rtabmap_msgs::UserDataConstPtr userDataMsg; // Null
235  cv_bridge::CvImageConstPtr depthMsg;// 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), 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::rgbDataCallback(
247  const rtabmap_msgs::UserDataConstPtr & userDataMsg,
248  const sensor_msgs::ImageConstPtr& imageMsg,
249  const sensor_msgs::CameraInfoConstPtr& cameraInfoMsg)
250 {
251  nav_msgs::OdometryConstPtr odomMsg; // Null
252  sensor_msgs::LaserScan scanMsg; // Null
253  sensor_msgs::PointCloud2 scan3dMsg; // null
254  rtabmap_msgs::OdomInfoConstPtr odomInfoMsg; // null
255  cv_bridge::CvImageConstPtr depthMsg;// Null
256  commonSingleCameraCallback(odomMsg, userDataMsg, cv_bridge::toCvShare(imageMsg), depthMsg, *cameraInfoMsg, *cameraInfoMsg, scanMsg, scan3dMsg, odomInfoMsg);
257 }
258 void CommonDataSubscriber::rgbDataScan2dCallback(
259  const rtabmap_msgs::UserDataConstPtr & userDataMsg,
260  const sensor_msgs::ImageConstPtr& imageMsg,
261  const sensor_msgs::CameraInfoConstPtr& cameraInfoMsg,
262  const sensor_msgs::LaserScanConstPtr& scanMsg)
263 {
264  nav_msgs::OdometryConstPtr odomMsg; // null
265  sensor_msgs::PointCloud2 scan3dMsg; // Null
266  rtabmap_msgs::OdomInfoConstPtr odomInfoMsg; // null
267  cv_bridge::CvImageConstPtr depthMsg;// Null
268  commonSingleCameraCallback(odomMsg, userDataMsg, cv_bridge::toCvShare(imageMsg), depthMsg, *cameraInfoMsg, *cameraInfoMsg, *scanMsg, scan3dMsg, odomInfoMsg);
269 }
270 void CommonDataSubscriber::rgbDataScan3dCallback(
271  const rtabmap_msgs::UserDataConstPtr & userDataMsg,
272  const sensor_msgs::ImageConstPtr& imageMsg,
273  const sensor_msgs::CameraInfoConstPtr& cameraInfoMsg,
274  const sensor_msgs::PointCloud2ConstPtr& scanMsg)
275 {
276  nav_msgs::OdometryConstPtr odomMsg; // null
277  sensor_msgs::LaserScan scan2dMsg; // Null
278  rtabmap_msgs::OdomInfoConstPtr odomInfoMsg; // null
279  cv_bridge::CvImageConstPtr depthMsg;// Null
280  commonSingleCameraCallback(odomMsg, userDataMsg, cv_bridge::toCvShare(imageMsg), depthMsg, *cameraInfoMsg, *cameraInfoMsg, scan2dMsg, *scanMsg, odomInfoMsg);
281 }
282 void CommonDataSubscriber::rgbDataScanDescCallback(
283  const rtabmap_msgs::UserDataConstPtr & userDataMsg,
284  const sensor_msgs::ImageConstPtr& imageMsg,
285  const sensor_msgs::CameraInfoConstPtr& cameraInfoMsg,
286  const rtabmap_msgs::ScanDescriptorConstPtr& scanMsg)
287 {
288  nav_msgs::OdometryConstPtr odomMsg; // null
289  rtabmap_msgs::OdomInfoConstPtr odomInfoMsg; // null
290  cv_bridge::CvImageConstPtr depthMsg;// 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), depthMsg, *cameraInfoMsg, *cameraInfoMsg, scanMsg->scan, scanMsg->scan_cloud, odomInfoMsg, globalDescriptor);
297 }
298 void CommonDataSubscriber::rgbDataInfoCallback(
299  const rtabmap_msgs::UserDataConstPtr & userDataMsg,
300  const sensor_msgs::ImageConstPtr& imageMsg,
301  const sensor_msgs::CameraInfoConstPtr& cameraInfoMsg,
302  const rtabmap_msgs::OdomInfoConstPtr& odomInfoMsg)
303 {
304  nav_msgs::OdometryConstPtr odomMsg; // null
305  sensor_msgs::LaserScan scan2dMsg; // Null
306  sensor_msgs::PointCloud2 scan3dMsg; // Null
307  cv_bridge::CvImageConstPtr depthMsg;// Null
308  commonSingleCameraCallback(odomMsg, userDataMsg, cv_bridge::toCvShare(imageMsg), depthMsg, *cameraInfoMsg, *cameraInfoMsg, scan2dMsg, scan3dMsg, odomInfoMsg);
309 }
310 void CommonDataSubscriber::rgbDataScan2dInfoCallback(
311  const rtabmap_msgs::UserDataConstPtr & userDataMsg,
312  const sensor_msgs::ImageConstPtr& imageMsg,
313  const sensor_msgs::CameraInfoConstPtr& cameraInfoMsg,
314  const sensor_msgs::LaserScanConstPtr& scanMsg,
315  const rtabmap_msgs::OdomInfoConstPtr& odomInfoMsg)
316 {
317  nav_msgs::OdometryConstPtr odomMsg; // null
318  sensor_msgs::PointCloud2 scan3dMsg; // Null
319  cv_bridge::CvImageConstPtr depthMsg;// Null
320  commonSingleCameraCallback(odomMsg, userDataMsg, cv_bridge::toCvShare(imageMsg), depthMsg, *cameraInfoMsg, *cameraInfoMsg, *scanMsg, scan3dMsg, odomInfoMsg);
321 }
322 void CommonDataSubscriber::rgbDataScan3dInfoCallback(
323  const rtabmap_msgs::UserDataConstPtr & userDataMsg,
324  const sensor_msgs::ImageConstPtr& imageMsg,
325  const sensor_msgs::CameraInfoConstPtr& cameraInfoMsg,
326  const sensor_msgs::PointCloud2ConstPtr& scanMsg,
327  const rtabmap_msgs::OdomInfoConstPtr& odomInfoMsg)
328 {
329  nav_msgs::OdometryConstPtr odomMsg; // null
330  sensor_msgs::LaserScan scan2dMsg; // Null
331  cv_bridge::CvImageConstPtr depthMsg;// Null
332  commonSingleCameraCallback(odomMsg, userDataMsg, cv_bridge::toCvShare(imageMsg), depthMsg, *cameraInfoMsg, *cameraInfoMsg, scan2dMsg, *scanMsg, odomInfoMsg);
333 }
334 void CommonDataSubscriber::rgbDataScanDescInfoCallback(
335  const rtabmap_msgs::UserDataConstPtr & userDataMsg,
336  const sensor_msgs::ImageConstPtr& imageMsg,
337  const sensor_msgs::CameraInfoConstPtr& cameraInfoMsg,
338  const rtabmap_msgs::ScanDescriptorConstPtr& scanMsg,
339  const rtabmap_msgs::OdomInfoConstPtr& odomInfoMsg)
340 {
341  nav_msgs::OdometryConstPtr odomMsg; // null
342  cv_bridge::CvImageConstPtr depthMsg;// 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), depthMsg, *cameraInfoMsg, *cameraInfoMsg, scanMsg->scan, scanMsg->scan_cloud, odomInfoMsg, globalDescriptor);
349 }
350 
351 // RGB + Depth + Odom + User Data
352 void CommonDataSubscriber::rgbOdomDataCallback(
353  const nav_msgs::OdometryConstPtr & odomMsg,
354  const rtabmap_msgs::UserDataConstPtr & userDataMsg,
355  const sensor_msgs::ImageConstPtr& imageMsg,
356  const sensor_msgs::CameraInfoConstPtr& cameraInfoMsg)
357 {
358  sensor_msgs::LaserScan scanMsg; // Null
359  sensor_msgs::PointCloud2 scan3dMsg; // null
360  rtabmap_msgs::OdomInfoConstPtr odomInfoMsg; // null
361  cv_bridge::CvImageConstPtr depthMsg;// Null
362  commonSingleCameraCallback(odomMsg, userDataMsg, cv_bridge::toCvShare(imageMsg), depthMsg, *cameraInfoMsg, *cameraInfoMsg, scanMsg, scan3dMsg, odomInfoMsg);
363 }
364 void CommonDataSubscriber::rgbOdomDataScan2dCallback(
365  const nav_msgs::OdometryConstPtr & odomMsg,
366  const rtabmap_msgs::UserDataConstPtr & userDataMsg,
367  const sensor_msgs::ImageConstPtr& imageMsg,
368  const sensor_msgs::CameraInfoConstPtr& cameraInfoMsg,
369  const sensor_msgs::LaserScanConstPtr& scanMsg)
370 {
371  sensor_msgs::PointCloud2 scan3dMsg; // Null
372  rtabmap_msgs::OdomInfoConstPtr odomInfoMsg; // null
373  cv_bridge::CvImageConstPtr depthMsg;// Null
374  commonSingleCameraCallback(odomMsg, userDataMsg, cv_bridge::toCvShare(imageMsg), depthMsg, *cameraInfoMsg, *cameraInfoMsg, *scanMsg, scan3dMsg, odomInfoMsg);
375 }
376 void CommonDataSubscriber::rgbOdomDataScan3dCallback(
377  const nav_msgs::OdometryConstPtr & odomMsg,
378  const rtabmap_msgs::UserDataConstPtr & userDataMsg,
379  const sensor_msgs::ImageConstPtr& imageMsg,
380  const sensor_msgs::CameraInfoConstPtr& cameraInfoMsg,
381  const sensor_msgs::PointCloud2ConstPtr& scanMsg)
382 {
383  sensor_msgs::LaserScan scan2dMsg; // Null
384  rtabmap_msgs::OdomInfoConstPtr odomInfoMsg; // null
385  cv_bridge::CvImageConstPtr depthMsg;// Null
386  commonSingleCameraCallback(odomMsg, userDataMsg, cv_bridge::toCvShare(imageMsg), depthMsg, *cameraInfoMsg, *cameraInfoMsg, scan2dMsg, *scanMsg, odomInfoMsg);
387 }
388 void CommonDataSubscriber::rgbOdomDataScanDescCallback(
389  const nav_msgs::OdometryConstPtr & odomMsg,
390  const rtabmap_msgs::UserDataConstPtr & userDataMsg,
391  const sensor_msgs::ImageConstPtr& imageMsg,
392  const sensor_msgs::CameraInfoConstPtr& cameraInfoMsg,
393  const rtabmap_msgs::ScanDescriptorConstPtr& scanMsg)
394 {
395  rtabmap_msgs::OdomInfoConstPtr odomInfoMsg; // null
396  cv_bridge::CvImageConstPtr depthMsg;// 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), depthMsg, *cameraInfoMsg, *cameraInfoMsg, scanMsg->scan, scanMsg->scan_cloud, odomInfoMsg, globalDescriptor);
403 }
404 void CommonDataSubscriber::rgbOdomDataInfoCallback(
405  const nav_msgs::OdometryConstPtr & odomMsg,
406  const rtabmap_msgs::UserDataConstPtr & userDataMsg,
407  const sensor_msgs::ImageConstPtr& imageMsg,
408  const sensor_msgs::CameraInfoConstPtr& cameraInfoMsg,
409  const rtabmap_msgs::OdomInfoConstPtr& odomInfoMsg)
410 {
411  sensor_msgs::LaserScan scan2dMsg; // Null
412  sensor_msgs::PointCloud2 scan3dMsg; // Null
413  cv_bridge::CvImageConstPtr depthMsg;// Null
414  commonSingleCameraCallback(odomMsg, userDataMsg, cv_bridge::toCvShare(imageMsg), depthMsg, *cameraInfoMsg, *cameraInfoMsg, scan2dMsg, scan3dMsg, odomInfoMsg);
415 }
416 void CommonDataSubscriber::rgbOdomDataScan2dInfoCallback(
417  const nav_msgs::OdometryConstPtr & odomMsg,
418  const rtabmap_msgs::UserDataConstPtr & userDataMsg,
419  const sensor_msgs::ImageConstPtr& imageMsg,
420  const sensor_msgs::CameraInfoConstPtr& cameraInfoMsg,
421  const sensor_msgs::LaserScanConstPtr& scanMsg,
422  const rtabmap_msgs::OdomInfoConstPtr& odomInfoMsg)
423 {
424  sensor_msgs::PointCloud2 scan3dMsg; // Null
425  cv_bridge::CvImageConstPtr depthMsg;// Null
426  commonSingleCameraCallback(odomMsg, userDataMsg, cv_bridge::toCvShare(imageMsg), depthMsg, *cameraInfoMsg, *cameraInfoMsg, *scanMsg, scan3dMsg, odomInfoMsg);
427 }
428 void CommonDataSubscriber::rgbOdomDataScan3dInfoCallback(
429  const nav_msgs::OdometryConstPtr & odomMsg,
430  const rtabmap_msgs::UserDataConstPtr & userDataMsg,
431  const sensor_msgs::ImageConstPtr& imageMsg,
432  const sensor_msgs::CameraInfoConstPtr& cameraInfoMsg,
433  const sensor_msgs::PointCloud2ConstPtr& scanMsg,
434  const rtabmap_msgs::OdomInfoConstPtr& odomInfoMsg)
435 {
436  sensor_msgs::LaserScan scan2dMsg; // Null
437  cv_bridge::CvImageConstPtr depthMsg;// Null
438  commonSingleCameraCallback(odomMsg, userDataMsg, cv_bridge::toCvShare(imageMsg), depthMsg, *cameraInfoMsg, *cameraInfoMsg, scan2dMsg, *scanMsg, odomInfoMsg);
439 }
440 void CommonDataSubscriber::rgbOdomDataScanDescInfoCallback(
441  const nav_msgs::OdometryConstPtr & odomMsg,
442  const rtabmap_msgs::UserDataConstPtr & userDataMsg,
443  const sensor_msgs::ImageConstPtr& imageMsg,
444  const sensor_msgs::CameraInfoConstPtr& cameraInfoMsg,
445  const rtabmap_msgs::ScanDescriptorConstPtr& scanMsg,
446  const rtabmap_msgs::OdomInfoConstPtr& odomInfoMsg)
447 {
448  cv_bridge::CvImageConstPtr depthMsg;// Null
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), 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 rgb-only callback");
469 
470  std::string rgbPrefix = "rgb";
471  ros::NodeHandle rgb_nh(nh, rgbPrefix);
472  ros::NodeHandle rgb_pnh(pnh, rgbPrefix);
473  image_transport::ImageTransport rgb_it(rgb_nh);
474  image_transport::TransportHints hintsRgb("raw", ros::TransportHints(), rgb_pnh);
475 
476  imageSub_.subscribe(rgb_it, rgb_nh.resolveName("image"), syncQueueSize_, hintsRgb);
477  cameraInfoSub_.subscribe(rgb_nh, "camera_info", topicQueueSize_);
478 
479 #ifdef RTABMAP_SYNC_USER_DATA
480  if(subscribeOdom && subscribeUserData)
481  {
482  odomSub_.subscribe(nh, "odom", topicQueueSize_);
483  userDataSub_.subscribe(nh, "user_data", topicQueueSize_);
484 
485  if(subscribeScanDesc)
486  {
488  scanDescSub_.subscribe(nh, "scan_descriptor", topicQueueSize_);
489  if(subscribeOdomInfo)
490  {
491  subscribedToOdomInfo_ = true;
492  odomInfoSub_.subscribe(nh, "odom_info", topicQueueSize_);
494  }
495  else
496  {
498  }
499  }
500  else if(subscribeScan2d)
501  {
502  subscribedToScan2d_ = true;
503  scanSub_.subscribe(nh, "scan", topicQueueSize_);
504  if(subscribeOdomInfo)
505  {
506  subscribedToOdomInfo_ = true;
507  odomInfoSub_.subscribe(nh, "odom_info", topicQueueSize_);
509  }
510  else
511  {
513  }
514  }
515  else if(subscribeScan3d)
516  {
517  subscribedToScan3d_ = true;
518  scan3dSub_.subscribe(nh, "scan_cloud", topicQueueSize_);
519  if(subscribeOdomInfo)
520  {
521  subscribedToOdomInfo_ = true;
522  odomInfoSub_.subscribe(nh, "odom_info", topicQueueSize_);
524  }
525  else
526  {
528  }
529  }
530  else if(subscribeOdomInfo)
531  {
532  subscribedToOdomInfo_ = true;
533  odomInfoSub_.subscribe(nh, "odom_info", topicQueueSize_);
535  }
536  else
537  {
539  }
540  }
541  else
542 #endif
543  if(subscribeOdom)
544  {
545  odomSub_.subscribe(nh, "odom", topicQueueSize_);
546 
547  if(subscribeScanDesc)
548  {
550  scanDescSub_.subscribe(nh, "scan_descriptor", topicQueueSize_);
551  if(subscribeOdomInfo)
552  {
553  subscribedToOdomInfo_ = true;
554  odomInfoSub_.subscribe(nh, "odom_info", topicQueueSize_);
556  }
557  else
558  {
560  }
561  }
562  else if(subscribeScan2d)
563  {
564  subscribedToScan2d_ = true;
565  scanSub_.subscribe(nh, "scan", topicQueueSize_);
566  if(subscribeOdomInfo)
567  {
568  subscribedToOdomInfo_ = true;
569  odomInfoSub_.subscribe(nh, "odom_info", topicQueueSize_);
571  }
572  else
573  {
575  }
576  }
577  else if(subscribeScan3d)
578  {
579  subscribedToScan3d_ = true;
580  scan3dSub_.subscribe(nh, "scan_cloud", topicQueueSize_);
581  if(subscribeOdomInfo)
582  {
583  subscribedToOdomInfo_ = true;
584  odomInfoSub_.subscribe(nh, "odom_info", topicQueueSize_);
586  }
587  else
588  {
590  }
591  }
592  else if(subscribeOdomInfo)
593  {
594  subscribedToOdomInfo_ = true;
595  odomInfoSub_.subscribe(nh, "odom_info", topicQueueSize_);
597  }
598  else
599  {
601  }
602  }
603 #ifdef RTABMAP_SYNC_USER_DATA
604  else if(subscribeUserData)
605  {
606  userDataSub_.subscribe(nh, "user_data", topicQueueSize_);
607 
608  if(subscribeScanDesc)
609  {
611  scanDescSub_.subscribe(nh, "scan_descriptor", topicQueueSize_);
612 
613  if(subscribeOdomInfo)
614  {
615  subscribedToOdomInfo_ = true;
616  odomInfoSub_.subscribe(nh, "odom_info", topicQueueSize_);
618  }
619  else
620  {
622  }
623  }
624  else if(subscribeScan2d)
625  {
626  subscribedToScan2d_ = true;
627  scanSub_.subscribe(nh, "scan", topicQueueSize_);
628 
629  if(subscribeOdomInfo)
630  {
631  subscribedToOdomInfo_ = true;
632  odomInfoSub_.subscribe(nh, "odom_info", topicQueueSize_);
634  }
635  else
636  {
638  }
639  }
640  else if(subscribeScan3d)
641  {
642  subscribedToScan3d_ = true;
643  scan3dSub_.subscribe(nh, "scan_cloud", topicQueueSize_);
644  if(subscribeOdomInfo)
645  {
646  subscribedToOdomInfo_ = true;
647  odomInfoSub_.subscribe(nh, "odom_info", topicQueueSize_);
649  }
650  else
651  {
653  }
654  }
655  else if(subscribeOdomInfo)
656  {
657  subscribedToOdomInfo_ = true;
658  odomInfoSub_.subscribe(nh, "odom_info", topicQueueSize_);
660  }
661  else
662  {
664  }
665  }
666 #endif
667  else
668  {
669  if(subscribeScanDesc)
670  {
672  scanDescSub_.subscribe(nh, "scan_descriptor", topicQueueSize_);
673  if(subscribeOdomInfo)
674  {
675  subscribedToOdomInfo_ = true;
676  odomInfoSub_.subscribe(nh, "odom_info", topicQueueSize_);
678  }
679  else
680  {
682  }
683  }
684  else if(subscribeScan2d)
685  {
686  subscribedToScan2d_ = true;
687  scanSub_.subscribe(nh, "scan", topicQueueSize_);
688  if(subscribeOdomInfo)
689  {
690  subscribedToOdomInfo_ = true;
691  odomInfoSub_.subscribe(nh, "odom_info", topicQueueSize_);
693  }
694  else
695  {
697  }
698  }
699  else if(subscribeScan3d)
700  {
701  subscribedToScan3d_ = true;
702  scan3dSub_.subscribe(nh, "scan_cloud", topicQueueSize_);
703  if(subscribeOdomInfo)
704  {
705  subscribedToOdomInfo_ = true;
706  odomInfoSub_.subscribe(nh, "odom_info", topicQueueSize_);
708  }
709  else
710  {
712  }
713  }
714  else if(subscribeOdomInfo)
715  {
716  subscribedToOdomInfo_ = true;
717  odomInfoSub_.subscribe(nh, "odom_info", topicQueueSize_);
719  }
720  else
721  {
723  }
724  }
725 }
726 
727 } /* 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
SYNC_DECL2
#define SYNC_DECL2(CLASS, PREFIX, APPROX, QUEUE_SIZE, SUB0, SUB1)
Definition: CommonDataSubscriberDefines.h:108
boost::shared_ptr
rtabmap_sync::CommonDataSubscriber::setupRGBCallbacks
void setupRGBCallbacks(ros::NodeHandle &nh, ros::NodeHandle &pnh, bool subscribeOdom, bool subscribeUserData, bool subscribeScan2d, bool subscribeScan3d, bool subscribeScanDesc, bool subscribeOdomInfo)
Definition: CommonDataSubscriberRGB.cpp:458
rtabmap_sync
Definition: CommonDataSubscriber.h:59
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::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


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