CommonDataSubscriberRGBD4.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(4); \
00038                 std::vector<cv_bridge::CvImageConstPtr> depthMsgs(4); \
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                 rtabmap_ros::toCvShare(image4Msg, imageMsgs[3], depthMsgs[3]); \
00043                 std::vector<sensor_msgs::CameraInfo> cameraInfoMsgs; \
00044                 cameraInfoMsgs.push_back(image1Msg->rgbCameraInfo); \
00045                 cameraInfoMsgs.push_back(image2Msg->rgbCameraInfo); \
00046                 cameraInfoMsgs.push_back(image3Msg->rgbCameraInfo); \
00047                 cameraInfoMsgs.push_back(image4Msg->rgbCameraInfo);
00048 
00049 // 4 RGBD
00050 void CommonDataSubscriber::rgbd4Callback(
00051                 const rtabmap_ros::RGBDImageConstPtr& image1Msg,
00052                 const rtabmap_ros::RGBDImageConstPtr& image2Msg,
00053                 const rtabmap_ros::RGBDImageConstPtr& image3Msg,
00054                 const rtabmap_ros::RGBDImageConstPtr& image4Msg)
00055 {
00056         IMAGE_CONVERSION();
00057 
00058         nav_msgs::OdometryConstPtr odomMsg; // Null
00059         rtabmap_ros::UserDataConstPtr userDataMsg; // Null
00060         sensor_msgs::LaserScanConstPtr scanMsg; // Null
00061         sensor_msgs::PointCloud2ConstPtr scan3dMsg; // Null
00062         rtabmap_ros::OdomInfoConstPtr odomInfoMsg; // null
00063         commonDepthCallback(odomMsg, userDataMsg, imageMsgs, depthMsgs, cameraInfoMsgs, scanMsg, scan3dMsg, odomInfoMsg);
00064 }
00065 void CommonDataSubscriber::rgbd4Scan2dCallback(
00066                 const rtabmap_ros::RGBDImageConstPtr& image1Msg,
00067                 const rtabmap_ros::RGBDImageConstPtr& image2Msg,
00068                 const rtabmap_ros::RGBDImageConstPtr& image3Msg,
00069                 const rtabmap_ros::RGBDImageConstPtr& image4Msg,
00070                 const sensor_msgs::LaserScanConstPtr& scanMsg)
00071 {
00072         IMAGE_CONVERSION();
00073 
00074         nav_msgs::OdometryConstPtr odomMsg; // Null
00075         rtabmap_ros::UserDataConstPtr userDataMsg; // Null
00076         sensor_msgs::PointCloud2ConstPtr scan3dMsg; // Null
00077         rtabmap_ros::OdomInfoConstPtr odomInfoMsg; // null
00078         commonDepthCallback(odomMsg, userDataMsg, imageMsgs, depthMsgs, cameraInfoMsgs, scanMsg, scan3dMsg, odomInfoMsg);
00079 }
00080 void CommonDataSubscriber::rgbd4Scan3dCallback(
00081                 const rtabmap_ros::RGBDImageConstPtr& image1Msg,
00082                 const rtabmap_ros::RGBDImageConstPtr& image2Msg,
00083                 const rtabmap_ros::RGBDImageConstPtr& image3Msg,
00084                 const rtabmap_ros::RGBDImageConstPtr& image4Msg,
00085                 const sensor_msgs::PointCloud2ConstPtr& scan3dMsg)
00086 {
00087         IMAGE_CONVERSION();
00088 
00089         nav_msgs::OdometryConstPtr odomMsg; // Null
00090         rtabmap_ros::UserDataConstPtr userDataMsg; // Null
00091         sensor_msgs::LaserScanConstPtr scanMsg; // Null
00092         rtabmap_ros::OdomInfoConstPtr odomInfoMsg; // null
00093         commonDepthCallback(odomMsg, userDataMsg, imageMsgs, depthMsgs, cameraInfoMsgs, scanMsg, scan3dMsg, odomInfoMsg);
00094 }
00095 void CommonDataSubscriber::rgbd4InfoCallback(
00096                 const rtabmap_ros::RGBDImageConstPtr& image1Msg,
00097                 const rtabmap_ros::RGBDImageConstPtr& image2Msg,
00098                 const rtabmap_ros::RGBDImageConstPtr& image3Msg,
00099                 const rtabmap_ros::RGBDImageConstPtr& image4Msg,
00100                 const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg)
00101 {
00102         IMAGE_CONVERSION();
00103 
00104         nav_msgs::OdometryConstPtr odomMsg; // Null
00105         rtabmap_ros::UserDataConstPtr userDataMsg; // Null
00106         sensor_msgs::LaserScanConstPtr scanMsg; // Null
00107         sensor_msgs::PointCloud2ConstPtr scan3dMsg; // Null
00108         commonDepthCallback(odomMsg, userDataMsg, imageMsgs, depthMsgs, cameraInfoMsgs, scanMsg, scan3dMsg, odomInfoMsg);
00109 }
00110 void CommonDataSubscriber::rgbd4Scan2dInfoCallback(
00111                 const rtabmap_ros::RGBDImageConstPtr& image1Msg,
00112                 const rtabmap_ros::RGBDImageConstPtr& image2Msg,
00113                 const rtabmap_ros::RGBDImageConstPtr& image3Msg,
00114                 const rtabmap_ros::RGBDImageConstPtr& image4Msg,
00115                 const sensor_msgs::LaserScanConstPtr& scanMsg,
00116                 const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg)
00117 {
00118         IMAGE_CONVERSION();
00119 
00120         nav_msgs::OdometryConstPtr odomMsg; // Null
00121         rtabmap_ros::UserDataConstPtr userDataMsg; // Null
00122         sensor_msgs::PointCloud2ConstPtr scan3dMsg; // Null
00123         commonDepthCallback(odomMsg, userDataMsg, imageMsgs, depthMsgs, cameraInfoMsgs, scanMsg, scan3dMsg, odomInfoMsg);
00124 }
00125 void CommonDataSubscriber::rgbd4Scan3dInfoCallback(
00126                 const rtabmap_ros::RGBDImageConstPtr& image1Msg,
00127                 const rtabmap_ros::RGBDImageConstPtr& image2Msg,
00128                 const rtabmap_ros::RGBDImageConstPtr& image3Msg,
00129                 const rtabmap_ros::RGBDImageConstPtr& image4Msg,
00130                 const sensor_msgs::PointCloud2ConstPtr& scan3dMsg,
00131                 const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg)
00132 {
00133         IMAGE_CONVERSION();
00134 
00135         nav_msgs::OdometryConstPtr odomMsg; // Null
00136         rtabmap_ros::UserDataConstPtr userDataMsg; // Null
00137         sensor_msgs::LaserScanConstPtr scanMsg; // Null
00138         commonDepthCallback(odomMsg, userDataMsg, imageMsgs, depthMsgs, cameraInfoMsgs, scanMsg, scan3dMsg, odomInfoMsg);
00139 }
00140 
00141 // 2 RGBD + Odom
00142 void CommonDataSubscriber::rgbd4OdomCallback(
00143                 const nav_msgs::OdometryConstPtr & odomMsg,
00144                 const rtabmap_ros::RGBDImageConstPtr& image1Msg,
00145                 const rtabmap_ros::RGBDImageConstPtr& image2Msg,
00146                 const rtabmap_ros::RGBDImageConstPtr& image3Msg,
00147                 const rtabmap_ros::RGBDImageConstPtr& image4Msg)
00148 {
00149         IMAGE_CONVERSION();
00150 
00151         rtabmap_ros::UserDataConstPtr userDataMsg; // Null
00152         sensor_msgs::LaserScanConstPtr scanMsg; // Null
00153         sensor_msgs::PointCloud2ConstPtr scan3dMsg; // Null
00154         rtabmap_ros::OdomInfoConstPtr odomInfoMsg; // null
00155         commonDepthCallback(odomMsg, userDataMsg, imageMsgs, depthMsgs, cameraInfoMsgs, scanMsg, scan3dMsg, odomInfoMsg);
00156 }
00157 void CommonDataSubscriber::rgbd4OdomScan2dCallback(
00158                 const nav_msgs::OdometryConstPtr & odomMsg,
00159                 const rtabmap_ros::RGBDImageConstPtr& image1Msg,
00160                 const rtabmap_ros::RGBDImageConstPtr& image2Msg,
00161                 const rtabmap_ros::RGBDImageConstPtr& image3Msg,
00162                 const rtabmap_ros::RGBDImageConstPtr& image4Msg,
00163                 const sensor_msgs::LaserScanConstPtr& scanMsg)
00164 {
00165         IMAGE_CONVERSION();
00166 
00167         rtabmap_ros::UserDataConstPtr userDataMsg; // Null
00168         sensor_msgs::PointCloud2ConstPtr scan3dMsg; // Null
00169         rtabmap_ros::OdomInfoConstPtr odomInfoMsg; // null
00170         commonDepthCallback(odomMsg, userDataMsg, imageMsgs, depthMsgs, cameraInfoMsgs, scanMsg, scan3dMsg, odomInfoMsg);
00171 }
00172 void CommonDataSubscriber::rgbd4OdomScan3dCallback(
00173                 const nav_msgs::OdometryConstPtr & odomMsg,
00174                 const rtabmap_ros::RGBDImageConstPtr& image1Msg,
00175                 const rtabmap_ros::RGBDImageConstPtr& image2Msg,
00176                 const rtabmap_ros::RGBDImageConstPtr& image3Msg,
00177                 const rtabmap_ros::RGBDImageConstPtr& image4Msg,
00178                 const sensor_msgs::PointCloud2ConstPtr& scan3dMsg)
00179 {
00180         IMAGE_CONVERSION();
00181 
00182         rtabmap_ros::UserDataConstPtr userDataMsg; // Null
00183         sensor_msgs::LaserScanConstPtr scanMsg; // Null
00184         rtabmap_ros::OdomInfoConstPtr odomInfoMsg; // null
00185         commonDepthCallback(odomMsg, userDataMsg, imageMsgs, depthMsgs, cameraInfoMsgs, scanMsg, scan3dMsg, odomInfoMsg);
00186 }
00187 void CommonDataSubscriber::rgbd4OdomInfoCallback(
00188                 const nav_msgs::OdometryConstPtr & odomMsg,
00189                 const rtabmap_ros::RGBDImageConstPtr& image1Msg,
00190                 const rtabmap_ros::RGBDImageConstPtr& image2Msg,
00191                 const rtabmap_ros::RGBDImageConstPtr& image3Msg,
00192                 const rtabmap_ros::RGBDImageConstPtr& image4Msg,
00193                 const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg)
00194 {
00195         IMAGE_CONVERSION();
00196 
00197         rtabmap_ros::UserDataConstPtr userDataMsg; // Null
00198         sensor_msgs::LaserScanConstPtr scanMsg; // Null
00199         sensor_msgs::PointCloud2ConstPtr scan3dMsg; // Null
00200         commonDepthCallback(odomMsg, userDataMsg, imageMsgs, depthMsgs, cameraInfoMsgs, scanMsg, scan3dMsg, odomInfoMsg);
00201 }
00202 void CommonDataSubscriber::rgbd4OdomScan2dInfoCallback(
00203                 const nav_msgs::OdometryConstPtr & odomMsg,
00204                 const rtabmap_ros::RGBDImageConstPtr& image1Msg,
00205                 const rtabmap_ros::RGBDImageConstPtr& image2Msg,
00206                 const rtabmap_ros::RGBDImageConstPtr& image3Msg,
00207                 const rtabmap_ros::RGBDImageConstPtr& image4Msg,
00208                 const sensor_msgs::LaserScanConstPtr& scanMsg,
00209                 const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg)
00210 {
00211         IMAGE_CONVERSION();
00212 
00213         rtabmap_ros::UserDataConstPtr userDataMsg; // Null
00214         sensor_msgs::PointCloud2ConstPtr scan3dMsg; // Null
00215         commonDepthCallback(odomMsg, userDataMsg, imageMsgs, depthMsgs, cameraInfoMsgs, scanMsg, scan3dMsg, odomInfoMsg);
00216 }
00217 void CommonDataSubscriber::rgbd4OdomScan3dInfoCallback(
00218                 const nav_msgs::OdometryConstPtr & odomMsg,
00219                 const rtabmap_ros::RGBDImageConstPtr& image1Msg,
00220                 const rtabmap_ros::RGBDImageConstPtr& image2Msg,
00221                 const rtabmap_ros::RGBDImageConstPtr& image3Msg,
00222                 const rtabmap_ros::RGBDImageConstPtr& image4Msg,
00223                 const sensor_msgs::PointCloud2ConstPtr& scan3dMsg,
00224                 const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg)
00225 {
00226         IMAGE_CONVERSION();
00227 
00228         rtabmap_ros::UserDataConstPtr userDataMsg; // Null
00229         sensor_msgs::LaserScanConstPtr scanMsg; // Null
00230         commonDepthCallback(odomMsg, userDataMsg, imageMsgs, depthMsgs, cameraInfoMsgs, scanMsg, scan3dMsg, odomInfoMsg);
00231 }
00232 
00233 // 2 RGBD + User Data
00234 void CommonDataSubscriber::rgbd4DataCallback(
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 rtabmap_ros::RGBDImageConstPtr& image4Msg)
00240 {
00241         IMAGE_CONVERSION();
00242 
00243         nav_msgs::OdometryConstPtr odomMsg; // Null
00244         sensor_msgs::LaserScanConstPtr scanMsg; // Null
00245         sensor_msgs::PointCloud2ConstPtr scan3dMsg; // Null
00246         rtabmap_ros::OdomInfoConstPtr odomInfoMsg; // null
00247         commonDepthCallback(odomMsg, userDataMsg, imageMsgs, depthMsgs, cameraInfoMsgs, scanMsg, scan3dMsg, odomInfoMsg);
00248 }
00249 void CommonDataSubscriber::rgbd4DataScan2dCallback(
00250                 const rtabmap_ros::UserDataConstPtr& userDataMsg,
00251                 const rtabmap_ros::RGBDImageConstPtr& image1Msg,
00252                 const rtabmap_ros::RGBDImageConstPtr& image2Msg,
00253                 const rtabmap_ros::RGBDImageConstPtr& image3Msg,
00254                 const rtabmap_ros::RGBDImageConstPtr& image4Msg,
00255                 const sensor_msgs::LaserScanConstPtr& scanMsg)
00256 {
00257         IMAGE_CONVERSION();
00258 
00259         nav_msgs::OdometryConstPtr odomMsg; // Null
00260         sensor_msgs::PointCloud2ConstPtr scan3dMsg; // Null
00261         rtabmap_ros::OdomInfoConstPtr odomInfoMsg; // null
00262         commonDepthCallback(odomMsg, userDataMsg, imageMsgs, depthMsgs, cameraInfoMsgs, scanMsg, scan3dMsg, odomInfoMsg);
00263 }
00264 void CommonDataSubscriber::rgbd4DataScan3dCallback(
00265                 const rtabmap_ros::UserDataConstPtr& userDataMsg,
00266                 const rtabmap_ros::RGBDImageConstPtr& image1Msg,
00267                 const rtabmap_ros::RGBDImageConstPtr& image2Msg,
00268                 const rtabmap_ros::RGBDImageConstPtr& image3Msg,
00269                 const rtabmap_ros::RGBDImageConstPtr& image4Msg,
00270                 const sensor_msgs::PointCloud2ConstPtr& scan3dMsg)
00271 {
00272         IMAGE_CONVERSION();
00273 
00274         nav_msgs::OdometryConstPtr odomMsg; // Null
00275         sensor_msgs::LaserScanConstPtr scanMsg; // Null
00276         rtabmap_ros::OdomInfoConstPtr odomInfoMsg; // null
00277         commonDepthCallback(odomMsg, userDataMsg, imageMsgs, depthMsgs, cameraInfoMsgs, scanMsg, scan3dMsg, odomInfoMsg);
00278 }
00279 void CommonDataSubscriber::rgbd4DataInfoCallback(
00280                 const rtabmap_ros::UserDataConstPtr& userDataMsg,
00281                 const rtabmap_ros::RGBDImageConstPtr& image1Msg,
00282                 const rtabmap_ros::RGBDImageConstPtr& image2Msg,
00283                 const rtabmap_ros::RGBDImageConstPtr& image3Msg,
00284                 const rtabmap_ros::RGBDImageConstPtr& image4Msg,
00285                 const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg)
00286 {
00287         IMAGE_CONVERSION();
00288 
00289         nav_msgs::OdometryConstPtr odomMsg; // Null
00290         sensor_msgs::LaserScanConstPtr scanMsg; // Null
00291         sensor_msgs::PointCloud2ConstPtr scan3dMsg; // Null
00292         commonDepthCallback(odomMsg, userDataMsg, imageMsgs, depthMsgs, cameraInfoMsgs, scanMsg, scan3dMsg, odomInfoMsg);
00293 }
00294 void CommonDataSubscriber::rgbd4DataScan2dInfoCallback(
00295                 const rtabmap_ros::UserDataConstPtr& userDataMsg,
00296                 const rtabmap_ros::RGBDImageConstPtr& image1Msg,
00297                 const rtabmap_ros::RGBDImageConstPtr& image2Msg,
00298                 const rtabmap_ros::RGBDImageConstPtr& image3Msg,
00299                 const rtabmap_ros::RGBDImageConstPtr& image4Msg,
00300                 const sensor_msgs::LaserScanConstPtr& scanMsg,
00301                 const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg)
00302 {
00303         IMAGE_CONVERSION();
00304 
00305         nav_msgs::OdometryConstPtr odomMsg; // Null
00306         sensor_msgs::PointCloud2ConstPtr scan3dMsg; // Null
00307         commonDepthCallback(odomMsg, userDataMsg, imageMsgs, depthMsgs, cameraInfoMsgs, scanMsg, scan3dMsg, odomInfoMsg);
00308 }
00309 void CommonDataSubscriber::rgbd4DataScan3dInfoCallback(
00310                 const rtabmap_ros::UserDataConstPtr& userDataMsg,
00311                 const rtabmap_ros::RGBDImageConstPtr& image1Msg,
00312                 const rtabmap_ros::RGBDImageConstPtr& image2Msg,
00313                 const rtabmap_ros::RGBDImageConstPtr& image3Msg,
00314                 const rtabmap_ros::RGBDImageConstPtr& image4Msg,
00315                 const sensor_msgs::PointCloud2ConstPtr& scan3dMsg,
00316                 const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg)
00317 {
00318         IMAGE_CONVERSION();
00319 
00320         nav_msgs::OdometryConstPtr odomMsg; // Null
00321         sensor_msgs::LaserScanConstPtr scanMsg; // Null
00322         commonDepthCallback(odomMsg, userDataMsg, imageMsgs, depthMsgs, cameraInfoMsgs, scanMsg, scan3dMsg, odomInfoMsg);
00323 }
00324 
00325 // 2 RGBD + Odom + User Data
00326 void CommonDataSubscriber::rgbd4OdomDataCallback(
00327                 const nav_msgs::OdometryConstPtr& odomMsg,
00328                 const rtabmap_ros::UserDataConstPtr& userDataMsg,
00329                 const rtabmap_ros::RGBDImageConstPtr& image1Msg,
00330                 const rtabmap_ros::RGBDImageConstPtr& image2Msg,
00331                 const rtabmap_ros::RGBDImageConstPtr& image3Msg,
00332                 const rtabmap_ros::RGBDImageConstPtr& image4Msg)
00333 {
00334         IMAGE_CONVERSION();
00335 
00336         sensor_msgs::LaserScanConstPtr scanMsg; // Null
00337         sensor_msgs::PointCloud2ConstPtr scan3dMsg; // Null
00338         rtabmap_ros::OdomInfoConstPtr odomInfoMsg; // null
00339         commonDepthCallback(odomMsg, userDataMsg, imageMsgs, depthMsgs, cameraInfoMsgs, scanMsg, scan3dMsg, odomInfoMsg);
00340 }
00341 void CommonDataSubscriber::rgbd4OdomDataScan2dCallback(
00342                 const nav_msgs::OdometryConstPtr& odomMsg,
00343                 const rtabmap_ros::UserDataConstPtr& userDataMsg,
00344                 const rtabmap_ros::RGBDImageConstPtr& image1Msg,
00345                 const rtabmap_ros::RGBDImageConstPtr& image2Msg,
00346                 const rtabmap_ros::RGBDImageConstPtr& image3Msg,
00347                 const rtabmap_ros::RGBDImageConstPtr& image4Msg,
00348                 const sensor_msgs::LaserScanConstPtr& scanMsg)
00349 {
00350         IMAGE_CONVERSION();
00351 
00352         sensor_msgs::PointCloud2ConstPtr scan3dMsg; // Null
00353         rtabmap_ros::OdomInfoConstPtr odomInfoMsg; // null
00354         commonDepthCallback(odomMsg, userDataMsg, imageMsgs, depthMsgs, cameraInfoMsgs, scanMsg, scan3dMsg, odomInfoMsg);
00355 }
00356 void CommonDataSubscriber::rgbd4OdomDataScan3dCallback(
00357                 const nav_msgs::OdometryConstPtr& odomMsg,
00358                 const rtabmap_ros::UserDataConstPtr& userDataMsg,
00359                 const rtabmap_ros::RGBDImageConstPtr& image1Msg,
00360                 const rtabmap_ros::RGBDImageConstPtr& image2Msg,
00361                 const rtabmap_ros::RGBDImageConstPtr& image3Msg,
00362                 const rtabmap_ros::RGBDImageConstPtr& image4Msg,
00363                 const sensor_msgs::PointCloud2ConstPtr& scan3dMsg)
00364 {
00365         IMAGE_CONVERSION();
00366 
00367         sensor_msgs::LaserScanConstPtr scanMsg; // Null
00368         rtabmap_ros::OdomInfoConstPtr odomInfoMsg; // null
00369         commonDepthCallback(odomMsg, userDataMsg, imageMsgs, depthMsgs, cameraInfoMsgs, scanMsg, scan3dMsg, odomInfoMsg);
00370 }
00371 void CommonDataSubscriber::rgbd4OdomDataInfoCallback(
00372                 const nav_msgs::OdometryConstPtr& odomMsg,
00373                 const rtabmap_ros::UserDataConstPtr& userDataMsg,
00374                 const rtabmap_ros::RGBDImageConstPtr& image1Msg,
00375                 const rtabmap_ros::RGBDImageConstPtr& image2Msg,
00376                 const rtabmap_ros::RGBDImageConstPtr& image3Msg,
00377                 const rtabmap_ros::RGBDImageConstPtr& image4Msg,
00378                 const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg)
00379 {
00380         IMAGE_CONVERSION();
00381 
00382         sensor_msgs::LaserScanConstPtr scanMsg; // Null
00383         sensor_msgs::PointCloud2ConstPtr scan3dMsg; // Null
00384         commonDepthCallback(odomMsg, userDataMsg, imageMsgs, depthMsgs, cameraInfoMsgs, scanMsg, scan3dMsg, odomInfoMsg);
00385 }
00386 void CommonDataSubscriber::rgbd4OdomDataScan2dInfoCallback(
00387                 const nav_msgs::OdometryConstPtr& odomMsg,
00388                 const rtabmap_ros::UserDataConstPtr& userDataMsg,
00389                 const rtabmap_ros::RGBDImageConstPtr& image1Msg,
00390                 const rtabmap_ros::RGBDImageConstPtr& image2Msg,
00391                 const rtabmap_ros::RGBDImageConstPtr& image3Msg,
00392                 const rtabmap_ros::RGBDImageConstPtr& image4Msg,
00393                 const sensor_msgs::LaserScanConstPtr& scanMsg,
00394                 const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg)
00395 {
00396         IMAGE_CONVERSION();
00397 
00398         sensor_msgs::PointCloud2ConstPtr scan3dMsg; // Null
00399         commonDepthCallback(odomMsg, userDataMsg, imageMsgs, depthMsgs, cameraInfoMsgs, scanMsg, scan3dMsg, odomInfoMsg);
00400 }
00401 void CommonDataSubscriber::rgbd4OdomDataScan3dInfoCallback(
00402                 const nav_msgs::OdometryConstPtr& odomMsg,
00403                 const rtabmap_ros::UserDataConstPtr& userDataMsg,
00404                 const rtabmap_ros::RGBDImageConstPtr& image1Msg,
00405                 const rtabmap_ros::RGBDImageConstPtr& image2Msg,
00406                 const rtabmap_ros::RGBDImageConstPtr& image3Msg,
00407                 const rtabmap_ros::RGBDImageConstPtr& image4Msg,
00408                 const sensor_msgs::PointCloud2ConstPtr& scan3dMsg,
00409                 const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg)
00410 {
00411         IMAGE_CONVERSION();
00412 
00413         sensor_msgs::LaserScanConstPtr scanMsg; // Null
00414         commonDepthCallback(odomMsg, userDataMsg, imageMsgs, depthMsgs, cameraInfoMsgs, scanMsg, scan3dMsg, odomInfoMsg);
00415 }
00416 
00417 void CommonDataSubscriber::setupRGBD4Callbacks(
00418                 ros::NodeHandle & nh,
00419                 ros::NodeHandle & pnh,
00420                 bool subscribeOdom,
00421                 bool subscribeUserData,
00422                 bool subscribeScan2d,
00423                 bool subscribeScan3d,
00424                 bool subscribeOdomInfo,
00425                 int queueSize,
00426                 bool approxSync)
00427 {
00428         ROS_INFO("Setup rgbd4 callback");
00429 
00430         rgbdSubs_.resize(4);
00431         for(int i=0; i<4; ++i)
00432         {
00433                 rgbdSubs_[i] = new message_filters::Subscriber<rtabmap_ros::RGBDImage>;
00434                 rgbdSubs_[i]->subscribe(nh, uFormat("rgbd_image%d", i), 1);
00435         }
00436         if(subscribeOdom && subscribeUserData)
00437         {
00438                 odomSub_.subscribe(nh, "odom", 1);
00439                 userDataSub_.subscribe(nh, "user_data", 1);
00440                 if(subscribeScan2d)
00441                 {
00442                         subscribedToScan2d_ = true;
00443                         scanSub_.subscribe(nh, "scan", 1);
00444                         if(subscribeOdomInfo)
00445                         {
00446                                 subscribedToOdomInfo_ = true;
00447                                 odomInfoSub_.subscribe(nh, "odom_info", 1);
00448                                 SYNC_DECL8(rgbd4OdomDataScan2dInfo, approxSync, queueSize, odomSub_, userDataSub_, (*rgbdSubs_[0]), (*rgbdSubs_[1]), (*rgbdSubs_[2]), (*rgbdSubs_[3]), scanSub_, odomInfoSub_);
00449                         }
00450                         else
00451                         {
00452                                 SYNC_DECL7(rgbd4OdomDataScan2d, approxSync, queueSize, odomSub_, userDataSub_, (*rgbdSubs_[0]), (*rgbdSubs_[1]), (*rgbdSubs_[2]), (*rgbdSubs_[3]), scanSub_);
00453                         }
00454                 }
00455                 else if(subscribeScan3d)
00456                 {
00457                         subscribedToScan3d_ = true;
00458                         scan3dSub_.subscribe(nh, "scan_cloud", 1);
00459                         if(subscribeOdomInfo)
00460                         {
00461                                 subscribedToOdomInfo_ = true;
00462                                 odomInfoSub_.subscribe(nh, "odom_info", 1);
00463                                 SYNC_DECL8(rgbd4OdomDataScan3dInfo, approxSync, queueSize, odomSub_, userDataSub_, (*rgbdSubs_[0]), (*rgbdSubs_[1]), (*rgbdSubs_[2]), (*rgbdSubs_[3]), scan3dSub_, odomInfoSub_);
00464                         }
00465                         else
00466                         {
00467                                 SYNC_DECL7(rgbd4OdomDataScan3d, approxSync, queueSize, odomSub_, userDataSub_, (*rgbdSubs_[0]), (*rgbdSubs_[1]), (*rgbdSubs_[2]), (*rgbdSubs_[3]), scan3dSub_);
00468                         }
00469                 }
00470                 else if(subscribeOdomInfo)
00471                 {
00472                         subscribedToOdomInfo_ = true;
00473                         odomInfoSub_.subscribe(nh, "odom_info", 1);
00474                         SYNC_DECL7(rgbd4OdomDataInfo, approxSync, queueSize, odomSub_, userDataSub_, (*rgbdSubs_[0]), (*rgbdSubs_[1]), (*rgbdSubs_[2]), (*rgbdSubs_[3]), odomInfoSub_);
00475                 }
00476                 else
00477                 {
00478                         SYNC_DECL6(rgbd4OdomData, approxSync, queueSize, odomSub_, userDataSub_, (*rgbdSubs_[0]), (*rgbdSubs_[1]), (*rgbdSubs_[2]), (*rgbdSubs_[3]));
00479                 }
00480         }
00481         else if(subscribeOdom)
00482         {
00483                 odomSub_.subscribe(nh, "odom", 1);
00484                 if(subscribeScan2d)
00485                 {
00486                         subscribedToScan2d_ = true;
00487                         scanSub_.subscribe(nh, "scan", 1);
00488                         if(subscribeOdomInfo)
00489                         {
00490                                 subscribedToOdomInfo_ = true;
00491                                 odomInfoSub_.subscribe(nh, "odom_info", 1);
00492                                 SYNC_DECL7(rgbd4OdomScan2dInfo, approxSync, queueSize, odomSub_, (*rgbdSubs_[0]), (*rgbdSubs_[1]), (*rgbdSubs_[2]), (*rgbdSubs_[3]), scanSub_, odomInfoSub_);
00493                         }
00494                         else
00495                         {
00496                                 SYNC_DECL6(rgbd4OdomScan2d, approxSync, queueSize, odomSub_, (*rgbdSubs_[0]), (*rgbdSubs_[1]), (*rgbdSubs_[2]), (*rgbdSubs_[3]), scanSub_);
00497                         }
00498                 }
00499                 else if(subscribeScan3d)
00500                 {
00501                         subscribedToScan3d_ = true;
00502                         scan3dSub_.subscribe(nh, "scan_cloud", 1);
00503                         if(subscribeOdomInfo)
00504                         {
00505                                 subscribedToOdomInfo_ = true;
00506                                 odomInfoSub_.subscribe(nh, "odom_info", 1);
00507                                 SYNC_DECL7(rgbd4OdomScan3dInfo, approxSync, queueSize, odomSub_, (*rgbdSubs_[0]), (*rgbdSubs_[1]), (*rgbdSubs_[2]), (*rgbdSubs_[3]), scan3dSub_, odomInfoSub_);
00508                         }
00509                         else
00510                         {
00511                                 SYNC_DECL6(rgbd4OdomScan3d, approxSync, queueSize, odomSub_, (*rgbdSubs_[0]), (*rgbdSubs_[1]), (*rgbdSubs_[2]), (*rgbdSubs_[3]), scan3dSub_);
00512                         }
00513                 }
00514                 else if(subscribeOdomInfo)
00515                 {
00516                         subscribedToOdomInfo_ = true;
00517                         odomInfoSub_.subscribe(nh, "odom_info", 1);
00518                         SYNC_DECL6(rgbd4OdomInfo, approxSync, queueSize, odomSub_, (*rgbdSubs_[0]), (*rgbdSubs_[1]), (*rgbdSubs_[2]), (*rgbdSubs_[3]), odomInfoSub_);
00519                 }
00520                 else
00521                 {
00522                         SYNC_DECL5(rgbd4Odom, approxSync, queueSize, odomSub_, (*rgbdSubs_[0]), (*rgbdSubs_[1]), (*rgbdSubs_[2]), (*rgbdSubs_[3]));
00523                 }
00524         }
00525         else if(subscribeUserData)
00526         {
00527                 userDataSub_.subscribe(nh, "user_data", 1);
00528                 if(subscribeScan2d)
00529                 {
00530                         subscribedToScan2d_ = true;
00531                         scanSub_.subscribe(nh, "scan", 1);
00532                         if(subscribeOdomInfo)
00533                         {
00534                                 subscribedToOdomInfo_ = true;
00535                                 odomInfoSub_.subscribe(nh, "odom_info", 1);
00536                                 SYNC_DECL7(rgbd4DataScan2dInfo, approxSync, queueSize, userDataSub_, (*rgbdSubs_[0]), (*rgbdSubs_[1]), (*rgbdSubs_[2]), (*rgbdSubs_[3]), scanSub_, odomInfoSub_);
00537                         }
00538                         else
00539                         {
00540                                 SYNC_DECL6(rgbd4DataScan2d, approxSync, queueSize, userDataSub_, (*rgbdSubs_[0]), (*rgbdSubs_[1]), (*rgbdSubs_[2]), (*rgbdSubs_[3]), scanSub_);
00541                         }
00542                 }
00543                 else if(subscribeScan3d)
00544                 {
00545                         subscribedToScan3d_ = true;
00546                         scan3dSub_.subscribe(nh, "scan_cloud", 1);
00547                         if(subscribeOdomInfo)
00548                         {
00549                                 subscribedToOdomInfo_ = true;
00550                                 odomInfoSub_.subscribe(nh, "odom_info", 1);
00551                                 SYNC_DECL7(rgbd4DataScan3dInfo, approxSync, queueSize, userDataSub_, (*rgbdSubs_[0]), (*rgbdSubs_[1]), (*rgbdSubs_[2]), (*rgbdSubs_[3]), scan3dSub_, odomInfoSub_);
00552                         }
00553                         else
00554                         {
00555                                 SYNC_DECL6(rgbd4DataScan3d, approxSync, queueSize, userDataSub_, (*rgbdSubs_[0]), (*rgbdSubs_[1]), (*rgbdSubs_[2]), (*rgbdSubs_[3]), scan3dSub_);
00556                         }
00557                 }
00558                 else if(subscribeOdomInfo)
00559                 {
00560                         subscribedToOdomInfo_ = true;
00561                         odomInfoSub_.subscribe(nh, "odom_info", 1);
00562                         SYNC_DECL6(rgbd4DataInfo, approxSync, queueSize, userDataSub_, (*rgbdSubs_[0]), (*rgbdSubs_[1]), (*rgbdSubs_[2]), (*rgbdSubs_[3]), odomInfoSub_);
00563                 }
00564                 else
00565                 {
00566                         SYNC_DECL5(rgbd4Data, approxSync, queueSize, userDataSub_, (*rgbdSubs_[0]), (*rgbdSubs_[1]), (*rgbdSubs_[2]), (*rgbdSubs_[3]));
00567                 }
00568         }
00569         else
00570         {
00571                 if(subscribeScan2d)
00572                 {
00573                         subscribedToScan2d_ = true;
00574                         scanSub_.subscribe(nh, "scan", 1);
00575                         if(subscribeOdomInfo)
00576                         {
00577                                 subscribedToOdomInfo_ = true;
00578                                 odomInfoSub_.subscribe(nh, "odom_info", 1);
00579                                 SYNC_DECL6(rgbd4Scan2dInfo, approxSync, queueSize, (*rgbdSubs_[0]), (*rgbdSubs_[1]), (*rgbdSubs_[2]), (*rgbdSubs_[3]), scanSub_, odomInfoSub_);
00580                         }
00581                         else
00582                         {
00583                                 SYNC_DECL5(rgbd4Scan2d, approxSync, queueSize, (*rgbdSubs_[0]), (*rgbdSubs_[1]), (*rgbdSubs_[2]), (*rgbdSubs_[3]), scanSub_);
00584                         }
00585                 }
00586                 else if(subscribeScan3d)
00587                 {
00588                         subscribedToScan3d_ = true;
00589                         scan3dSub_.subscribe(nh, "scan_cloud", 1);
00590                         if(subscribeOdomInfo)
00591                         {
00592                                 subscribedToOdomInfo_ = true;
00593                                 odomInfoSub_.subscribe(nh, "odom_info", 1);
00594                                 SYNC_DECL6(rgbd4Scan3dInfo, approxSync, queueSize, (*rgbdSubs_[0]), (*rgbdSubs_[1]), (*rgbdSubs_[2]), (*rgbdSubs_[3]), scan3dSub_, odomInfoSub_);
00595                         }
00596                         else
00597                         {
00598                                 SYNC_DECL5(rgbd4Scan3d, approxSync, queueSize, (*rgbdSubs_[0]), (*rgbdSubs_[1]), (*rgbdSubs_[2]), (*rgbdSubs_[3]), scan3dSub_);
00599                         }
00600                 }
00601                 else if(subscribeOdomInfo)
00602                 {
00603                         subscribedToOdomInfo_ = true;
00604                         odomInfoSub_.subscribe(nh, "odom_info", 1);
00605                         SYNC_DECL5(rgbd4Info, approxSync, queueSize, (*rgbdSubs_[0]), (*rgbdSubs_[1]), (*rgbdSubs_[2]), (*rgbdSubs_[3]), odomInfoSub_);
00606                 }
00607                 else
00608                 {
00609                         SYNC_DECL4(rgbd4, approxSync, queueSize, (*rgbdSubs_[0]), (*rgbdSubs_[1]), (*rgbdSubs_[2]), (*rgbdSubs_[3]));
00610                 }
00611         }
00612 }
00613 
00614 } /* namespace rtabmap_ros */


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