36 #include <boost/thread.hpp>
38 #include "rtabmap_msgs/RGBDImages.h"
81 int syncQueueSize = 10;
82 bool approxSync =
true;
84 double approxSyncMaxInterval = 0.0;
85 pnh.
param(
"approx_sync", approxSync, approxSync);
86 pnh.
param(
"approx_sync_max_interval", approxSyncMaxInterval, approxSyncMaxInterval);
87 pnh.
param(
"topic_queue_size", queueSize, queueSize);
90 pnh.
param(
"queue_size", syncQueueSize, syncQueueSize);
91 ROS_WARN(
"Parameter \"queue_size\" has been renamed "
92 "to \"sync_queue_size\" and will be removed "
93 "in future versions! The value (%d) is still copied to "
94 "\"sync_queue_size\".", syncQueueSize);
98 pnh.
param(
"sync_queue_size", syncQueueSize, syncQueueSize);
100 pnh.
param(
"rgbd_cameras", rgbdCameras, rgbdCameras);
114 for(
int i=0;
i<rgbdCameras; ++
i)
121 std::string subscribedTopicsMsg_;
125 if(approxSync && approxSyncMaxInterval>0.0)
127 rgbd2ApproximateSync_->setMaxIntervalDuration(
ros::Duration(approxSyncMaxInterval));
130 else if(rgbdCameras==3)
133 if(approxSync && approxSyncMaxInterval>0.0)
135 rgbd3ApproximateSync_->setMaxIntervalDuration(
ros::Duration(approxSyncMaxInterval));
138 else if(rgbdCameras==4)
141 if(approxSync && approxSyncMaxInterval>0.0)
143 rgbd4ApproximateSync_->setMaxIntervalDuration(
ros::Duration(approxSyncMaxInterval));
146 else if(rgbdCameras==5)
149 if(approxSync && approxSyncMaxInterval>0.0)
151 rgbd5ApproximateSync_->setMaxIntervalDuration(
ros::Duration(approxSyncMaxInterval));
154 else if(rgbdCameras==6)
157 if(approxSync && approxSyncMaxInterval>0.0)
159 rgbd6ApproximateSync_->setMaxIntervalDuration(
ros::Duration(approxSyncMaxInterval));
162 else if(rgbdCameras==7)
164 SYNC_DECL7(
RGBDXSync, rgbd7, approxSync, syncQueueSize, (*
rgbdSubs_[0]), (*
rgbdSubs_[1]), (*
rgbdSubs_[2]), (*
rgbdSubs_[3]), (*
rgbdSubs_[4]), (*
rgbdSubs_[5]), (*
rgbdSubs_[6]));
165 if(approxSync && approxSyncMaxInterval>0.0)
167 rgbd7ApproximateSync_->setMaxIntervalDuration(
ros::Duration(approxSyncMaxInterval));
170 else if(rgbdCameras==8)
172 SYNC_DECL8(
RGBDXSync, rgbd8, approxSync, syncQueueSize, (*
rgbdSubs_[0]), (*
rgbdSubs_[1]), (*
rgbdSubs_[2]), (*
rgbdSubs_[3]), (*
rgbdSubs_[4]), (*
rgbdSubs_[5]), (*
rgbdSubs_[6]), (*
rgbdSubs_[7]));
173 if(approxSync && approxSyncMaxInterval>0.0)
175 rgbd8ApproximateSync_->setMaxIntervalDuration(
ros::Duration(approxSyncMaxInterval));
179 std::string subscribedTopicsMsg =
uFormat(
"%s%s", subscribedTopicsMsg_.c_str(),
180 approxSync&&approxSyncMaxInterval!=0.0?
uFormat(
" (approx sync max interval=%fs)", approxSyncMaxInterval).
c_str():
"");
186 uFormat(
"%s: Did not receive data since 5 seconds! Make sure the input topics are "
187 "published (\"$ rostopic hz my_topic\") and the timestamps in their "
188 "header are set. %s%s",
190 approxSync?
"":
"Parameter \"approx_sync\" is false, which means that input "
191 "topics should have all the exact timestamp for the callback to be called.",
192 subscribedTopicsMsg.c_str()));
195 DATA_SYNCS2(rgbd2, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage);
196 DATA_SYNCS3(rgbd3, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage);
197 DATA_SYNCS4(rgbd4, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage);
198 DATA_SYNCS5(rgbd5, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage);
199 DATA_SYNCS6(rgbd6, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage);
200 DATA_SYNCS7(rgbd7, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage);
201 DATA_SYNCS8(rgbd8, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage);
206 std::vector<message_filters::Subscriber<rtabmap_msgs::RGBDImage>*>
rgbdSubs_;
211 void RGBDXSync::rgbd2Callback(
212 const rtabmap_msgs::RGBDImageConstPtr& image0,
213 const rtabmap_msgs::RGBDImageConstPtr& image1)
217 rtabmap_msgs::RGBDImages output;
218 output.header = image0->header;
219 output.rgbd_images.resize(2);
220 output.rgbd_images[0]=(*image0);
221 output.rgbd_images[1]=(*image1);
225 void RGBDXSync::rgbd3Callback(
226 const rtabmap_msgs::RGBDImageConstPtr& image0,
227 const rtabmap_msgs::RGBDImageConstPtr& image1,
228 const rtabmap_msgs::RGBDImageConstPtr& image2)
231 rtabmap_msgs::RGBDImages output;
232 output.header = image0->header;
233 output.rgbd_images.resize(3);
234 output.rgbd_images[0]=(*image0);
235 output.rgbd_images[1]=(*image1);
236 output.rgbd_images[2]=(*image2);
240 void RGBDXSync::rgbd4Callback(
241 const rtabmap_msgs::RGBDImageConstPtr& image0,
242 const rtabmap_msgs::RGBDImageConstPtr& image1,
243 const rtabmap_msgs::RGBDImageConstPtr& image2,
244 const rtabmap_msgs::RGBDImageConstPtr& image3)
247 rtabmap_msgs::RGBDImages output;
248 output.header = image0->header;
249 output.rgbd_images.resize(4);
250 output.rgbd_images[0]=(*image0);
251 output.rgbd_images[1]=(*image1);
252 output.rgbd_images[2]=(*image2);
253 output.rgbd_images[3]=(*image3);
257 void RGBDXSync::rgbd5Callback(
258 const rtabmap_msgs::RGBDImageConstPtr& image0,
259 const rtabmap_msgs::RGBDImageConstPtr& image1,
260 const rtabmap_msgs::RGBDImageConstPtr& image2,
261 const rtabmap_msgs::RGBDImageConstPtr& image3,
262 const rtabmap_msgs::RGBDImageConstPtr& image4)
265 rtabmap_msgs::RGBDImages output;
266 output.header = image0->header;
267 output.rgbd_images.resize(5);
268 output.rgbd_images[0]=(*image0);
269 output.rgbd_images[1]=(*image1);
270 output.rgbd_images[2]=(*image2);
271 output.rgbd_images[3]=(*image3);
272 output.rgbd_images[4]=(*image4);
276 void RGBDXSync::rgbd6Callback(
277 const rtabmap_msgs::RGBDImageConstPtr& image0,
278 const rtabmap_msgs::RGBDImageConstPtr& image1,
279 const rtabmap_msgs::RGBDImageConstPtr& image2,
280 const rtabmap_msgs::RGBDImageConstPtr& image3,
281 const rtabmap_msgs::RGBDImageConstPtr& image4,
282 const rtabmap_msgs::RGBDImageConstPtr& image5)
285 rtabmap_msgs::RGBDImages output;
286 output.header = image0->header;
287 output.rgbd_images.resize(6);
288 output.rgbd_images[0]=(*image0);
289 output.rgbd_images[1]=(*image1);
290 output.rgbd_images[2]=(*image2);
291 output.rgbd_images[3]=(*image3);
292 output.rgbd_images[4]=(*image4);
293 output.rgbd_images[5]=(*image5);
297 void RGBDXSync::rgbd7Callback(
298 const rtabmap_msgs::RGBDImageConstPtr& image0,
299 const rtabmap_msgs::RGBDImageConstPtr& image1,
300 const rtabmap_msgs::RGBDImageConstPtr& image2,
301 const rtabmap_msgs::RGBDImageConstPtr& image3,
302 const rtabmap_msgs::RGBDImageConstPtr& image4,
303 const rtabmap_msgs::RGBDImageConstPtr& image5,
304 const rtabmap_msgs::RGBDImageConstPtr& image6)
307 rtabmap_msgs::RGBDImages output;
308 output.header = image0->header;
309 output.rgbd_images.resize(7);
310 output.rgbd_images[0]=(*image0);
311 output.rgbd_images[1]=(*image1);
312 output.rgbd_images[2]=(*image2);
313 output.rgbd_images[3]=(*image3);
314 output.rgbd_images[4]=(*image4);
315 output.rgbd_images[5]=(*image5);
316 output.rgbd_images[6]=(*image6);
320 void RGBDXSync::rgbd8Callback(
321 const rtabmap_msgs::RGBDImageConstPtr& image0,
322 const rtabmap_msgs::RGBDImageConstPtr& image1,
323 const rtabmap_msgs::RGBDImageConstPtr& image2,
324 const rtabmap_msgs::RGBDImageConstPtr& image3,
325 const rtabmap_msgs::RGBDImageConstPtr& image4,
326 const rtabmap_msgs::RGBDImageConstPtr& image5,
327 const rtabmap_msgs::RGBDImageConstPtr& image6,
328 const rtabmap_msgs::RGBDImageConstPtr& image7)
331 rtabmap_msgs::RGBDImages output;
332 output.header = image0->header;
333 output.rgbd_images.resize(8);
334 output.rgbd_images[0]=(*image0);
335 output.rgbd_images[1]=(*image1);
336 output.rgbd_images[2]=(*image2);
337 output.rgbd_images[3]=(*image3);
338 output.rgbd_images[4]=(*image4);
339 output.rgbd_images[5]=(*image5);
340 output.rgbd_images[6]=(*image6);
341 output.rgbd_images[7]=(*image7);