CommonDataSubscriberRGBD2.cpp
Go to the documentation of this file.
00001 /*
00002 Copyright (c) 2010-2016, Mathieu Labbe - IntRoLab - Universite de Sherbrooke
00003 All rights reserved.
00004 
00005 Redistribution and use in source and binary forms, with or without
00006 modification, are permitted provided that the following conditions are met:
00007     * Redistributions of source code must retain the above copyright
00008       notice, this list of conditions and the following disclaimer.
00009     * Redistributions in binary form must reproduce the above copyright
00010       notice, this list of conditions and the following disclaimer in the
00011       documentation and/or other materials provided with the distribution.
00012     * Neither the name of the Universite de Sherbrooke nor the
00013       names of its contributors may be used to endorse or promote products
00014       derived from this software without specific prior written permission.
00015 
00016 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
00017 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
00018 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
00019 DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY
00020 DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
00021 (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00022 LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
00023 ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
00024 (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
00025 SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
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(2); \
00038                 std::vector<cv_bridge::CvImageConstPtr> depthMsgs(2); \
00039                 rtabmap_ros::toCvShare(image1Msg, imageMsgs[0], depthMsgs[0]); \
00040                 rtabmap_ros::toCvShare(image2Msg, imageMsgs[1], depthMsgs[1]); \
00041                 std::vector<sensor_msgs::CameraInfo> cameraInfoMsgs; \
00042                 cameraInfoMsgs.push_back(image1Msg->rgbCameraInfo); \
00043                 cameraInfoMsgs.push_back(image2Msg->rgbCameraInfo);
00044 
00045 // 2 RGBD
00046 void CommonDataSubscriber::rgbd2Callback(
00047                 const rtabmap_ros::RGBDImageConstPtr& image1Msg,
00048                 const rtabmap_ros::RGBDImageConstPtr& image2Msg)
00049 {
00050         IMAGE_CONVERSION();
00051 
00052         nav_msgs::OdometryConstPtr odomMsg; // Null
00053         rtabmap_ros::UserDataConstPtr userDataMsg; // Null
00054         sensor_msgs::LaserScanConstPtr scanMsg; // Null
00055         sensor_msgs::PointCloud2ConstPtr scan3dMsg; // Null
00056         rtabmap_ros::OdomInfoConstPtr odomInfoMsg; // null
00057         commonDepthCallback(odomMsg, userDataMsg, imageMsgs, depthMsgs, cameraInfoMsgs, scanMsg, scan3dMsg, odomInfoMsg);
00058 }
00059 void CommonDataSubscriber::rgbd2Scan2dCallback(
00060                 const rtabmap_ros::RGBDImageConstPtr& image1Msg,
00061                 const rtabmap_ros::RGBDImageConstPtr& image2Msg,
00062                 const sensor_msgs::LaserScanConstPtr& scanMsg)
00063 {
00064         IMAGE_CONVERSION();
00065 
00066         nav_msgs::OdometryConstPtr odomMsg; // Null
00067         rtabmap_ros::UserDataConstPtr userDataMsg; // Null
00068         sensor_msgs::PointCloud2ConstPtr scan3dMsg; // Null
00069         rtabmap_ros::OdomInfoConstPtr odomInfoMsg; // null
00070         commonDepthCallback(odomMsg, userDataMsg, imageMsgs, depthMsgs, cameraInfoMsgs, scanMsg, scan3dMsg, odomInfoMsg);
00071 }
00072 void CommonDataSubscriber::rgbd2Scan3dCallback(
00073                 const rtabmap_ros::RGBDImageConstPtr& image1Msg,
00074                 const rtabmap_ros::RGBDImageConstPtr& image2Msg,
00075                 const sensor_msgs::PointCloud2ConstPtr& scan3dMsg)
00076 {
00077         IMAGE_CONVERSION();
00078 
00079         nav_msgs::OdometryConstPtr odomMsg; // Null
00080         rtabmap_ros::UserDataConstPtr userDataMsg; // Null
00081         sensor_msgs::LaserScanConstPtr scanMsg; // Null
00082         rtabmap_ros::OdomInfoConstPtr odomInfoMsg; // null
00083         commonDepthCallback(odomMsg, userDataMsg, imageMsgs, depthMsgs, cameraInfoMsgs, scanMsg, scan3dMsg, odomInfoMsg);
00084 }
00085 void CommonDataSubscriber::rgbd2InfoCallback(
00086                 const rtabmap_ros::RGBDImageConstPtr& image1Msg,
00087                 const rtabmap_ros::RGBDImageConstPtr& image2Msg,
00088                 const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg)
00089 {
00090         IMAGE_CONVERSION();
00091 
00092         nav_msgs::OdometryConstPtr odomMsg; // Null
00093         rtabmap_ros::UserDataConstPtr userDataMsg; // Null
00094         sensor_msgs::LaserScanConstPtr scanMsg; // Null
00095         sensor_msgs::PointCloud2ConstPtr scan3dMsg; // Null
00096         commonDepthCallback(odomMsg, userDataMsg, imageMsgs, depthMsgs, cameraInfoMsgs, scanMsg, scan3dMsg, odomInfoMsg);
00097 }
00098 void CommonDataSubscriber::rgbd2Scan2dInfoCallback(
00099                 const rtabmap_ros::RGBDImageConstPtr& image1Msg,
00100                 const rtabmap_ros::RGBDImageConstPtr& image2Msg,
00101                 const sensor_msgs::LaserScanConstPtr& scanMsg,
00102                 const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg)
00103 {
00104         IMAGE_CONVERSION();
00105 
00106         nav_msgs::OdometryConstPtr odomMsg; // Null
00107         rtabmap_ros::UserDataConstPtr userDataMsg; // Null
00108         sensor_msgs::PointCloud2ConstPtr scan3dMsg; // Null
00109         commonDepthCallback(odomMsg, userDataMsg, imageMsgs, depthMsgs, cameraInfoMsgs, scanMsg, scan3dMsg, odomInfoMsg);
00110 }
00111 void CommonDataSubscriber::rgbd2Scan3dInfoCallback(
00112                 const rtabmap_ros::RGBDImageConstPtr& image1Msg,
00113                 const rtabmap_ros::RGBDImageConstPtr& image2Msg,
00114                 const sensor_msgs::PointCloud2ConstPtr& scan3dMsg,
00115                 const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg)
00116 {
00117         IMAGE_CONVERSION();
00118 
00119         nav_msgs::OdometryConstPtr odomMsg; // Null
00120         rtabmap_ros::UserDataConstPtr userDataMsg; // Null
00121         sensor_msgs::LaserScanConstPtr scanMsg; // Null
00122         commonDepthCallback(odomMsg, userDataMsg, imageMsgs, depthMsgs, cameraInfoMsgs, scanMsg, scan3dMsg, odomInfoMsg);
00123 }
00124 
00125 // 2 RGBD + Odom
00126 void CommonDataSubscriber::rgbd2OdomCallback(
00127                 const nav_msgs::OdometryConstPtr & odomMsg,
00128                 const rtabmap_ros::RGBDImageConstPtr& image1Msg,
00129                 const rtabmap_ros::RGBDImageConstPtr& image2Msg)
00130 {
00131         IMAGE_CONVERSION();
00132 
00133         rtabmap_ros::UserDataConstPtr userDataMsg; // Null
00134         sensor_msgs::LaserScanConstPtr scanMsg; // Null
00135         sensor_msgs::PointCloud2ConstPtr scan3dMsg; // Null
00136         rtabmap_ros::OdomInfoConstPtr odomInfoMsg; // null
00137         commonDepthCallback(odomMsg, userDataMsg, imageMsgs, depthMsgs, cameraInfoMsgs, scanMsg, scan3dMsg, odomInfoMsg);
00138 }
00139 void CommonDataSubscriber::rgbd2OdomScan2dCallback(
00140                 const nav_msgs::OdometryConstPtr & odomMsg,
00141                 const rtabmap_ros::RGBDImageConstPtr& image1Msg,
00142                 const rtabmap_ros::RGBDImageConstPtr& image2Msg,
00143                 const sensor_msgs::LaserScanConstPtr& scanMsg)
00144 {
00145         IMAGE_CONVERSION();
00146 
00147         rtabmap_ros::UserDataConstPtr userDataMsg; // Null
00148         sensor_msgs::PointCloud2ConstPtr scan3dMsg; // Null
00149         rtabmap_ros::OdomInfoConstPtr odomInfoMsg; // null
00150         commonDepthCallback(odomMsg, userDataMsg, imageMsgs, depthMsgs, cameraInfoMsgs, scanMsg, scan3dMsg, odomInfoMsg);
00151 }
00152 void CommonDataSubscriber::rgbd2OdomScan3dCallback(
00153                 const nav_msgs::OdometryConstPtr & odomMsg,
00154                 const rtabmap_ros::RGBDImageConstPtr& image1Msg,
00155                 const rtabmap_ros::RGBDImageConstPtr& image2Msg,
00156                 const sensor_msgs::PointCloud2ConstPtr& scan3dMsg)
00157 {
00158         IMAGE_CONVERSION();
00159 
00160         rtabmap_ros::UserDataConstPtr userDataMsg; // Null
00161         sensor_msgs::LaserScanConstPtr scanMsg; // Null
00162         rtabmap_ros::OdomInfoConstPtr odomInfoMsg; // null
00163         commonDepthCallback(odomMsg, userDataMsg, imageMsgs, depthMsgs, cameraInfoMsgs, scanMsg, scan3dMsg, odomInfoMsg);
00164 }
00165 void CommonDataSubscriber::rgbd2OdomInfoCallback(
00166                 const nav_msgs::OdometryConstPtr & odomMsg,
00167                 const rtabmap_ros::RGBDImageConstPtr& image1Msg,
00168                 const rtabmap_ros::RGBDImageConstPtr& image2Msg,
00169                 const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg)
00170 {
00171         IMAGE_CONVERSION();
00172 
00173         rtabmap_ros::UserDataConstPtr userDataMsg; // Null
00174         sensor_msgs::LaserScanConstPtr scanMsg; // Null
00175         sensor_msgs::PointCloud2ConstPtr scan3dMsg; // Null
00176         commonDepthCallback(odomMsg, userDataMsg, imageMsgs, depthMsgs, cameraInfoMsgs, scanMsg, scan3dMsg, odomInfoMsg);
00177 }
00178 void CommonDataSubscriber::rgbd2OdomScan2dInfoCallback(
00179                 const nav_msgs::OdometryConstPtr & odomMsg,
00180                 const rtabmap_ros::RGBDImageConstPtr& image1Msg,
00181                 const rtabmap_ros::RGBDImageConstPtr& image2Msg,
00182                 const sensor_msgs::LaserScanConstPtr& scanMsg,
00183                 const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg)
00184 {
00185         IMAGE_CONVERSION();
00186 
00187         rtabmap_ros::UserDataConstPtr userDataMsg; // Null
00188         sensor_msgs::PointCloud2ConstPtr scan3dMsg; // Null
00189         commonDepthCallback(odomMsg, userDataMsg, imageMsgs, depthMsgs, cameraInfoMsgs, scanMsg, scan3dMsg, odomInfoMsg);
00190 }
00191 void CommonDataSubscriber::rgbd2OdomScan3dInfoCallback(
00192                 const nav_msgs::OdometryConstPtr & odomMsg,
00193                 const rtabmap_ros::RGBDImageConstPtr& image1Msg,
00194                 const rtabmap_ros::RGBDImageConstPtr& image2Msg,
00195                 const sensor_msgs::PointCloud2ConstPtr& scan3dMsg,
00196                 const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg)
00197 {
00198         IMAGE_CONVERSION();
00199 
00200         rtabmap_ros::UserDataConstPtr userDataMsg; // Null
00201         sensor_msgs::LaserScanConstPtr scanMsg; // Null
00202         commonDepthCallback(odomMsg, userDataMsg, imageMsgs, depthMsgs, cameraInfoMsgs, scanMsg, scan3dMsg, odomInfoMsg);
00203 }
00204 
00205 // 2 RGBD + User Data
00206 void CommonDataSubscriber::rgbd2DataCallback(
00207                 const rtabmap_ros::UserDataConstPtr& userDataMsg,
00208                 const rtabmap_ros::RGBDImageConstPtr& image1Msg,
00209                 const rtabmap_ros::RGBDImageConstPtr& image2Msg)
00210 {
00211         IMAGE_CONVERSION();
00212 
00213         nav_msgs::OdometryConstPtr odomMsg; // Null
00214         sensor_msgs::LaserScanConstPtr scanMsg; // Null
00215         sensor_msgs::PointCloud2ConstPtr scan3dMsg; // Null
00216         rtabmap_ros::OdomInfoConstPtr odomInfoMsg; // null
00217         commonDepthCallback(odomMsg, userDataMsg, imageMsgs, depthMsgs, cameraInfoMsgs, scanMsg, scan3dMsg, odomInfoMsg);
00218 }
00219 void CommonDataSubscriber::rgbd2DataScan2dCallback(
00220                 const rtabmap_ros::UserDataConstPtr& userDataMsg,
00221                 const rtabmap_ros::RGBDImageConstPtr& image1Msg,
00222                 const rtabmap_ros::RGBDImageConstPtr& image2Msg,
00223                 const sensor_msgs::LaserScanConstPtr& scanMsg)
00224 {
00225         IMAGE_CONVERSION();
00226 
00227         nav_msgs::OdometryConstPtr odomMsg; // Null
00228         sensor_msgs::PointCloud2ConstPtr scan3dMsg; // Null
00229         rtabmap_ros::OdomInfoConstPtr odomInfoMsg; // null
00230         commonDepthCallback(odomMsg, userDataMsg, imageMsgs, depthMsgs, cameraInfoMsgs, scanMsg, scan3dMsg, odomInfoMsg);
00231 }
00232 void CommonDataSubscriber::rgbd2DataScan3dCallback(
00233                 const rtabmap_ros::UserDataConstPtr& userDataMsg,
00234                 const rtabmap_ros::RGBDImageConstPtr& image1Msg,
00235                 const rtabmap_ros::RGBDImageConstPtr& image2Msg,
00236                 const sensor_msgs::PointCloud2ConstPtr& scan3dMsg)
00237 {
00238         IMAGE_CONVERSION();
00239 
00240         nav_msgs::OdometryConstPtr odomMsg; // Null
00241         sensor_msgs::LaserScanConstPtr scanMsg; // Null
00242         rtabmap_ros::OdomInfoConstPtr odomInfoMsg; // null
00243         commonDepthCallback(odomMsg, userDataMsg, imageMsgs, depthMsgs, cameraInfoMsgs, scanMsg, scan3dMsg, odomInfoMsg);
00244 }
00245 void CommonDataSubscriber::rgbd2DataInfoCallback(
00246                 const rtabmap_ros::UserDataConstPtr& userDataMsg,
00247                 const rtabmap_ros::RGBDImageConstPtr& image1Msg,
00248                 const rtabmap_ros::RGBDImageConstPtr& image2Msg,
00249                 const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg)
00250 {
00251         IMAGE_CONVERSION();
00252 
00253         nav_msgs::OdometryConstPtr odomMsg; // Null
00254         sensor_msgs::LaserScanConstPtr scanMsg; // Null
00255         sensor_msgs::PointCloud2ConstPtr scan3dMsg; // Null
00256         commonDepthCallback(odomMsg, userDataMsg, imageMsgs, depthMsgs, cameraInfoMsgs, scanMsg, scan3dMsg, odomInfoMsg);
00257 }
00258 void CommonDataSubscriber::rgbd2DataScan2dInfoCallback(
00259                 const rtabmap_ros::UserDataConstPtr& userDataMsg,
00260                 const rtabmap_ros::RGBDImageConstPtr& image1Msg,
00261                 const rtabmap_ros::RGBDImageConstPtr& image2Msg,
00262                 const sensor_msgs::LaserScanConstPtr& scanMsg,
00263                 const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg)
00264 {
00265         IMAGE_CONVERSION();
00266 
00267         nav_msgs::OdometryConstPtr odomMsg; // Null
00268         sensor_msgs::PointCloud2ConstPtr scan3dMsg; // Null
00269         commonDepthCallback(odomMsg, userDataMsg, imageMsgs, depthMsgs, cameraInfoMsgs, scanMsg, scan3dMsg, odomInfoMsg);
00270 }
00271 void CommonDataSubscriber::rgbd2DataScan3dInfoCallback(
00272                 const rtabmap_ros::UserDataConstPtr& userDataMsg,
00273                 const rtabmap_ros::RGBDImageConstPtr& image1Msg,
00274                 const rtabmap_ros::RGBDImageConstPtr& image2Msg,
00275                 const sensor_msgs::PointCloud2ConstPtr& scan3dMsg,
00276                 const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg)
00277 {
00278         IMAGE_CONVERSION();
00279 
00280         nav_msgs::OdometryConstPtr odomMsg; // Null
00281         sensor_msgs::LaserScanConstPtr scanMsg; // Null
00282         commonDepthCallback(odomMsg, userDataMsg, imageMsgs, depthMsgs, cameraInfoMsgs, scanMsg, scan3dMsg, odomInfoMsg);
00283 }
00284 
00285 // 2 RGBD + Odom + User Data
00286 void CommonDataSubscriber::rgbd2OdomDataCallback(
00287                 const nav_msgs::OdometryConstPtr& odomMsg,
00288                 const rtabmap_ros::UserDataConstPtr& userDataMsg,
00289                 const rtabmap_ros::RGBDImageConstPtr& image1Msg,
00290                 const rtabmap_ros::RGBDImageConstPtr& image2Msg)
00291 {
00292         IMAGE_CONVERSION();
00293 
00294         sensor_msgs::LaserScanConstPtr scanMsg; // Null
00295         sensor_msgs::PointCloud2ConstPtr scan3dMsg; // Null
00296         rtabmap_ros::OdomInfoConstPtr odomInfoMsg; // null
00297         commonDepthCallback(odomMsg, userDataMsg, imageMsgs, depthMsgs, cameraInfoMsgs, scanMsg, scan3dMsg, odomInfoMsg);
00298 }
00299 void CommonDataSubscriber::rgbd2OdomDataScan2dCallback(
00300                 const nav_msgs::OdometryConstPtr& odomMsg,
00301                 const rtabmap_ros::UserDataConstPtr& userDataMsg,
00302                 const rtabmap_ros::RGBDImageConstPtr& image1Msg,
00303                 const rtabmap_ros::RGBDImageConstPtr& image2Msg,
00304                 const sensor_msgs::LaserScanConstPtr& scanMsg)
00305 {
00306         IMAGE_CONVERSION();
00307 
00308         sensor_msgs::PointCloud2ConstPtr scan3dMsg; // Null
00309         rtabmap_ros::OdomInfoConstPtr odomInfoMsg; // null
00310         commonDepthCallback(odomMsg, userDataMsg, imageMsgs, depthMsgs, cameraInfoMsgs, scanMsg, scan3dMsg, odomInfoMsg);
00311 }
00312 void CommonDataSubscriber::rgbd2OdomDataScan3dCallback(
00313                 const nav_msgs::OdometryConstPtr& odomMsg,
00314                 const rtabmap_ros::UserDataConstPtr& userDataMsg,
00315                 const rtabmap_ros::RGBDImageConstPtr& image1Msg,
00316                 const rtabmap_ros::RGBDImageConstPtr& image2Msg,
00317                 const sensor_msgs::PointCloud2ConstPtr& scan3dMsg)
00318 {
00319         IMAGE_CONVERSION();
00320 
00321         sensor_msgs::LaserScanConstPtr scanMsg; // Null
00322         rtabmap_ros::OdomInfoConstPtr odomInfoMsg; // null
00323         commonDepthCallback(odomMsg, userDataMsg, imageMsgs, depthMsgs, cameraInfoMsgs, scanMsg, scan3dMsg, odomInfoMsg);
00324 }
00325 void CommonDataSubscriber::rgbd2OdomDataInfoCallback(
00326                 const nav_msgs::OdometryConstPtr& odomMsg,
00327                 const rtabmap_ros::UserDataConstPtr& userDataMsg,
00328                 const rtabmap_ros::RGBDImageConstPtr& image1Msg,
00329                 const rtabmap_ros::RGBDImageConstPtr& image2Msg,
00330                 const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg)
00331 {
00332         IMAGE_CONVERSION();
00333 
00334         sensor_msgs::LaserScanConstPtr scanMsg; // Null
00335         sensor_msgs::PointCloud2ConstPtr scan3dMsg; // Null
00336         commonDepthCallback(odomMsg, userDataMsg, imageMsgs, depthMsgs, cameraInfoMsgs, scanMsg, scan3dMsg, odomInfoMsg);
00337 }
00338 void CommonDataSubscriber::rgbd2OdomDataScan2dInfoCallback(
00339                 const nav_msgs::OdometryConstPtr& odomMsg,
00340                 const rtabmap_ros::UserDataConstPtr& userDataMsg,
00341                 const rtabmap_ros::RGBDImageConstPtr& image1Msg,
00342                 const rtabmap_ros::RGBDImageConstPtr& image2Msg,
00343                 const sensor_msgs::LaserScanConstPtr& scanMsg,
00344                 const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg)
00345 {
00346         IMAGE_CONVERSION();
00347 
00348         sensor_msgs::PointCloud2ConstPtr scan3dMsg; // Null
00349         commonDepthCallback(odomMsg, userDataMsg, imageMsgs, depthMsgs, cameraInfoMsgs, scanMsg, scan3dMsg, odomInfoMsg);
00350 }
00351 void CommonDataSubscriber::rgbd2OdomDataScan3dInfoCallback(
00352                 const nav_msgs::OdometryConstPtr& odomMsg,
00353                 const rtabmap_ros::UserDataConstPtr& userDataMsg,
00354                 const rtabmap_ros::RGBDImageConstPtr& image1Msg,
00355                 const rtabmap_ros::RGBDImageConstPtr& image2Msg,
00356                 const sensor_msgs::PointCloud2ConstPtr& scan3dMsg,
00357                 const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg)
00358 {
00359         IMAGE_CONVERSION();
00360 
00361         sensor_msgs::LaserScanConstPtr scanMsg; // Null
00362         commonDepthCallback(odomMsg, userDataMsg, imageMsgs, depthMsgs, cameraInfoMsgs, scanMsg, scan3dMsg, odomInfoMsg);
00363 }
00364 
00365 void CommonDataSubscriber::setupRGBD2Callbacks(
00366                 ros::NodeHandle & nh,
00367                 ros::NodeHandle & pnh,
00368                 bool subscribeOdom,
00369                 bool subscribeUserData,
00370                 bool subscribeScan2d,
00371                 bool subscribeScan3d,
00372                 bool subscribeOdomInfo,
00373                 int queueSize,
00374                 bool approxSync)
00375 {
00376         ROS_INFO("Setup rgbd2 callback");
00377 
00378         rgbdSubs_.resize(2);
00379         for(int i=0; i<2; ++i)
00380         {
00381                 rgbdSubs_[i] = new message_filters::Subscriber<rtabmap_ros::RGBDImage>;
00382                 rgbdSubs_[i]->subscribe(nh, uFormat("rgbd_image%d", i), 1);
00383         }
00384         if(subscribeOdom && subscribeUserData)
00385         {
00386                 odomSub_.subscribe(nh, "odom", 1);
00387                 userDataSub_.subscribe(nh, "user_data", 1);
00388                 if(subscribeScan2d)
00389                 {
00390                         subscribedToScan2d_ = true;
00391                         scanSub_.subscribe(nh, "scan", 1);
00392                         if(subscribeOdomInfo)
00393                         {
00394                                 subscribedToOdomInfo_ = true;
00395                                 odomInfoSub_.subscribe(nh, "odom_info", 1);
00396                                 SYNC_DECL6(rgbd2OdomDataScan2dInfo, approxSync, queueSize, odomSub_, userDataSub_, (*rgbdSubs_[0]), (*rgbdSubs_[1]), scanSub_, odomInfoSub_);
00397                         }
00398                         else
00399                         {
00400                                 SYNC_DECL5(rgbd2OdomDataScan2d, approxSync, queueSize, odomSub_, userDataSub_, (*rgbdSubs_[0]), (*rgbdSubs_[1]), scanSub_);
00401                         }
00402                 }
00403                 else if(subscribeScan3d)
00404                 {
00405                         subscribedToScan3d_ = true;
00406                         scan3dSub_.subscribe(nh, "scan_cloud", 1);
00407                         if(subscribeOdomInfo)
00408                         {
00409                                 subscribedToOdomInfo_ = true;
00410                                 odomInfoSub_.subscribe(nh, "odom_info", 1);
00411                                 SYNC_DECL6(rgbd2OdomDataScan3dInfo, approxSync, queueSize, odomSub_, userDataSub_, (*rgbdSubs_[0]), (*rgbdSubs_[1]), scan3dSub_, odomInfoSub_);
00412                         }
00413                         else
00414                         {
00415                                 SYNC_DECL5(rgbd2OdomDataScan3d, approxSync, queueSize, odomSub_, userDataSub_, (*rgbdSubs_[0]), (*rgbdSubs_[1]), scan3dSub_);
00416                         }
00417                 }
00418                 else if(subscribeOdomInfo)
00419                 {
00420                         subscribedToOdomInfo_ = true;
00421                         odomInfoSub_.subscribe(nh, "odom_info", 1);
00422                         SYNC_DECL5(rgbd2OdomDataInfo, approxSync, queueSize, odomSub_, userDataSub_, (*rgbdSubs_[0]), (*rgbdSubs_[1]), odomInfoSub_);
00423                 }
00424                 else
00425                 {
00426                         SYNC_DECL4(rgbd2OdomData, approxSync, queueSize, odomSub_, userDataSub_, (*rgbdSubs_[0]), (*rgbdSubs_[1]));
00427                 }
00428         }
00429         else if(subscribeOdom)
00430         {
00431                 odomSub_.subscribe(nh, "odom", 1);
00432                 if(subscribeScan2d)
00433                 {
00434                         subscribedToScan2d_ = true;
00435                         scanSub_.subscribe(nh, "scan", 1);
00436                         if(subscribeOdomInfo)
00437                         {
00438                                 subscribedToOdomInfo_ = true;
00439                                 odomInfoSub_.subscribe(nh, "odom_info", 1);
00440                                 SYNC_DECL5(rgbd2OdomScan2dInfo, approxSync, queueSize, odomSub_, (*rgbdSubs_[0]), (*rgbdSubs_[1]), scanSub_, odomInfoSub_);
00441                         }
00442                         else
00443                         {
00444                                 SYNC_DECL4(rgbd2OdomScan2d, approxSync, queueSize, odomSub_, (*rgbdSubs_[0]), (*rgbdSubs_[1]), scanSub_);
00445                         }
00446                 }
00447                 else if(subscribeScan3d)
00448                 {
00449                         subscribedToScan3d_ = true;
00450                         scan3dSub_.subscribe(nh, "scan_cloud", 1);
00451                         if(subscribeOdomInfo)
00452                         {
00453                                 subscribedToOdomInfo_ = true;
00454                                 odomInfoSub_.subscribe(nh, "odom_info", 1);
00455                                 SYNC_DECL5(rgbd2OdomScan3dInfo, approxSync, queueSize, odomSub_, (*rgbdSubs_[0]), (*rgbdSubs_[1]), scan3dSub_, odomInfoSub_);
00456                         }
00457                         else
00458                         {
00459                                 SYNC_DECL4(rgbd2OdomScan3d, approxSync, queueSize, odomSub_, (*rgbdSubs_[0]), (*rgbdSubs_[1]), scan3dSub_);
00460                         }
00461                 }
00462                 else if(subscribeOdomInfo)
00463                 {
00464                         subscribedToOdomInfo_ = true;
00465                         odomInfoSub_.subscribe(nh, "odom_info", 1);
00466                         SYNC_DECL4(rgbd2OdomInfo, approxSync, queueSize, odomSub_, (*rgbdSubs_[0]), (*rgbdSubs_[1]), odomInfoSub_);
00467                 }
00468                 else
00469                 {
00470                         SYNC_DECL3(rgbd2Odom, approxSync, queueSize, odomSub_, (*rgbdSubs_[0]), (*rgbdSubs_[1]));
00471                 }
00472         }
00473         else if(subscribeUserData)
00474         {
00475                 userDataSub_.subscribe(nh, "user_data", 1);
00476                 if(subscribeScan2d)
00477                 {
00478                         subscribedToScan2d_ = true;
00479                         scanSub_.subscribe(nh, "scan", 1);
00480                         if(subscribeOdomInfo)
00481                         {
00482                                 subscribedToOdomInfo_ = true;
00483                                 odomInfoSub_.subscribe(nh, "odom_info", 1);
00484                                 SYNC_DECL5(rgbd2DataScan2dInfo, approxSync, queueSize, userDataSub_, (*rgbdSubs_[0]), (*rgbdSubs_[1]), scanSub_, odomInfoSub_);
00485                         }
00486                         else
00487                         {
00488                                 SYNC_DECL4(rgbd2DataScan2d, approxSync, queueSize, userDataSub_, (*rgbdSubs_[0]), (*rgbdSubs_[1]), scanSub_);
00489                         }
00490                 }
00491                 else if(subscribeScan3d)
00492                 {
00493                         subscribedToScan3d_ = true;
00494                         scan3dSub_.subscribe(nh, "scan_cloud", 1);
00495                         if(subscribeOdomInfo)
00496                         {
00497                                 subscribedToOdomInfo_ = true;
00498                                 odomInfoSub_.subscribe(nh, "odom_info", 1);
00499                                 SYNC_DECL5(rgbd2DataScan3dInfo, approxSync, queueSize, userDataSub_, (*rgbdSubs_[0]), (*rgbdSubs_[1]), scan3dSub_, odomInfoSub_);
00500                         }
00501                         else
00502                         {
00503                                 SYNC_DECL4(rgbd2DataScan3d, approxSync, queueSize, userDataSub_, (*rgbdSubs_[0]), (*rgbdSubs_[1]), scan3dSub_);
00504                         }
00505                 }
00506                 else if(subscribeOdomInfo)
00507                 {
00508                         subscribedToOdomInfo_ = true;
00509                         odomInfoSub_.subscribe(nh, "odom_info", 1);
00510                         SYNC_DECL4(rgbd2DataInfo, approxSync, queueSize, userDataSub_, (*rgbdSubs_[0]), (*rgbdSubs_[1]), odomInfoSub_);
00511                 }
00512                 else
00513                 {
00514                         SYNC_DECL3(rgbd2Data, approxSync, queueSize, userDataSub_, (*rgbdSubs_[0]), (*rgbdSubs_[1]));
00515                 }
00516         }
00517         else
00518         {
00519                 if(subscribeScan2d)
00520                 {
00521                         subscribedToScan2d_ = true;
00522                         scanSub_.subscribe(nh, "scan", 1);
00523                         if(subscribeOdomInfo)
00524                         {
00525                                 subscribedToOdomInfo_ = true;
00526                                 odomInfoSub_.subscribe(nh, "odom_info", 1);
00527                                 SYNC_DECL4(rgbd2Scan2dInfo, approxSync, queueSize, (*rgbdSubs_[0]), (*rgbdSubs_[1]), scanSub_, odomInfoSub_);
00528                         }
00529                         else
00530                         {
00531                                 SYNC_DECL3(rgbd2Scan2d, approxSync, queueSize, (*rgbdSubs_[0]), (*rgbdSubs_[1]), scanSub_);
00532                         }
00533                 }
00534                 else if(subscribeScan3d)
00535                 {
00536                         subscribedToScan3d_ = true;
00537                         scan3dSub_.subscribe(nh, "scan_cloud", 1);
00538                         if(subscribeOdomInfo)
00539                         {
00540                                 subscribedToOdomInfo_ = true;
00541                                 odomInfoSub_.subscribe(nh, "odom_info", 1);
00542                                 SYNC_DECL4(rgbd2Scan3dInfo, approxSync, queueSize, (*rgbdSubs_[0]), (*rgbdSubs_[1]), scan3dSub_, odomInfoSub_);
00543                         }
00544                         else
00545                         {
00546                                 SYNC_DECL3(rgbd2Scan3d, approxSync, queueSize, (*rgbdSubs_[0]), (*rgbdSubs_[1]), scan3dSub_);
00547                         }
00548                 }
00549                 else if(subscribeOdomInfo)
00550                 {
00551                         subscribedToOdomInfo_ = true;
00552                         odomInfoSub_.subscribe(nh, "odom_info", 1);
00553                         SYNC_DECL3(rgbd2Info, approxSync, queueSize, (*rgbdSubs_[0]), (*rgbdSubs_[1]), odomInfoSub_);
00554                 }
00555                 else
00556                 {
00557                         SYNC_DECL2(rgbd2, approxSync, queueSize, (*rgbdSubs_[0]), (*rgbdSubs_[1]));
00558                 }
00559         }
00560 }
00561 
00562 } /* namespace rtabmap_ros */


rtabmap_ros
Author(s): Mathieu Labbe
autogenerated on Thu Jun 6 2019 21:30:49