CommonDataSubscriberStereo.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 
00030 namespace rtabmap_ros {
00031 
00032 // Stereo
00033 void CommonDataSubscriber::stereoCallback(
00034                 const sensor_msgs::ImageConstPtr& leftImageMsg,
00035            const sensor_msgs::ImageConstPtr& rightImageMsg,
00036            const sensor_msgs::CameraInfoConstPtr& leftCamInfoMsg,
00037            const sensor_msgs::CameraInfoConstPtr& rightCamInfoMsg)
00038 {
00039         callbackCalled();
00040         nav_msgs::OdometryConstPtr odomMsg; // Null
00041         rtabmap_ros::UserDataConstPtr userDataMsg; // Null
00042         sensor_msgs::LaserScanConstPtr scanMsg; // null
00043         sensor_msgs::PointCloud2ConstPtr scan3dMsg; // null
00044         rtabmap_ros::OdomInfoConstPtr odomInfoMsg; // null
00045         commonStereoCallback(odomMsg, userDataMsg, cv_bridge::toCvShare(leftImageMsg), cv_bridge::toCvShare(rightImageMsg), *leftCamInfoMsg, *rightCamInfoMsg, scanMsg, scan3dMsg, odomInfoMsg);
00046 }
00047 void CommonDataSubscriber::stereoInfoCallback(
00048                 const sensor_msgs::ImageConstPtr& leftImageMsg,
00049            const sensor_msgs::ImageConstPtr& rightImageMsg,
00050            const sensor_msgs::CameraInfoConstPtr& leftCamInfoMsg,
00051            const sensor_msgs::CameraInfoConstPtr& rightCamInfoMsg,
00052            const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg)
00053 {
00054         callbackCalled();
00055         nav_msgs::OdometryConstPtr odomMsg; // Null
00056         rtabmap_ros::UserDataConstPtr userDataMsg; // Null
00057         sensor_msgs::LaserScanConstPtr scan2dMsg; // null
00058         sensor_msgs::PointCloud2ConstPtr scan3dMsg; // null
00059         commonStereoCallback(odomMsg, userDataMsg, cv_bridge::toCvShare(leftImageMsg), cv_bridge::toCvShare(rightImageMsg), *leftCamInfoMsg, *rightCamInfoMsg, scan2dMsg, scan3dMsg, odomInfoMsg);
00060 }
00061 
00062 // Stereo + Odom
00063 void CommonDataSubscriber::stereoOdomCallback(
00064                 const nav_msgs::OdometryConstPtr & odomMsg,
00065                 const sensor_msgs::ImageConstPtr& leftImageMsg,
00066                 const sensor_msgs::ImageConstPtr& rightImageMsg,
00067                 const sensor_msgs::CameraInfoConstPtr& leftCamInfoMsg,
00068                 const sensor_msgs::CameraInfoConstPtr& rightCamInfoMsg)
00069 {
00070         callbackCalled();
00071         rtabmap_ros::UserDataConstPtr userDataMsg; // Null
00072         sensor_msgs::LaserScanConstPtr scanMsg; // Null
00073         sensor_msgs::PointCloud2ConstPtr scan3dMsg; // null
00074         rtabmap_ros::OdomInfoConstPtr odomInfoMsg; // null
00075         commonStereoCallback(odomMsg, userDataMsg, cv_bridge::toCvShare(leftImageMsg), cv_bridge::toCvShare(rightImageMsg), *leftCamInfoMsg, *rightCamInfoMsg, scanMsg, scan3dMsg, odomInfoMsg);
00076 }
00077 void CommonDataSubscriber::stereoOdomInfoCallback(
00078                 const nav_msgs::OdometryConstPtr & odomMsg,
00079                 const sensor_msgs::ImageConstPtr& leftImageMsg,
00080                 const sensor_msgs::ImageConstPtr& rightImageMsg,
00081                 const sensor_msgs::CameraInfoConstPtr& leftCamInfoMsg,
00082                 const sensor_msgs::CameraInfoConstPtr& rightCamInfoMsg,
00083                 const rtabmap_ros::OdomInfoConstPtr & odomInfoMsg)
00084 {
00085         callbackCalled();
00086         rtabmap_ros::UserDataConstPtr userDataMsg; // Null
00087         sensor_msgs::LaserScanConstPtr scan2dMsg; // Null
00088         sensor_msgs::PointCloud2ConstPtr scan3dMsg; // Null
00089         commonStereoCallback(odomMsg, userDataMsg, cv_bridge::toCvShare(leftImageMsg), cv_bridge::toCvShare(rightImageMsg), *leftCamInfoMsg, *rightCamInfoMsg, scan2dMsg, scan3dMsg, odomInfoMsg);
00090 }
00091 
00092 void CommonDataSubscriber::setupStereoCallbacks(
00093                 ros::NodeHandle & nh,
00094                 ros::NodeHandle & pnh,
00095                 bool subscribeOdom,
00096                 bool subscribeOdomInfo,
00097                 int queueSize,
00098                 bool approxSync)
00099 {
00100         ROS_INFO("Setup stereo callback");
00101 
00102         ros::NodeHandle left_nh(nh, "left");
00103         ros::NodeHandle right_nh(nh, "right");
00104         ros::NodeHandle left_pnh(pnh, "left");
00105         ros::NodeHandle right_pnh(pnh, "right");
00106         image_transport::ImageTransport left_it(left_nh);
00107         image_transport::ImageTransport right_it(right_nh);
00108         image_transport::TransportHints hintsLeft("raw", ros::TransportHints(), left_pnh);
00109         image_transport::TransportHints hintsRight("raw", ros::TransportHints(), right_pnh);
00110 
00111         imageRectLeft_.subscribe(left_it, left_nh.resolveName("image_rect"), 1, hintsLeft);
00112         imageRectRight_.subscribe(right_it, right_nh.resolveName("image_rect"), 1, hintsRight);
00113         cameraInfoLeft_.subscribe(left_nh, "camera_info", 1);
00114         cameraInfoRight_.subscribe(right_nh, "camera_info", 1);
00115 
00116         if(subscribeOdom)
00117         {
00118                 odomSub_.subscribe(nh, "odom", 1);
00119 
00120                 if(subscribeOdomInfo)
00121                 {
00122                         subscribedToOdomInfo_ = true;
00123                         odomInfoSub_.subscribe(nh, "odom_info", 1);
00124                         SYNC_DECL6(stereoOdomInfo, approxSync, queueSize, odomSub_, imageRectLeft_, imageRectRight_, cameraInfoLeft_, cameraInfoRight_, odomInfoSub_);
00125                 }
00126                 else
00127                 {
00128                         SYNC_DECL5(stereoOdom, approxSync, queueSize, odomSub_, imageRectLeft_, imageRectRight_, cameraInfoLeft_, cameraInfoRight_);
00129                 }
00130         }
00131         else
00132         {
00133                 if(subscribeOdomInfo)
00134                 {
00135                         subscribedToOdomInfo_ = true;
00136                         odomInfoSub_.subscribe(nh, "odom_info", 1);
00137                         SYNC_DECL5(stereoInfo, approxSync, queueSize, imageRectLeft_, imageRectRight_, cameraInfoLeft_, cameraInfoRight_, odomInfoSub_);
00138                 }
00139                 else
00140                 {
00141                         SYNC_DECL4(stereo, approxSync, queueSize, imageRectLeft_, imageRectRight_, cameraInfoLeft_, cameraInfoRight_);
00142                 }
00143         }
00144 }
00145 
00146 } /* namespace rtabmap_ros */


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