00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028 #include <rtabmap_ros/CommonDataSubscriber.h>
00029 #include <rtabmap/utilite/UConversion.h>
00030 #include <rtabmap_ros/MsgConversion.h>
00031 #include <cv_bridge/cv_bridge.h>
00032
00033 namespace rtabmap_ros {
00034
00035 #define IMAGE_CONVERSION() \
00036 callbackCalled(); \
00037 std::vector<cv_bridge::CvImageConstPtr> imageMsgs(3); \
00038 std::vector<cv_bridge::CvImageConstPtr> depthMsgs(3); \
00039 rtabmap_ros::toCvShare(image1Msg, imageMsgs[0], depthMsgs[0]); \
00040 rtabmap_ros::toCvShare(image2Msg, imageMsgs[1], depthMsgs[1]); \
00041 rtabmap_ros::toCvShare(image3Msg, imageMsgs[2], depthMsgs[2]); \
00042 std::vector<sensor_msgs::CameraInfo> cameraInfoMsgs; \
00043 cameraInfoMsgs.push_back(image1Msg->rgbCameraInfo); \
00044 cameraInfoMsgs.push_back(image2Msg->rgbCameraInfo); \
00045 cameraInfoMsgs.push_back(image3Msg->rgbCameraInfo);
00046
00047
00048 void CommonDataSubscriber::rgbd3Callback(
00049 const rtabmap_ros::RGBDImageConstPtr& image1Msg,
00050 const rtabmap_ros::RGBDImageConstPtr& image2Msg,
00051 const rtabmap_ros::RGBDImageConstPtr& image3Msg)
00052 {
00053 IMAGE_CONVERSION();
00054
00055 nav_msgs::OdometryConstPtr odomMsg;
00056 rtabmap_ros::UserDataConstPtr userDataMsg;
00057 sensor_msgs::LaserScanConstPtr scanMsg;
00058 sensor_msgs::PointCloud2ConstPtr scan3dMsg;
00059 rtabmap_ros::OdomInfoConstPtr odomInfoMsg;
00060 commonDepthCallback(odomMsg, userDataMsg, imageMsgs, depthMsgs, cameraInfoMsgs, scanMsg, scan3dMsg, odomInfoMsg);
00061 }
00062 void CommonDataSubscriber::rgbd3Scan2dCallback(
00063 const rtabmap_ros::RGBDImageConstPtr& image1Msg,
00064 const rtabmap_ros::RGBDImageConstPtr& image2Msg,
00065 const rtabmap_ros::RGBDImageConstPtr& image3Msg,
00066 const sensor_msgs::LaserScanConstPtr& scanMsg)
00067 {
00068 IMAGE_CONVERSION();
00069
00070 nav_msgs::OdometryConstPtr odomMsg;
00071 rtabmap_ros::UserDataConstPtr userDataMsg;
00072 sensor_msgs::PointCloud2ConstPtr scan3dMsg;
00073 rtabmap_ros::OdomInfoConstPtr odomInfoMsg;
00074 commonDepthCallback(odomMsg, userDataMsg, imageMsgs, depthMsgs, cameraInfoMsgs, scanMsg, scan3dMsg, odomInfoMsg);
00075 }
00076 void CommonDataSubscriber::rgbd3Scan3dCallback(
00077 const rtabmap_ros::RGBDImageConstPtr& image1Msg,
00078 const rtabmap_ros::RGBDImageConstPtr& image2Msg,
00079 const rtabmap_ros::RGBDImageConstPtr& image3Msg,
00080 const sensor_msgs::PointCloud2ConstPtr& scan3dMsg)
00081 {
00082 IMAGE_CONVERSION();
00083
00084 nav_msgs::OdometryConstPtr odomMsg;
00085 rtabmap_ros::UserDataConstPtr userDataMsg;
00086 sensor_msgs::LaserScanConstPtr scanMsg;
00087 rtabmap_ros::OdomInfoConstPtr odomInfoMsg;
00088 commonDepthCallback(odomMsg, userDataMsg, imageMsgs, depthMsgs, cameraInfoMsgs, scanMsg, scan3dMsg, odomInfoMsg);
00089 }
00090 void CommonDataSubscriber::rgbd3InfoCallback(
00091 const rtabmap_ros::RGBDImageConstPtr& image1Msg,
00092 const rtabmap_ros::RGBDImageConstPtr& image2Msg,
00093 const rtabmap_ros::RGBDImageConstPtr& image3Msg,
00094 const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg)
00095 {
00096 IMAGE_CONVERSION();
00097
00098 nav_msgs::OdometryConstPtr odomMsg;
00099 rtabmap_ros::UserDataConstPtr userDataMsg;
00100 sensor_msgs::LaserScanConstPtr scanMsg;
00101 sensor_msgs::PointCloud2ConstPtr scan3dMsg;
00102 commonDepthCallback(odomMsg, userDataMsg, imageMsgs, depthMsgs, cameraInfoMsgs, scanMsg, scan3dMsg, odomInfoMsg);
00103 }
00104 void CommonDataSubscriber::rgbd3Scan2dInfoCallback(
00105 const rtabmap_ros::RGBDImageConstPtr& image1Msg,
00106 const rtabmap_ros::RGBDImageConstPtr& image2Msg,
00107 const rtabmap_ros::RGBDImageConstPtr& image3Msg,
00108 const sensor_msgs::LaserScanConstPtr& scanMsg,
00109 const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg)
00110 {
00111 IMAGE_CONVERSION();
00112
00113 nav_msgs::OdometryConstPtr odomMsg;
00114 rtabmap_ros::UserDataConstPtr userDataMsg;
00115 sensor_msgs::PointCloud2ConstPtr scan3dMsg;
00116 commonDepthCallback(odomMsg, userDataMsg, imageMsgs, depthMsgs, cameraInfoMsgs, scanMsg, scan3dMsg, odomInfoMsg);
00117 }
00118 void CommonDataSubscriber::rgbd3Scan3dInfoCallback(
00119 const rtabmap_ros::RGBDImageConstPtr& image1Msg,
00120 const rtabmap_ros::RGBDImageConstPtr& image2Msg,
00121 const rtabmap_ros::RGBDImageConstPtr& image3Msg,
00122 const sensor_msgs::PointCloud2ConstPtr& scan3dMsg,
00123 const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg)
00124 {
00125 IMAGE_CONVERSION();
00126
00127 nav_msgs::OdometryConstPtr odomMsg;
00128 rtabmap_ros::UserDataConstPtr userDataMsg;
00129 sensor_msgs::LaserScanConstPtr scanMsg;
00130 commonDepthCallback(odomMsg, userDataMsg, imageMsgs, depthMsgs, cameraInfoMsgs, scanMsg, scan3dMsg, odomInfoMsg);
00131 }
00132
00133
00134 void CommonDataSubscriber::rgbd3OdomCallback(
00135 const nav_msgs::OdometryConstPtr & odomMsg,
00136 const rtabmap_ros::RGBDImageConstPtr& image1Msg,
00137 const rtabmap_ros::RGBDImageConstPtr& image2Msg,
00138 const rtabmap_ros::RGBDImageConstPtr& image3Msg)
00139 {
00140 IMAGE_CONVERSION();
00141
00142 rtabmap_ros::UserDataConstPtr userDataMsg;
00143 sensor_msgs::LaserScanConstPtr scanMsg;
00144 sensor_msgs::PointCloud2ConstPtr scan3dMsg;
00145 rtabmap_ros::OdomInfoConstPtr odomInfoMsg;
00146 commonDepthCallback(odomMsg, userDataMsg, imageMsgs, depthMsgs, cameraInfoMsgs, scanMsg, scan3dMsg, odomInfoMsg);
00147 }
00148 void CommonDataSubscriber::rgbd3OdomScan2dCallback(
00149 const nav_msgs::OdometryConstPtr & odomMsg,
00150 const rtabmap_ros::RGBDImageConstPtr& image1Msg,
00151 const rtabmap_ros::RGBDImageConstPtr& image2Msg,
00152 const rtabmap_ros::RGBDImageConstPtr& image3Msg,
00153 const sensor_msgs::LaserScanConstPtr& scanMsg)
00154 {
00155 IMAGE_CONVERSION();
00156
00157 rtabmap_ros::UserDataConstPtr userDataMsg;
00158 sensor_msgs::PointCloud2ConstPtr scan3dMsg;
00159 rtabmap_ros::OdomInfoConstPtr odomInfoMsg;
00160 commonDepthCallback(odomMsg, userDataMsg, imageMsgs, depthMsgs, cameraInfoMsgs, scanMsg, scan3dMsg, odomInfoMsg);
00161 }
00162 void CommonDataSubscriber::rgbd3OdomScan3dCallback(
00163 const nav_msgs::OdometryConstPtr & odomMsg,
00164 const rtabmap_ros::RGBDImageConstPtr& image1Msg,
00165 const rtabmap_ros::RGBDImageConstPtr& image2Msg,
00166 const rtabmap_ros::RGBDImageConstPtr& image3Msg,
00167 const sensor_msgs::PointCloud2ConstPtr& scan3dMsg)
00168 {
00169 IMAGE_CONVERSION();
00170
00171 rtabmap_ros::UserDataConstPtr userDataMsg;
00172 sensor_msgs::LaserScanConstPtr scanMsg;
00173 rtabmap_ros::OdomInfoConstPtr odomInfoMsg;
00174 commonDepthCallback(odomMsg, userDataMsg, imageMsgs, depthMsgs, cameraInfoMsgs, scanMsg, scan3dMsg, odomInfoMsg);
00175 }
00176 void CommonDataSubscriber::rgbd3OdomInfoCallback(
00177 const nav_msgs::OdometryConstPtr & odomMsg,
00178 const rtabmap_ros::RGBDImageConstPtr& image1Msg,
00179 const rtabmap_ros::RGBDImageConstPtr& image2Msg,
00180 const rtabmap_ros::RGBDImageConstPtr& image3Msg,
00181 const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg)
00182 {
00183 IMAGE_CONVERSION();
00184
00185 rtabmap_ros::UserDataConstPtr userDataMsg;
00186 sensor_msgs::LaserScanConstPtr scanMsg;
00187 sensor_msgs::PointCloud2ConstPtr scan3dMsg;
00188 commonDepthCallback(odomMsg, userDataMsg, imageMsgs, depthMsgs, cameraInfoMsgs, scanMsg, scan3dMsg, odomInfoMsg);
00189 }
00190 void CommonDataSubscriber::rgbd3OdomScan2dInfoCallback(
00191 const nav_msgs::OdometryConstPtr & odomMsg,
00192 const rtabmap_ros::RGBDImageConstPtr& image1Msg,
00193 const rtabmap_ros::RGBDImageConstPtr& image2Msg,
00194 const rtabmap_ros::RGBDImageConstPtr& image3Msg,
00195 const sensor_msgs::LaserScanConstPtr& scanMsg,
00196 const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg)
00197 {
00198 IMAGE_CONVERSION();
00199
00200 rtabmap_ros::UserDataConstPtr userDataMsg;
00201 sensor_msgs::PointCloud2ConstPtr scan3dMsg;
00202 commonDepthCallback(odomMsg, userDataMsg, imageMsgs, depthMsgs, cameraInfoMsgs, scanMsg, scan3dMsg, odomInfoMsg);
00203 }
00204 void CommonDataSubscriber::rgbd3OdomScan3dInfoCallback(
00205 const nav_msgs::OdometryConstPtr & odomMsg,
00206 const rtabmap_ros::RGBDImageConstPtr& image1Msg,
00207 const rtabmap_ros::RGBDImageConstPtr& image2Msg,
00208 const rtabmap_ros::RGBDImageConstPtr& image3Msg,
00209 const sensor_msgs::PointCloud2ConstPtr& scan3dMsg,
00210 const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg)
00211 {
00212 IMAGE_CONVERSION();
00213
00214 rtabmap_ros::UserDataConstPtr userDataMsg;
00215 sensor_msgs::LaserScanConstPtr scanMsg;
00216 commonDepthCallback(odomMsg, userDataMsg, imageMsgs, depthMsgs, cameraInfoMsgs, scanMsg, scan3dMsg, odomInfoMsg);
00217 }
00218
00219
00220 void CommonDataSubscriber::rgbd3DataCallback(
00221 const rtabmap_ros::UserDataConstPtr& userDataMsg,
00222 const rtabmap_ros::RGBDImageConstPtr& image1Msg,
00223 const rtabmap_ros::RGBDImageConstPtr& image2Msg,
00224 const rtabmap_ros::RGBDImageConstPtr& image3Msg)
00225 {
00226 IMAGE_CONVERSION();
00227
00228 nav_msgs::OdometryConstPtr odomMsg;
00229 sensor_msgs::LaserScanConstPtr scanMsg;
00230 sensor_msgs::PointCloud2ConstPtr scan3dMsg;
00231 rtabmap_ros::OdomInfoConstPtr odomInfoMsg;
00232 commonDepthCallback(odomMsg, userDataMsg, imageMsgs, depthMsgs, cameraInfoMsgs, scanMsg, scan3dMsg, odomInfoMsg);
00233 }
00234 void CommonDataSubscriber::rgbd3DataScan2dCallback(
00235 const rtabmap_ros::UserDataConstPtr& userDataMsg,
00236 const rtabmap_ros::RGBDImageConstPtr& image1Msg,
00237 const rtabmap_ros::RGBDImageConstPtr& image2Msg,
00238 const rtabmap_ros::RGBDImageConstPtr& image3Msg,
00239 const sensor_msgs::LaserScanConstPtr& scanMsg)
00240 {
00241 IMAGE_CONVERSION();
00242
00243 nav_msgs::OdometryConstPtr odomMsg;
00244 sensor_msgs::PointCloud2ConstPtr scan3dMsg;
00245 rtabmap_ros::OdomInfoConstPtr odomInfoMsg;
00246 commonDepthCallback(odomMsg, userDataMsg, imageMsgs, depthMsgs, cameraInfoMsgs, scanMsg, scan3dMsg, odomInfoMsg);
00247 }
00248 void CommonDataSubscriber::rgbd3DataScan3dCallback(
00249 const rtabmap_ros::UserDataConstPtr& userDataMsg,
00250 const rtabmap_ros::RGBDImageConstPtr& image1Msg,
00251 const rtabmap_ros::RGBDImageConstPtr& image2Msg,
00252 const rtabmap_ros::RGBDImageConstPtr& image3Msg,
00253 const sensor_msgs::PointCloud2ConstPtr& scan3dMsg)
00254 {
00255 IMAGE_CONVERSION();
00256
00257 nav_msgs::OdometryConstPtr odomMsg;
00258 sensor_msgs::LaserScanConstPtr scanMsg;
00259 rtabmap_ros::OdomInfoConstPtr odomInfoMsg;
00260 commonDepthCallback(odomMsg, userDataMsg, imageMsgs, depthMsgs, cameraInfoMsgs, scanMsg, scan3dMsg, odomInfoMsg);
00261 }
00262 void CommonDataSubscriber::rgbd3DataInfoCallback(
00263 const rtabmap_ros::UserDataConstPtr& userDataMsg,
00264 const rtabmap_ros::RGBDImageConstPtr& image1Msg,
00265 const rtabmap_ros::RGBDImageConstPtr& image2Msg,
00266 const rtabmap_ros::RGBDImageConstPtr& image3Msg,
00267 const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg)
00268 {
00269 IMAGE_CONVERSION();
00270
00271 nav_msgs::OdometryConstPtr odomMsg;
00272 sensor_msgs::LaserScanConstPtr scanMsg;
00273 sensor_msgs::PointCloud2ConstPtr scan3dMsg;
00274 commonDepthCallback(odomMsg, userDataMsg, imageMsgs, depthMsgs, cameraInfoMsgs, scanMsg, scan3dMsg, odomInfoMsg);
00275 }
00276 void CommonDataSubscriber::rgbd3DataScan2dInfoCallback(
00277 const rtabmap_ros::UserDataConstPtr& userDataMsg,
00278 const rtabmap_ros::RGBDImageConstPtr& image1Msg,
00279 const rtabmap_ros::RGBDImageConstPtr& image2Msg,
00280 const rtabmap_ros::RGBDImageConstPtr& image3Msg,
00281 const sensor_msgs::LaserScanConstPtr& scanMsg,
00282 const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg)
00283 {
00284 IMAGE_CONVERSION();
00285
00286 nav_msgs::OdometryConstPtr odomMsg;
00287 sensor_msgs::PointCloud2ConstPtr scan3dMsg;
00288 commonDepthCallback(odomMsg, userDataMsg, imageMsgs, depthMsgs, cameraInfoMsgs, scanMsg, scan3dMsg, odomInfoMsg);
00289 }
00290 void CommonDataSubscriber::rgbd3DataScan3dInfoCallback(
00291 const rtabmap_ros::UserDataConstPtr& userDataMsg,
00292 const rtabmap_ros::RGBDImageConstPtr& image1Msg,
00293 const rtabmap_ros::RGBDImageConstPtr& image2Msg,
00294 const rtabmap_ros::RGBDImageConstPtr& image3Msg,
00295 const sensor_msgs::PointCloud2ConstPtr& scan3dMsg,
00296 const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg)
00297 {
00298 IMAGE_CONVERSION();
00299
00300 nav_msgs::OdometryConstPtr odomMsg;
00301 sensor_msgs::LaserScanConstPtr scanMsg;
00302 commonDepthCallback(odomMsg, userDataMsg, imageMsgs, depthMsgs, cameraInfoMsgs, scanMsg, scan3dMsg, odomInfoMsg);
00303 }
00304
00305
00306 void CommonDataSubscriber::rgbd3OdomDataCallback(
00307 const nav_msgs::OdometryConstPtr& odomMsg,
00308 const rtabmap_ros::UserDataConstPtr& userDataMsg,
00309 const rtabmap_ros::RGBDImageConstPtr& image1Msg,
00310 const rtabmap_ros::RGBDImageConstPtr& image2Msg,
00311 const rtabmap_ros::RGBDImageConstPtr& image3Msg)
00312 {
00313 IMAGE_CONVERSION();
00314
00315 sensor_msgs::LaserScanConstPtr scanMsg;
00316 sensor_msgs::PointCloud2ConstPtr scan3dMsg;
00317 rtabmap_ros::OdomInfoConstPtr odomInfoMsg;
00318 commonDepthCallback(odomMsg, userDataMsg, imageMsgs, depthMsgs, cameraInfoMsgs, scanMsg, scan3dMsg, odomInfoMsg);
00319 }
00320 void CommonDataSubscriber::rgbd3OdomDataScan2dCallback(
00321 const nav_msgs::OdometryConstPtr& odomMsg,
00322 const rtabmap_ros::UserDataConstPtr& userDataMsg,
00323 const rtabmap_ros::RGBDImageConstPtr& image1Msg,
00324 const rtabmap_ros::RGBDImageConstPtr& image2Msg,
00325 const rtabmap_ros::RGBDImageConstPtr& image3Msg,
00326 const sensor_msgs::LaserScanConstPtr& scanMsg)
00327 {
00328 IMAGE_CONVERSION();
00329
00330 sensor_msgs::PointCloud2ConstPtr scan3dMsg;
00331 rtabmap_ros::OdomInfoConstPtr odomInfoMsg;
00332 commonDepthCallback(odomMsg, userDataMsg, imageMsgs, depthMsgs, cameraInfoMsgs, scanMsg, scan3dMsg, odomInfoMsg);
00333 }
00334 void CommonDataSubscriber::rgbd3OdomDataScan3dCallback(
00335 const nav_msgs::OdometryConstPtr& odomMsg,
00336 const rtabmap_ros::UserDataConstPtr& userDataMsg,
00337 const rtabmap_ros::RGBDImageConstPtr& image1Msg,
00338 const rtabmap_ros::RGBDImageConstPtr& image2Msg,
00339 const rtabmap_ros::RGBDImageConstPtr& image3Msg,
00340 const sensor_msgs::PointCloud2ConstPtr& scan3dMsg)
00341 {
00342 IMAGE_CONVERSION();
00343
00344 sensor_msgs::LaserScanConstPtr scanMsg;
00345 rtabmap_ros::OdomInfoConstPtr odomInfoMsg;
00346 commonDepthCallback(odomMsg, userDataMsg, imageMsgs, depthMsgs, cameraInfoMsgs, scanMsg, scan3dMsg, odomInfoMsg);
00347 }
00348 void CommonDataSubscriber::rgbd3OdomDataInfoCallback(
00349 const nav_msgs::OdometryConstPtr& odomMsg,
00350 const rtabmap_ros::UserDataConstPtr& userDataMsg,
00351 const rtabmap_ros::RGBDImageConstPtr& image1Msg,
00352 const rtabmap_ros::RGBDImageConstPtr& image2Msg,
00353 const rtabmap_ros::RGBDImageConstPtr& image3Msg,
00354 const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg)
00355 {
00356 IMAGE_CONVERSION();
00357
00358 sensor_msgs::LaserScanConstPtr scanMsg;
00359 sensor_msgs::PointCloud2ConstPtr scan3dMsg;
00360 commonDepthCallback(odomMsg, userDataMsg, imageMsgs, depthMsgs, cameraInfoMsgs, scanMsg, scan3dMsg, odomInfoMsg);
00361 }
00362 void CommonDataSubscriber::rgbd3OdomDataScan2dInfoCallback(
00363 const nav_msgs::OdometryConstPtr& odomMsg,
00364 const rtabmap_ros::UserDataConstPtr& userDataMsg,
00365 const rtabmap_ros::RGBDImageConstPtr& image1Msg,
00366 const rtabmap_ros::RGBDImageConstPtr& image2Msg,
00367 const rtabmap_ros::RGBDImageConstPtr& image3Msg,
00368 const sensor_msgs::LaserScanConstPtr& scanMsg,
00369 const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg)
00370 {
00371 IMAGE_CONVERSION();
00372
00373 sensor_msgs::PointCloud2ConstPtr scan3dMsg;
00374 commonDepthCallback(odomMsg, userDataMsg, imageMsgs, depthMsgs, cameraInfoMsgs, scanMsg, scan3dMsg, odomInfoMsg);
00375 }
00376 void CommonDataSubscriber::rgbd3OdomDataScan3dInfoCallback(
00377 const nav_msgs::OdometryConstPtr& odomMsg,
00378 const rtabmap_ros::UserDataConstPtr& userDataMsg,
00379 const rtabmap_ros::RGBDImageConstPtr& image1Msg,
00380 const rtabmap_ros::RGBDImageConstPtr& image2Msg,
00381 const rtabmap_ros::RGBDImageConstPtr& image3Msg,
00382 const sensor_msgs::PointCloud2ConstPtr& scan3dMsg,
00383 const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg)
00384 {
00385 IMAGE_CONVERSION();
00386
00387 sensor_msgs::LaserScanConstPtr scanMsg;
00388 commonDepthCallback(odomMsg, userDataMsg, imageMsgs, depthMsgs, cameraInfoMsgs, scanMsg, scan3dMsg, odomInfoMsg);
00389 }
00390
00391 void CommonDataSubscriber::setupRGBD3Callbacks(
00392 ros::NodeHandle & nh,
00393 ros::NodeHandle & pnh,
00394 bool subscribeOdom,
00395 bool subscribeUserData,
00396 bool subscribeScan2d,
00397 bool subscribeScan3d,
00398 bool subscribeOdomInfo,
00399 int queueSize,
00400 bool approxSync)
00401 {
00402 ROS_INFO("Setup rgbd3 callback");
00403
00404 rgbdSubs_.resize(3);
00405 for(int i=0; i<3; ++i)
00406 {
00407 rgbdSubs_[i] = new message_filters::Subscriber<rtabmap_ros::RGBDImage>;
00408 rgbdSubs_[i]->subscribe(nh, uFormat("rgbd_image%d", i), 1);
00409 }
00410 if(subscribeOdom && subscribeUserData)
00411 {
00412 odomSub_.subscribe(nh, "odom", 1);
00413 userDataSub_.subscribe(nh, "user_data", 1);
00414 if(subscribeScan2d)
00415 {
00416 subscribedToScan2d_ = true;
00417 scanSub_.subscribe(nh, "scan", 1);
00418 if(subscribeOdomInfo)
00419 {
00420 subscribedToOdomInfo_ = true;
00421 odomInfoSub_.subscribe(nh, "odom_info", 1);
00422 SYNC_DECL7(rgbd3OdomDataScan2dInfo, approxSync, queueSize, odomSub_, userDataSub_, (*rgbdSubs_[0]), (*rgbdSubs_[1]), (*rgbdSubs_[2]), scanSub_, odomInfoSub_);
00423 }
00424 else
00425 {
00426 SYNC_DECL6(rgbd3OdomDataScan2d, approxSync, queueSize, odomSub_, userDataSub_, (*rgbdSubs_[0]), (*rgbdSubs_[1]), (*rgbdSubs_[2]), scanSub_);
00427 }
00428 }
00429 else if(subscribeScan3d)
00430 {
00431 subscribedToScan3d_ = true;
00432 scan3dSub_.subscribe(nh, "scan_cloud", 1);
00433 if(subscribeOdomInfo)
00434 {
00435 subscribedToOdomInfo_ = true;
00436 odomInfoSub_.subscribe(nh, "odom_info", 1);
00437 SYNC_DECL7(rgbd3OdomDataScan3dInfo, approxSync, queueSize, odomSub_, userDataSub_, (*rgbdSubs_[0]), (*rgbdSubs_[1]), (*rgbdSubs_[2]), scan3dSub_, odomInfoSub_);
00438 }
00439 else
00440 {
00441 SYNC_DECL6(rgbd3OdomDataScan3d, approxSync, queueSize, odomSub_, userDataSub_, (*rgbdSubs_[0]), (*rgbdSubs_[1]), (*rgbdSubs_[2]), scan3dSub_);
00442 }
00443 }
00444 else if(subscribeOdomInfo)
00445 {
00446 subscribedToOdomInfo_ = true;
00447 odomInfoSub_.subscribe(nh, "odom_info", 1);
00448 SYNC_DECL6(rgbd3OdomDataInfo, approxSync, queueSize, odomSub_, userDataSub_, (*rgbdSubs_[0]), (*rgbdSubs_[1]), (*rgbdSubs_[2]), odomInfoSub_);
00449 }
00450 else
00451 {
00452 SYNC_DECL5(rgbd3OdomData, approxSync, queueSize, odomSub_, userDataSub_, (*rgbdSubs_[0]), (*rgbdSubs_[1]), (*rgbdSubs_[2]));
00453 }
00454 }
00455 else if(subscribeOdom)
00456 {
00457 odomSub_.subscribe(nh, "odom", 1);
00458 if(subscribeScan2d)
00459 {
00460 subscribedToScan2d_ = true;
00461 scanSub_.subscribe(nh, "scan", 1);
00462 if(subscribeOdomInfo)
00463 {
00464 subscribedToOdomInfo_ = true;
00465 odomInfoSub_.subscribe(nh, "odom_info", 1);
00466 SYNC_DECL6(rgbd3OdomScan2dInfo, approxSync, queueSize, odomSub_, (*rgbdSubs_[0]), (*rgbdSubs_[1]), (*rgbdSubs_[2]), scanSub_, odomInfoSub_);
00467 }
00468 else
00469 {
00470 SYNC_DECL5(rgbd3OdomScan2d, approxSync, queueSize, odomSub_, (*rgbdSubs_[0]), (*rgbdSubs_[1]), (*rgbdSubs_[2]), scanSub_);
00471 }
00472 }
00473 else if(subscribeScan3d)
00474 {
00475 subscribedToScan3d_ = true;
00476 scan3dSub_.subscribe(nh, "scan_cloud", 1);
00477 if(subscribeOdomInfo)
00478 {
00479 subscribedToOdomInfo_ = true;
00480 odomInfoSub_.subscribe(nh, "odom_info", 1);
00481 SYNC_DECL6(rgbd3OdomScan3dInfo, approxSync, queueSize, odomSub_, (*rgbdSubs_[0]), (*rgbdSubs_[1]), (*rgbdSubs_[2]), scan3dSub_, odomInfoSub_);
00482 }
00483 else
00484 {
00485 SYNC_DECL5(rgbd3OdomScan3d, approxSync, queueSize, odomSub_, (*rgbdSubs_[0]), (*rgbdSubs_[1]), (*rgbdSubs_[2]), scan3dSub_);
00486 }
00487 }
00488 else if(subscribeOdomInfo)
00489 {
00490 subscribedToOdomInfo_ = true;
00491 odomInfoSub_.subscribe(nh, "odom_info", 1);
00492 SYNC_DECL5(rgbd3OdomInfo, approxSync, queueSize, odomSub_, (*rgbdSubs_[0]), (*rgbdSubs_[1]), (*rgbdSubs_[2]), odomInfoSub_);
00493 }
00494 else
00495 {
00496 SYNC_DECL4(rgbd3Odom, approxSync, queueSize, odomSub_, (*rgbdSubs_[0]), (*rgbdSubs_[1]), (*rgbdSubs_[2]));
00497 }
00498 }
00499 else if(subscribeUserData)
00500 {
00501 userDataSub_.subscribe(nh, "user_data", 1);
00502 if(subscribeScan2d)
00503 {
00504 subscribedToScan2d_ = true;
00505 scanSub_.subscribe(nh, "scan", 1);
00506 if(subscribeOdomInfo)
00507 {
00508 subscribedToOdomInfo_ = true;
00509 odomInfoSub_.subscribe(nh, "odom_info", 1);
00510 SYNC_DECL6(rgbd3DataScan2dInfo, approxSync, queueSize, userDataSub_, (*rgbdSubs_[0]), (*rgbdSubs_[1]), (*rgbdSubs_[2]), scanSub_, odomInfoSub_);
00511 }
00512 else
00513 {
00514 SYNC_DECL5(rgbd3DataScan2d, approxSync, queueSize, userDataSub_, (*rgbdSubs_[0]), (*rgbdSubs_[1]), (*rgbdSubs_[2]), scanSub_);
00515 }
00516 }
00517 else if(subscribeScan3d)
00518 {
00519 subscribedToScan3d_ = true;
00520 scan3dSub_.subscribe(nh, "scan_cloud", 1);
00521 if(subscribeOdomInfo)
00522 {
00523 subscribedToOdomInfo_ = true;
00524 odomInfoSub_.subscribe(nh, "odom_info", 1);
00525 SYNC_DECL6(rgbd3DataScan3dInfo, approxSync, queueSize, userDataSub_, (*rgbdSubs_[0]), (*rgbdSubs_[1]), (*rgbdSubs_[2]), scan3dSub_, odomInfoSub_);
00526 }
00527 else
00528 {
00529 SYNC_DECL5(rgbd3DataScan3d, approxSync, queueSize, userDataSub_, (*rgbdSubs_[0]), (*rgbdSubs_[1]), (*rgbdSubs_[2]), scan3dSub_);
00530 }
00531 }
00532 else if(subscribeOdomInfo)
00533 {
00534 subscribedToOdomInfo_ = true;
00535 odomInfoSub_.subscribe(nh, "odom_info", 1);
00536 SYNC_DECL5(rgbd3DataInfo, approxSync, queueSize, userDataSub_, (*rgbdSubs_[0]), (*rgbdSubs_[1]), (*rgbdSubs_[2]), odomInfoSub_);
00537 }
00538 else
00539 {
00540 SYNC_DECL4(rgbd3Data, approxSync, queueSize, userDataSub_, (*rgbdSubs_[0]), (*rgbdSubs_[1]), (*rgbdSubs_[2]));
00541 }
00542 }
00543 else
00544 {
00545 if(subscribeScan2d)
00546 {
00547 subscribedToScan2d_ = true;
00548 scanSub_.subscribe(nh, "scan", 1);
00549 if(subscribeOdomInfo)
00550 {
00551 subscribedToOdomInfo_ = true;
00552 odomInfoSub_.subscribe(nh, "odom_info", 1);
00553 SYNC_DECL5(rgbd3Scan2dInfo, approxSync, queueSize, (*rgbdSubs_[0]), (*rgbdSubs_[1]), (*rgbdSubs_[2]), scanSub_, odomInfoSub_);
00554 }
00555 else
00556 {
00557 SYNC_DECL4(rgbd3Scan2d, approxSync, queueSize, (*rgbdSubs_[0]), (*rgbdSubs_[1]), (*rgbdSubs_[2]), scanSub_);
00558 }
00559 }
00560 else if(subscribeScan3d)
00561 {
00562 subscribedToScan3d_ = true;
00563 scan3dSub_.subscribe(nh, "scan_cloud", 1);
00564 if(subscribeOdomInfo)
00565 {
00566 subscribedToOdomInfo_ = true;
00567 odomInfoSub_.subscribe(nh, "odom_info", 1);
00568 SYNC_DECL5(rgbd3Scan3dInfo, approxSync, queueSize, (*rgbdSubs_[0]), (*rgbdSubs_[1]), (*rgbdSubs_[2]), scan3dSub_, odomInfoSub_);
00569 }
00570 else
00571 {
00572 SYNC_DECL4(rgbd3Scan3d, approxSync, queueSize, (*rgbdSubs_[0]), (*rgbdSubs_[1]), (*rgbdSubs_[2]), scan3dSub_);
00573 }
00574 }
00575 else if(subscribeOdomInfo)
00576 {
00577 subscribedToOdomInfo_ = true;
00578 odomInfoSub_.subscribe(nh, "odom_info", 1);
00579 SYNC_DECL4(rgbd3Info, approxSync, queueSize, (*rgbdSubs_[0]), (*rgbdSubs_[1]), (*rgbdSubs_[2]), odomInfoSub_);
00580 }
00581 else
00582 {
00583 SYNC_DECL3(rgbd3, approxSync, queueSize, (*rgbdSubs_[0]), (*rgbdSubs_[1]), (*rgbdSubs_[2]));
00584 }
00585 }
00586 }
00587
00588 }