CommonDataSubscriberRGBD.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 // 1 RGBD camera
00036 void CommonDataSubscriber::rgbdCallback(
00037                 const rtabmap_ros::RGBDImageConstPtr& image1Msg)
00038 {
00039         cv_bridge::CvImageConstPtr rgb, depth;
00040         rtabmap_ros::toCvShare(image1Msg, rgb, depth);
00041 
00042         rtabmap_ros::UserDataConstPtr userDataMsg; // Null
00043         nav_msgs::OdometryConstPtr odomMsg; // Null
00044         sensor_msgs::LaserScanConstPtr scanMsg; // Null
00045         sensor_msgs::PointCloud2ConstPtr scan3dMsg; // Null
00046         rtabmap_ros::OdomInfoConstPtr odomInfoMsg; // null
00047         commonSingleDepthCallback(odomMsg, userDataMsg, rgb, depth, image1Msg->rgbCameraInfo, image1Msg->depthCameraInfo, scanMsg, scan3dMsg, odomInfoMsg);
00048 }
00049 void CommonDataSubscriber::rgbdScan2dCallback(
00050                 const rtabmap_ros::RGBDImageConstPtr& image1Msg,
00051                 const sensor_msgs::LaserScanConstPtr& scanMsg)
00052 {
00053         cv_bridge::CvImageConstPtr rgb, depth;
00054         rtabmap_ros::toCvShare(image1Msg, rgb, depth);
00055 
00056         rtabmap_ros::UserDataConstPtr userDataMsg; // Null
00057         nav_msgs::OdometryConstPtr odomMsg; // Null
00058         sensor_msgs::PointCloud2ConstPtr scan3dMsg; // Null
00059         rtabmap_ros::OdomInfoConstPtr odomInfoMsg; // null
00060         commonSingleDepthCallback(odomMsg, userDataMsg, rgb, depth, image1Msg->rgbCameraInfo, image1Msg->depthCameraInfo, scanMsg, scan3dMsg, odomInfoMsg);
00061 }
00062 void CommonDataSubscriber::rgbdScan3dCallback(
00063                 const rtabmap_ros::RGBDImageConstPtr& image1Msg,
00064                 const sensor_msgs::PointCloud2ConstPtr& scan3dMsg)
00065 {
00066         cv_bridge::CvImageConstPtr rgb, depth;
00067         rtabmap_ros::toCvShare(image1Msg, rgb, depth);
00068 
00069         rtabmap_ros::UserDataConstPtr userDataMsg; // Null
00070         nav_msgs::OdometryConstPtr odomMsg; // Null
00071         sensor_msgs::LaserScanConstPtr scanMsg; // Null
00072         rtabmap_ros::OdomInfoConstPtr odomInfoMsg; // null
00073         commonSingleDepthCallback(odomMsg, userDataMsg, rgb, depth, image1Msg->rgbCameraInfo, image1Msg->depthCameraInfo, scanMsg, scan3dMsg, odomInfoMsg);
00074 }
00075 void CommonDataSubscriber::rgbdInfoCallback(
00076                 const rtabmap_ros::RGBDImageConstPtr& image1Msg,
00077                 const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg)
00078 {
00079         cv_bridge::CvImageConstPtr rgb, depth;
00080         rtabmap_ros::toCvShare(image1Msg, rgb, depth);
00081 
00082         rtabmap_ros::UserDataConstPtr userDataMsg; // Null
00083         nav_msgs::OdometryConstPtr odomMsg; // Null
00084         sensor_msgs::LaserScanConstPtr scanMsg; // Null
00085         sensor_msgs::PointCloud2ConstPtr scan3dMsg; // Null
00086         commonSingleDepthCallback(odomMsg, userDataMsg, rgb, depth, image1Msg->rgbCameraInfo, image1Msg->depthCameraInfo, scanMsg, scan3dMsg, odomInfoMsg);
00087 }
00088 void CommonDataSubscriber::rgbdScan2dInfoCallback(
00089                 const rtabmap_ros::RGBDImageConstPtr& image1Msg,
00090                 const sensor_msgs::LaserScanConstPtr& scanMsg,
00091                 const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg)
00092 {
00093         cv_bridge::CvImageConstPtr rgb, depth;
00094         rtabmap_ros::toCvShare(image1Msg, rgb, depth);
00095 
00096         rtabmap_ros::UserDataConstPtr userDataMsg; // Null
00097         nav_msgs::OdometryConstPtr odomMsg; // Null
00098         sensor_msgs::PointCloud2ConstPtr scan3dMsg; // Null
00099         commonSingleDepthCallback(odomMsg, userDataMsg, rgb, depth, image1Msg->rgbCameraInfo, image1Msg->depthCameraInfo, scanMsg, scan3dMsg, odomInfoMsg);
00100 }
00101 void CommonDataSubscriber::rgbdScan3dInfoCallback(
00102                 const rtabmap_ros::RGBDImageConstPtr& image1Msg,
00103                 const sensor_msgs::PointCloud2ConstPtr& scan3dMsg,
00104                 const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg)
00105 {
00106         cv_bridge::CvImageConstPtr rgb, depth;
00107         rtabmap_ros::toCvShare(image1Msg, rgb, depth);
00108 
00109         rtabmap_ros::UserDataConstPtr userDataMsg; // Null
00110         nav_msgs::OdometryConstPtr odomMsg; // Null
00111         sensor_msgs::LaserScanConstPtr scanMsg; // Null
00112         commonSingleDepthCallback(odomMsg, userDataMsg, rgb, depth, image1Msg->rgbCameraInfo, image1Msg->depthCameraInfo, scanMsg, scan3dMsg, odomInfoMsg);
00113 }
00114 
00115 // 1 RGBD camera + Odom
00116 void CommonDataSubscriber::rgbdOdomCallback(
00117                 const nav_msgs::OdometryConstPtr & odomMsg,
00118                 const rtabmap_ros::RGBDImageConstPtr& image1Msg)
00119 {
00120         cv_bridge::CvImageConstPtr rgb, depth;
00121         rtabmap_ros::toCvShare(image1Msg, rgb, depth);
00122 
00123         rtabmap_ros::UserDataConstPtr userDataMsg; // Null
00124         sensor_msgs::LaserScanConstPtr scanMsg; // Null
00125         sensor_msgs::PointCloud2ConstPtr scan3dMsg; // Null
00126         rtabmap_ros::OdomInfoConstPtr odomInfoMsg; // null
00127         commonSingleDepthCallback(odomMsg, userDataMsg, rgb, depth, image1Msg->rgbCameraInfo, image1Msg->depthCameraInfo, scanMsg, scan3dMsg, odomInfoMsg);
00128 }
00129 void CommonDataSubscriber::rgbdOdomScan2dCallback(
00130                 const nav_msgs::OdometryConstPtr & odomMsg,
00131                 const rtabmap_ros::RGBDImageConstPtr& image1Msg,
00132                 const sensor_msgs::LaserScanConstPtr& scanMsg)
00133 {
00134         cv_bridge::CvImageConstPtr rgb, depth;
00135         rtabmap_ros::toCvShare(image1Msg, rgb, depth);
00136 
00137         rtabmap_ros::UserDataConstPtr userDataMsg; // Null
00138         sensor_msgs::PointCloud2ConstPtr scan3dMsg; // Null
00139         rtabmap_ros::OdomInfoConstPtr odomInfoMsg; // null
00140         commonSingleDepthCallback(odomMsg, userDataMsg, rgb, depth, image1Msg->rgbCameraInfo, image1Msg->depthCameraInfo, scanMsg, scan3dMsg, odomInfoMsg);
00141 }
00142 void CommonDataSubscriber::rgbdOdomScan3dCallback(
00143                 const nav_msgs::OdometryConstPtr & odomMsg,
00144                 const rtabmap_ros::RGBDImageConstPtr& image1Msg,
00145                 const sensor_msgs::PointCloud2ConstPtr& scan3dMsg)
00146 {
00147         cv_bridge::CvImageConstPtr rgb, depth;
00148         rtabmap_ros::toCvShare(image1Msg, rgb, depth);
00149 
00150         rtabmap_ros::UserDataConstPtr userDataMsg; // Null
00151         sensor_msgs::LaserScanConstPtr scanMsg; // Null
00152         rtabmap_ros::OdomInfoConstPtr odomInfoMsg; // null
00153         commonSingleDepthCallback(odomMsg, userDataMsg, rgb, depth, image1Msg->rgbCameraInfo, image1Msg->depthCameraInfo, scanMsg, scan3dMsg, odomInfoMsg);
00154 }
00155 void CommonDataSubscriber::rgbdOdomInfoCallback(
00156                 const nav_msgs::OdometryConstPtr & odomMsg,
00157                 const rtabmap_ros::RGBDImageConstPtr& image1Msg,
00158                 const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg)
00159 {
00160         cv_bridge::CvImageConstPtr rgb, depth;
00161         rtabmap_ros::toCvShare(image1Msg, rgb, depth);
00162 
00163         rtabmap_ros::UserDataConstPtr userDataMsg; // Null
00164         sensor_msgs::LaserScanConstPtr scanMsg; // Null
00165         sensor_msgs::PointCloud2ConstPtr scan3dMsg; // Null
00166         commonSingleDepthCallback(odomMsg, userDataMsg, rgb, depth, image1Msg->rgbCameraInfo, image1Msg->depthCameraInfo, scanMsg, scan3dMsg, odomInfoMsg);
00167 }
00168 void CommonDataSubscriber::rgbdOdomScan2dInfoCallback(
00169                 const nav_msgs::OdometryConstPtr & odomMsg,
00170                 const rtabmap_ros::RGBDImageConstPtr& image1Msg,
00171                 const sensor_msgs::LaserScanConstPtr& scanMsg,
00172                 const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg)
00173 {
00174         cv_bridge::CvImageConstPtr rgb, depth;
00175         rtabmap_ros::toCvShare(image1Msg, rgb, depth);
00176 
00177         rtabmap_ros::UserDataConstPtr userDataMsg; // Null
00178         sensor_msgs::PointCloud2ConstPtr scan3dMsg; // Null
00179         commonSingleDepthCallback(odomMsg, userDataMsg, rgb, depth, image1Msg->rgbCameraInfo, image1Msg->depthCameraInfo, scanMsg, scan3dMsg, odomInfoMsg);
00180 }
00181 void CommonDataSubscriber::rgbdOdomScan3dInfoCallback(
00182                 const nav_msgs::OdometryConstPtr & odomMsg,
00183                 const rtabmap_ros::RGBDImageConstPtr& image1Msg,
00184                 const sensor_msgs::PointCloud2ConstPtr& scan3dMsg,
00185                 const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg)
00186 {
00187         cv_bridge::CvImageConstPtr rgb, depth;
00188         rtabmap_ros::toCvShare(image1Msg, rgb, depth);
00189 
00190         rtabmap_ros::UserDataConstPtr userDataMsg; // Null
00191         sensor_msgs::LaserScanConstPtr scanMsg; // Null
00192         commonSingleDepthCallback(odomMsg, userDataMsg, rgb, depth, image1Msg->rgbCameraInfo, image1Msg->depthCameraInfo, scanMsg, scan3dMsg, odomInfoMsg);
00193 }
00194 
00195 // 1 RGBD camera + User Data
00196 void CommonDataSubscriber::rgbdDataCallback(
00197                 const rtabmap_ros::UserDataConstPtr & userDataMsg,
00198                 const rtabmap_ros::RGBDImageConstPtr& image1Msg)
00199 {
00200         cv_bridge::CvImageConstPtr rgb, depth;
00201         rtabmap_ros::toCvShare(image1Msg, rgb, depth);
00202 
00203         nav_msgs::OdometryConstPtr odomMsg; // Null
00204         sensor_msgs::LaserScanConstPtr scanMsg; // Null
00205         sensor_msgs::PointCloud2ConstPtr scan3dMsg; // Null
00206         rtabmap_ros::OdomInfoConstPtr odomInfoMsg; // null
00207         commonSingleDepthCallback(odomMsg, userDataMsg, rgb, depth, image1Msg->rgbCameraInfo, image1Msg->depthCameraInfo, scanMsg, scan3dMsg, odomInfoMsg);
00208 }
00209 void CommonDataSubscriber::rgbdDataScan2dCallback(
00210                 const rtabmap_ros::UserDataConstPtr & userDataMsg,
00211                 const rtabmap_ros::RGBDImageConstPtr& image1Msg,
00212                 const sensor_msgs::LaserScanConstPtr& scanMsg)
00213 {
00214         cv_bridge::CvImageConstPtr rgb, depth;
00215         rtabmap_ros::toCvShare(image1Msg, rgb, depth);
00216 
00217         nav_msgs::OdometryConstPtr odomMsg; // Null
00218         sensor_msgs::PointCloud2ConstPtr scan3dMsg; // Null
00219         rtabmap_ros::OdomInfoConstPtr odomInfoMsg; // null
00220         commonSingleDepthCallback(odomMsg, userDataMsg,rgb, depth, image1Msg->rgbCameraInfo, image1Msg->depthCameraInfo, scanMsg, scan3dMsg, odomInfoMsg);
00221 }
00222 void CommonDataSubscriber::rgbdDataScan3dCallback(
00223                 const rtabmap_ros::UserDataConstPtr & userDataMsg,
00224                 const rtabmap_ros::RGBDImageConstPtr& image1Msg,
00225                 const sensor_msgs::PointCloud2ConstPtr& scan3dMsg)
00226 {
00227         cv_bridge::CvImageConstPtr rgb, depth;
00228         rtabmap_ros::toCvShare(image1Msg, rgb, depth);
00229 
00230         nav_msgs::OdometryConstPtr odomMsg; // Null
00231         sensor_msgs::LaserScanConstPtr scanMsg; // Null
00232         rtabmap_ros::OdomInfoConstPtr odomInfoMsg; // null
00233         commonSingleDepthCallback(odomMsg, userDataMsg,rgb, depth, image1Msg->rgbCameraInfo, image1Msg->depthCameraInfo, scanMsg, scan3dMsg, odomInfoMsg);
00234 }
00235 void CommonDataSubscriber::rgbdDataInfoCallback(
00236                 const rtabmap_ros::UserDataConstPtr & userDataMsg,
00237                 const rtabmap_ros::RGBDImageConstPtr& image1Msg,
00238                 const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg)
00239 {
00240         cv_bridge::CvImageConstPtr rgb, depth;
00241         rtabmap_ros::toCvShare(image1Msg, rgb, depth);
00242 
00243         nav_msgs::OdometryConstPtr odomMsg; // Null
00244         sensor_msgs::LaserScanConstPtr scanMsg; // Null
00245         sensor_msgs::PointCloud2ConstPtr scan3dMsg; // Null
00246         commonSingleDepthCallback(odomMsg, userDataMsg,rgb, depth, image1Msg->rgbCameraInfo, image1Msg->depthCameraInfo, scanMsg, scan3dMsg, odomInfoMsg);
00247 }
00248 void CommonDataSubscriber::rgbdDataScan2dInfoCallback(
00249                 const rtabmap_ros::UserDataConstPtr & userDataMsg,
00250                 const rtabmap_ros::RGBDImageConstPtr& image1Msg,
00251                 const sensor_msgs::LaserScanConstPtr& scanMsg,
00252                 const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg)
00253 {
00254         cv_bridge::CvImageConstPtr rgb, depth;
00255         rtabmap_ros::toCvShare(image1Msg, rgb, depth);
00256 
00257         nav_msgs::OdometryConstPtr odomMsg; // Null
00258         sensor_msgs::PointCloud2ConstPtr scan3dMsg; // Null
00259         commonSingleDepthCallback(odomMsg, userDataMsg,rgb, depth, image1Msg->rgbCameraInfo, image1Msg->depthCameraInfo, scanMsg, scan3dMsg, odomInfoMsg);
00260 }
00261 void CommonDataSubscriber::rgbdDataScan3dInfoCallback(
00262                 const rtabmap_ros::UserDataConstPtr & userDataMsg,
00263                 const rtabmap_ros::RGBDImageConstPtr& image1Msg,
00264                 const sensor_msgs::PointCloud2ConstPtr& scan3dMsg,
00265                 const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg)
00266 {
00267         cv_bridge::CvImageConstPtr rgb, depth;
00268         rtabmap_ros::toCvShare(image1Msg, rgb, depth);
00269 
00270         nav_msgs::OdometryConstPtr odomMsg; // Null
00271         sensor_msgs::LaserScanConstPtr scanMsg; // Null
00272         commonSingleDepthCallback(odomMsg, userDataMsg,rgb, depth, image1Msg->rgbCameraInfo, image1Msg->depthCameraInfo, scanMsg, scan3dMsg, odomInfoMsg);
00273 }
00274 
00275 // 1 RGBD camera + Odom + User Data
00276 void CommonDataSubscriber::rgbdOdomDataCallback(
00277                 const nav_msgs::OdometryConstPtr & odomMsg,
00278                 const rtabmap_ros::UserDataConstPtr & userDataMsg,
00279                 const rtabmap_ros::RGBDImageConstPtr& image1Msg)
00280 {
00281         cv_bridge::CvImageConstPtr rgb, depth;
00282         rtabmap_ros::toCvShare(image1Msg, rgb, depth);
00283 
00284         sensor_msgs::LaserScanConstPtr scanMsg; // Null
00285         sensor_msgs::PointCloud2ConstPtr scan3dMsg; // Null
00286         rtabmap_ros::OdomInfoConstPtr odomInfoMsg; // null
00287         commonSingleDepthCallback(odomMsg, userDataMsg,rgb, depth, image1Msg->rgbCameraInfo, image1Msg->depthCameraInfo, scanMsg, scan3dMsg, odomInfoMsg);
00288 }
00289 void CommonDataSubscriber::rgbdOdomDataScan2dCallback(
00290                 const nav_msgs::OdometryConstPtr & odomMsg,
00291                 const rtabmap_ros::UserDataConstPtr & userDataMsg,
00292                 const rtabmap_ros::RGBDImageConstPtr& image1Msg,
00293                 const sensor_msgs::LaserScanConstPtr& scanMsg)
00294 {
00295         cv_bridge::CvImageConstPtr rgb, depth;
00296         rtabmap_ros::toCvShare(image1Msg, rgb, depth);
00297 
00298         sensor_msgs::PointCloud2ConstPtr scan3dMsg; // Null
00299         rtabmap_ros::OdomInfoConstPtr odomInfoMsg; // null
00300         commonSingleDepthCallback(odomMsg, userDataMsg,rgb, depth, image1Msg->rgbCameraInfo, image1Msg->depthCameraInfo, scanMsg, scan3dMsg, odomInfoMsg);
00301 }
00302 void CommonDataSubscriber::rgbdOdomDataScan3dCallback(
00303                 const nav_msgs::OdometryConstPtr & odomMsg,
00304                 const rtabmap_ros::UserDataConstPtr & userDataMsg,
00305                 const rtabmap_ros::RGBDImageConstPtr& image1Msg,
00306                 const sensor_msgs::PointCloud2ConstPtr& scan3dMsg)
00307 {
00308         cv_bridge::CvImageConstPtr rgb, depth;
00309         rtabmap_ros::toCvShare(image1Msg, rgb, depth);
00310 
00311         sensor_msgs::LaserScanConstPtr scanMsg; // Null
00312         rtabmap_ros::OdomInfoConstPtr odomInfoMsg; // null
00313         commonSingleDepthCallback(odomMsg, userDataMsg,rgb, depth, image1Msg->rgbCameraInfo, image1Msg->depthCameraInfo, scanMsg, scan3dMsg, odomInfoMsg);
00314 }
00315 void CommonDataSubscriber::rgbdOdomDataInfoCallback(
00316                 const nav_msgs::OdometryConstPtr & odomMsg,
00317                 const rtabmap_ros::UserDataConstPtr & userDataMsg,
00318                 const rtabmap_ros::RGBDImageConstPtr& image1Msg,
00319                 const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg)
00320 {
00321         cv_bridge::CvImageConstPtr rgb, depth;
00322         rtabmap_ros::toCvShare(image1Msg, rgb, depth);
00323 
00324         sensor_msgs::LaserScanConstPtr scanMsg; // Null
00325         sensor_msgs::PointCloud2ConstPtr scan3dMsg; // Null
00326         commonSingleDepthCallback(odomMsg, userDataMsg,rgb, depth, image1Msg->rgbCameraInfo, image1Msg->depthCameraInfo, scanMsg, scan3dMsg, odomInfoMsg);
00327 }
00328 void CommonDataSubscriber::rgbdOdomDataScan2dInfoCallback(
00329                 const nav_msgs::OdometryConstPtr & odomMsg,
00330                 const rtabmap_ros::UserDataConstPtr & userDataMsg,
00331                 const rtabmap_ros::RGBDImageConstPtr& image1Msg,
00332                 const sensor_msgs::LaserScanConstPtr& scanMsg,
00333                 const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg)
00334 {
00335         cv_bridge::CvImageConstPtr rgb, depth;
00336         rtabmap_ros::toCvShare(image1Msg, rgb, depth);
00337 
00338         sensor_msgs::PointCloud2ConstPtr scan3dMsg; // Null
00339         commonSingleDepthCallback(odomMsg, userDataMsg,rgb, depth, image1Msg->rgbCameraInfo, image1Msg->depthCameraInfo, scanMsg, scan3dMsg, odomInfoMsg);
00340 }
00341 void CommonDataSubscriber::rgbdOdomDataScan3dInfoCallback(
00342                 const nav_msgs::OdometryConstPtr & odomMsg,
00343                 const rtabmap_ros::UserDataConstPtr & userDataMsg,
00344                 const rtabmap_ros::RGBDImageConstPtr& image1Msg,
00345                 const sensor_msgs::PointCloud2ConstPtr& scan3dMsg,
00346                 const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg)
00347 {
00348         cv_bridge::CvImageConstPtr rgb, depth;
00349         rtabmap_ros::toCvShare(image1Msg, rgb, depth);
00350 
00351         sensor_msgs::LaserScanConstPtr scanMsg; // Null
00352         commonSingleDepthCallback(odomMsg, userDataMsg,rgb, depth, image1Msg->rgbCameraInfo, image1Msg->depthCameraInfo, scanMsg, scan3dMsg, odomInfoMsg);
00353 }
00354 
00355 void CommonDataSubscriber::setupRGBDCallbacks(
00356                 ros::NodeHandle & nh,
00357                 ros::NodeHandle & pnh,
00358                 bool subscribeOdom,
00359                 bool subscribeUserData,
00360                 bool subscribeScan2d,
00361                 bool subscribeScan3d,
00362                 bool subscribeOdomInfo,
00363                 int queueSize,
00364                 bool approxSync)
00365 {
00366         ROS_INFO("Setup rgbd callback");
00367 
00368         if(subscribeOdom || subscribeUserData || subscribeScan2d || subscribeScan3d || subscribeOdomInfo)
00369         {
00370                 rgbdSubs_.resize(1);
00371                 rgbdSubs_[0] = new message_filters::Subscriber<rtabmap_ros::RGBDImage>;
00372                 rgbdSubs_[0]->subscribe(nh, "rgbd_image", 1);
00373 
00374 
00375                 if(subscribeOdom && subscribeUserData)
00376                 {
00377                         odomSub_.subscribe(nh, "odom", 1);
00378                         userDataSub_.subscribe(nh, "user_data", 1);
00379                         if(subscribeScan2d)
00380                         {
00381                                 subscribedToScan2d_ = true;
00382                                 scanSub_.subscribe(nh, "scan", 1);
00383                                 if(subscribeOdomInfo)
00384                                 {
00385                                         subscribedToOdomInfo_ = true;
00386                                         odomInfoSub_.subscribe(nh, "odom_info", 1);
00387                                         SYNC_DECL5(rgbdOdomDataScan2dInfo, approxSync, queueSize, odomSub_, userDataSub_, (*rgbdSubs_[0]), scanSub_, odomInfoSub_);
00388                                 }
00389                                 else
00390                                 {
00391                                         SYNC_DECL4(rgbdOdomDataScan2d, approxSync, queueSize, odomSub_, userDataSub_, (*rgbdSubs_[0]), scanSub_);
00392                                 }
00393                         }
00394                         else if(subscribeScan3d)
00395                         {
00396                                 subscribedToScan3d_ = true;
00397                                 scan3dSub_.subscribe(nh, "scan_cloud", 1);
00398                                 if(subscribeOdomInfo)
00399                                 {
00400                                         subscribedToOdomInfo_ = true;
00401                                         odomInfoSub_.subscribe(nh, "odom_info", 1);
00402                                         SYNC_DECL5(rgbdOdomDataScan3dInfo, approxSync, queueSize, odomSub_, userDataSub_, (*rgbdSubs_[0]), scan3dSub_, odomInfoSub_);
00403                                 }
00404                                 else
00405                                 {
00406                                         SYNC_DECL4(rgbdOdomDataScan3d, approxSync, queueSize, odomSub_, userDataSub_, (*rgbdSubs_[0]), scan3dSub_);
00407                                 }
00408                         }
00409                         else if(subscribeOdomInfo)
00410                         {
00411                                 subscribedToOdomInfo_ = true;
00412                                 odomInfoSub_.subscribe(nh, "odom_info", 1);
00413                                 SYNC_DECL4(rgbdOdomDataInfo, approxSync, queueSize, odomSub_, userDataSub_, (*rgbdSubs_[0]), odomInfoSub_);
00414                         }
00415                         else
00416                         {
00417                                 SYNC_DECL3(rgbdOdomData, approxSync, queueSize, odomSub_, userDataSub_, (*rgbdSubs_[0]));
00418                         }
00419                 }
00420                 else if(subscribeOdom)
00421                 {
00422                         odomSub_.subscribe(nh, "odom", 1);
00423                         if(subscribeScan2d)
00424                         {
00425                                 subscribedToScan2d_ = true;
00426                                 scanSub_.subscribe(nh, "scan", 1);
00427                                 if(subscribeOdomInfo)
00428                                 {
00429                                         subscribedToOdomInfo_ = true;
00430                                         odomInfoSub_.subscribe(nh, "odom_info", 1);
00431                                         SYNC_DECL4(rgbdOdomScan2dInfo, approxSync, queueSize, odomSub_, (*rgbdSubs_[0]), scanSub_, odomInfoSub_);
00432                                 }
00433                                 else
00434                                 {
00435                                         SYNC_DECL3(rgbdOdomScan2d, approxSync, queueSize, odomSub_, (*rgbdSubs_[0]), scanSub_);
00436                                 }
00437                         }
00438                         else if(subscribeScan3d)
00439                         {
00440                                 subscribedToScan3d_ = true;
00441                                 scan3dSub_.subscribe(nh, "scan_cloud", 1);
00442                                 if(subscribeOdomInfo)
00443                                 {
00444                                         subscribedToOdomInfo_ = true;
00445                                         odomInfoSub_.subscribe(nh, "odom_info", 1);
00446                                         SYNC_DECL4(rgbdOdomScan3dInfo, approxSync, queueSize, odomSub_, (*rgbdSubs_[0]), scan3dSub_, odomInfoSub_);
00447                                 }
00448                                 else
00449                                 {
00450                                         SYNC_DECL3(rgbdOdomScan3d, approxSync, queueSize, odomSub_, (*rgbdSubs_[0]), scan3dSub_);
00451                                 }
00452                         }
00453                         else if(subscribeOdomInfo)
00454                         {
00455                                 subscribedToOdomInfo_ = true;
00456                                 odomInfoSub_.subscribe(nh, "odom_info", 1);
00457                                 SYNC_DECL3(rgbdOdomInfo, approxSync, queueSize, odomSub_, (*rgbdSubs_[0]), odomInfoSub_);
00458                         }
00459                         else
00460                         {
00461                                 SYNC_DECL2(rgbdOdom, approxSync, queueSize, odomSub_, (*rgbdSubs_[0]));
00462                         }
00463                 }
00464                 else if(subscribeUserData)
00465                 {
00466                         userDataSub_.subscribe(nh, "user_data", 1);
00467                         if(subscribeScan2d)
00468                         {
00469                                 subscribedToScan2d_ = true;
00470                                 scanSub_.subscribe(nh, "scan", 1);
00471                                 if(subscribeOdomInfo)
00472                                 {
00473                                         subscribedToOdomInfo_ = true;
00474                                         odomInfoSub_.subscribe(nh, "odom_info", 1);
00475                                         SYNC_DECL4(rgbdDataScan2dInfo, approxSync, queueSize, userDataSub_, (*rgbdSubs_[0]), scanSub_, odomInfoSub_);
00476                                 }
00477                                 else
00478                                 {
00479                                         SYNC_DECL3(rgbdDataScan2d, approxSync, queueSize, userDataSub_, (*rgbdSubs_[0]), scanSub_);
00480                                 }
00481                         }
00482                         else if(subscribeScan3d)
00483                         {
00484                                 subscribedToScan3d_ = true;
00485                                 scan3dSub_.subscribe(nh, "scan_cloud", 1);
00486                                 if(subscribeOdomInfo)
00487                                 {
00488                                         subscribedToOdomInfo_ = true;
00489                                         odomInfoSub_.subscribe(nh, "odom_info", 1);
00490                                         SYNC_DECL4(rgbdDataScan3dInfo, approxSync, queueSize, userDataSub_, (*rgbdSubs_[0]), scan3dSub_, odomInfoSub_);
00491                                 }
00492                                 else
00493                                 {
00494                                         SYNC_DECL3(rgbdDataScan3d, approxSync, queueSize, userDataSub_, (*rgbdSubs_[0]), scan3dSub_);
00495                                 }
00496                         }
00497                         else if(subscribeOdomInfo)
00498                         {
00499                                 subscribedToOdomInfo_ = true;
00500                                 odomInfoSub_.subscribe(nh, "odom_info", 1);
00501                                 SYNC_DECL3(rgbdDataInfo, approxSync, queueSize, userDataSub_, (*rgbdSubs_[0]), odomInfoSub_);
00502                         }
00503                         else
00504                         {
00505                                 SYNC_DECL2(rgbdData, approxSync, queueSize, userDataSub_, (*rgbdSubs_[0]));
00506                         }
00507                 }
00508                 else
00509                 {
00510                         if(subscribeScan2d)
00511                         {
00512                                 subscribedToScan2d_ = true;
00513                                 scanSub_.subscribe(nh, "scan", 1);
00514                                 if(subscribeOdomInfo)
00515                                 {
00516                                         subscribedToOdomInfo_ = true;
00517                                         odomInfoSub_.subscribe(nh, "odom_info", 1);
00518                                         SYNC_DECL3(rgbdScan2dInfo, approxSync, queueSize, (*rgbdSubs_[0]), scanSub_, odomInfoSub_);
00519                                 }
00520                                 else
00521                                 {
00522                                         SYNC_DECL2(rgbdScan2d, approxSync, queueSize, (*rgbdSubs_[0]), scanSub_);
00523                                 }
00524                         }
00525                         else if(subscribeScan3d)
00526                         {
00527                                 subscribedToScan3d_ = true;
00528                                 scan3dSub_.subscribe(nh, "scan_cloud", 1);
00529                                 if(subscribeOdomInfo)
00530                                 {
00531                                         subscribedToOdomInfo_ = true;
00532                                         odomInfoSub_.subscribe(nh, "odom_info", 1);
00533                                         SYNC_DECL3(rgbdScan3dInfo, approxSync, queueSize, (*rgbdSubs_[0]), scan3dSub_, odomInfoSub_);
00534                                 }
00535                                 else
00536                                 {
00537                                         SYNC_DECL2(rgbdScan3d, approxSync, queueSize, (*rgbdSubs_[0]), scan3dSub_);
00538                                 }
00539                         }
00540                         else if(subscribeOdomInfo)
00541                         {
00542                                 subscribedToOdomInfo_ = true;
00543                                 odomInfoSub_.subscribe(nh, "odom_info", 1);
00544                                 SYNC_DECL2(rgbdInfo, approxSync, queueSize, (*rgbdSubs_[0]), odomInfoSub_);
00545                         }
00546                         else
00547                         {
00548                                 ROS_FATAL("Not supposed to be here!");
00549                         }
00550                 }
00551         }
00552         else
00553         {
00554                 rgbdSub_ = nh.subscribe("rgbd_image", 1, &CommonDataSubscriber::rgbdCallback, this);
00555 
00556                 subscribedTopicsMsg_ =
00557                                 uFormat("\n%s subscribed to:\n   %s",
00558                                 ros::this_node::getName().c_str(),
00559                                 rgbdSub_.getTopic().c_str());
00560         }
00561 }
00562 
00563 } /* namespace rtabmap_ros */


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