33 const sensor_msgs::LaserScanConstPtr& scanMsg)
35 rtabmap_msgs::UserDataConstPtr userDataMsg;
36 nav_msgs::OdometryConstPtr odomMsg;
37 sensor_msgs::PointCloud2 scan3dMsg;
38 rtabmap_msgs::OdomInfoConstPtr odomInfoMsg;
42 const sensor_msgs::PointCloud2ConstPtr& scanMsg)
44 rtabmap_msgs::UserDataConstPtr userDataMsg;
45 nav_msgs::OdometryConstPtr odomMsg;
46 sensor_msgs::LaserScan scan2dMsg;
47 rtabmap_msgs::OdomInfoConstPtr odomInfoMsg;
51 const rtabmap_msgs::ScanDescriptorConstPtr& scanMsg)
53 rtabmap_msgs::UserDataConstPtr userDataMsg;
54 nav_msgs::OdometryConstPtr odomMsg;
55 rtabmap_msgs::OdomInfoConstPtr odomInfoMsg;
56 commonLaserScanCallback(odomMsg, userDataMsg, scanMsg->scan, scanMsg->scan_cloud, odomInfoMsg, scanMsg->global_descriptor);
58 void CommonDataSubscriber::scan2dInfoCallback(
59 const sensor_msgs::LaserScanConstPtr& scanMsg,
60 const rtabmap_msgs::OdomInfoConstPtr& odomInfoMsg)
62 rtabmap_msgs::UserDataConstPtr userDataMsg;
63 nav_msgs::OdometryConstPtr odomMsg;
64 sensor_msgs::PointCloud2 scan3dMsg;
67 void CommonDataSubscriber::scan3dInfoCallback(
68 const sensor_msgs::PointCloud2ConstPtr& scanMsg,
69 const rtabmap_msgs::OdomInfoConstPtr& odomInfoMsg)
71 rtabmap_msgs::UserDataConstPtr userDataMsg;
72 nav_msgs::OdometryConstPtr odomMsg;
73 sensor_msgs::LaserScan scan2dMsg;
76 void CommonDataSubscriber::scanDescInfoCallback(
77 const rtabmap_msgs::ScanDescriptorConstPtr& scanMsg,
78 const rtabmap_msgs::OdomInfoConstPtr& odomInfoMsg)
80 rtabmap_msgs::UserDataConstPtr userDataMsg;
81 nav_msgs::OdometryConstPtr odomMsg;
82 commonLaserScanCallback(odomMsg, userDataMsg, scanMsg->scan, scanMsg->scan_cloud, odomInfoMsg, scanMsg->global_descriptor);
85 void CommonDataSubscriber::odomScan2dCallback(
86 const nav_msgs::OdometryConstPtr & odomMsg,
87 const sensor_msgs::LaserScanConstPtr& scanMsg)
89 rtabmap_msgs::UserDataConstPtr userDataMsg;
90 sensor_msgs::PointCloud2 scan3dMsg;
91 rtabmap_msgs::OdomInfoConstPtr odomInfoMsg;
94 void CommonDataSubscriber::odomScan3dCallback(
95 const nav_msgs::OdometryConstPtr & odomMsg,
96 const sensor_msgs::PointCloud2ConstPtr& scanMsg)
98 rtabmap_msgs::UserDataConstPtr userDataMsg;
99 sensor_msgs::LaserScan scan2dMsg;
100 rtabmap_msgs::OdomInfoConstPtr odomInfoMsg;
103 void CommonDataSubscriber::odomScanDescCallback(
104 const nav_msgs::OdometryConstPtr & odomMsg,
105 const rtabmap_msgs::ScanDescriptorConstPtr& scanMsg)
107 rtabmap_msgs::UserDataConstPtr userDataMsg;
108 rtabmap_msgs::OdomInfoConstPtr odomInfoMsg;
109 commonLaserScanCallback(odomMsg, userDataMsg, scanMsg->scan, scanMsg->scan_cloud, odomInfoMsg, scanMsg->global_descriptor);
111 void CommonDataSubscriber::odomScan2dInfoCallback(
112 const nav_msgs::OdometryConstPtr & odomMsg,
113 const sensor_msgs::LaserScanConstPtr& scanMsg,
114 const rtabmap_msgs::OdomInfoConstPtr& odomInfoMsg)
116 rtabmap_msgs::UserDataConstPtr userDataMsg;
117 sensor_msgs::PointCloud2 scan3dMsg;
120 void CommonDataSubscriber::odomScan3dInfoCallback(
121 const nav_msgs::OdometryConstPtr & odomMsg,
122 const sensor_msgs::PointCloud2ConstPtr& scanMsg,
123 const rtabmap_msgs::OdomInfoConstPtr& odomInfoMsg)
125 rtabmap_msgs::UserDataConstPtr userDataMsg;
126 sensor_msgs::LaserScan scan2dMsg;
129 void CommonDataSubscriber::odomScanDescInfoCallback(
130 const nav_msgs::OdometryConstPtr & odomMsg,
131 const rtabmap_msgs::ScanDescriptorConstPtr& scanMsg,
132 const rtabmap_msgs::OdomInfoConstPtr& odomInfoMsg)
134 rtabmap_msgs::UserDataConstPtr userDataMsg;
135 commonLaserScanCallback(odomMsg, userDataMsg, scanMsg->scan, scanMsg->scan_cloud, odomInfoMsg, scanMsg->global_descriptor);
138 #ifdef RTABMAP_SYNC_USER_DATA
139 void CommonDataSubscriber::dataScan2dCallback(
140 const rtabmap_msgs::UserDataConstPtr & userDataMsg,
141 const sensor_msgs::LaserScanConstPtr& scanMsg)
143 nav_msgs::OdometryConstPtr odomMsg;
144 sensor_msgs::PointCloud2 scan3dMsg;
145 rtabmap_msgs::OdomInfoConstPtr odomInfoMsg;
148 void CommonDataSubscriber::dataScan3dCallback(
149 const rtabmap_msgs::UserDataConstPtr & userDataMsg,
150 const sensor_msgs::PointCloud2ConstPtr& scanMsg)
152 nav_msgs::OdometryConstPtr odomMsg;
153 sensor_msgs::LaserScan scan2dMsg;
154 rtabmap_msgs::OdomInfoConstPtr odomInfoMsg;
157 void CommonDataSubscriber::dataScanDescCallback(
158 const rtabmap_msgs::UserDataConstPtr & userDataMsg,
159 const rtabmap_msgs::ScanDescriptorConstPtr& scanMsg)
161 nav_msgs::OdometryConstPtr odomMsg;
162 rtabmap_msgs::OdomInfoConstPtr odomInfoMsg;
163 commonLaserScanCallback(odomMsg, userDataMsg, scanMsg->scan, scanMsg->scan_cloud, odomInfoMsg, scanMsg->global_descriptor);
165 void CommonDataSubscriber::dataScan2dInfoCallback(
166 const rtabmap_msgs::UserDataConstPtr & userDataMsg,
167 const sensor_msgs::LaserScanConstPtr& scanMsg,
168 const rtabmap_msgs::OdomInfoConstPtr& odomInfoMsg)
170 nav_msgs::OdometryConstPtr odomMsg;
171 sensor_msgs::PointCloud2 scan3dMsg;
174 void CommonDataSubscriber::dataScan3dInfoCallback(
175 const rtabmap_msgs::UserDataConstPtr & userDataMsg,
176 const sensor_msgs::PointCloud2ConstPtr& scanMsg,
177 const rtabmap_msgs::OdomInfoConstPtr& odomInfoMsg)
179 nav_msgs::OdometryConstPtr odomMsg;
180 sensor_msgs::LaserScan scan2dMsg;
183 void CommonDataSubscriber::dataScanDescInfoCallback(
184 const rtabmap_msgs::UserDataConstPtr & userDataMsg,
185 const rtabmap_msgs::ScanDescriptorConstPtr& scanMsg,
186 const rtabmap_msgs::OdomInfoConstPtr& odomInfoMsg)
188 nav_msgs::OdometryConstPtr odomMsg;
189 commonLaserScanCallback(odomMsg, userDataMsg, scanMsg->scan, scanMsg->scan_cloud, odomInfoMsg, scanMsg->global_descriptor);
192 void CommonDataSubscriber::odomDataScan2dCallback(
193 const nav_msgs::OdometryConstPtr & odomMsg,
194 const rtabmap_msgs::UserDataConstPtr & userDataMsg,
195 const sensor_msgs::LaserScanConstPtr& scanMsg)
197 sensor_msgs::PointCloud2 scan3dMsg;
198 rtabmap_msgs::OdomInfoConstPtr odomInfoMsg;
201 void CommonDataSubscriber::odomDataScan3dCallback(
202 const nav_msgs::OdometryConstPtr & odomMsg,
203 const rtabmap_msgs::UserDataConstPtr & userDataMsg,
204 const sensor_msgs::PointCloud2ConstPtr& scanMsg)
206 sensor_msgs::LaserScan scan2dMsg;
207 rtabmap_msgs::OdomInfoConstPtr odomInfoMsg;
210 void CommonDataSubscriber::odomDataScanDescCallback(
211 const nav_msgs::OdometryConstPtr & odomMsg,
212 const rtabmap_msgs::UserDataConstPtr & userDataMsg,
213 const rtabmap_msgs::ScanDescriptorConstPtr& scanMsg)
215 rtabmap_msgs::OdomInfoConstPtr odomInfoMsg;
216 commonLaserScanCallback(odomMsg, userDataMsg, scanMsg->scan, scanMsg->scan_cloud, odomInfoMsg, scanMsg->global_descriptor);
218 void CommonDataSubscriber::odomDataScan2dInfoCallback(
219 const nav_msgs::OdometryConstPtr & odomMsg,
220 const rtabmap_msgs::UserDataConstPtr & userDataMsg,
221 const sensor_msgs::LaserScanConstPtr& scanMsg,
222 const rtabmap_msgs::OdomInfoConstPtr& odomInfoMsg)
224 sensor_msgs::PointCloud2 scan3dMsg;
227 void CommonDataSubscriber::odomDataScan3dInfoCallback(
228 const nav_msgs::OdometryConstPtr & odomMsg,
229 const rtabmap_msgs::UserDataConstPtr & userDataMsg,
230 const sensor_msgs::PointCloud2ConstPtr& scanMsg,
231 const rtabmap_msgs::OdomInfoConstPtr& odomInfoMsg)
233 sensor_msgs::LaserScan scan2dMsg;
236 void CommonDataSubscriber::odomDataScanDescInfoCallback(
237 const nav_msgs::OdometryConstPtr & odomMsg,
238 const rtabmap_msgs::UserDataConstPtr & userDataMsg,
239 const rtabmap_msgs::ScanDescriptorConstPtr& scanMsg,
240 const rtabmap_msgs::OdomInfoConstPtr& odomInfoMsg)
242 commonLaserScanCallback(odomMsg, userDataMsg, scanMsg->scan, scanMsg->scan_cloud, odomInfoMsg, scanMsg->global_descriptor);
252 bool subscribeUserData,
253 bool subscribeOdomInfo)
257 if(subscribeOdom || subscribeUserData || subscribeOdomInfo)
275 #ifdef RTABMAP_SYNC_USER_DATA
276 if(subscribeOdom && subscribeUserData)
283 if(subscribeOdomInfo)
296 if(subscribeOdomInfo)
309 if(subscribeOdomInfo)
329 if(subscribeOdomInfo)
342 if(subscribeOdomInfo)
355 if(subscribeOdomInfo)
367 #ifdef RTABMAP_SYNC_USER_DATA
368 else if(subscribeUserData)
374 if(subscribeOdomInfo)
387 if(subscribeOdomInfo)
400 if(subscribeOdomInfo)
413 else if(subscribeOdomInfo)
438 uFormat(
"\n%s subscribed to:\n %s",
447 uFormat(
"\n%s subscribed to:\n %s",
456 uFormat(
"\n%s subscribed to:\n %s",