00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028 #include <rtabmap_ros/CommonDataSubscriber.h>
00029
00030 namespace rtabmap_ros {
00031
00032
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;
00041 rtabmap_ros::UserDataConstPtr userDataMsg;
00042 sensor_msgs::LaserScanConstPtr scanMsg;
00043 sensor_msgs::PointCloud2ConstPtr scan3dMsg;
00044 rtabmap_ros::OdomInfoConstPtr odomInfoMsg;
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;
00056 rtabmap_ros::UserDataConstPtr userDataMsg;
00057 sensor_msgs::LaserScanConstPtr scan2dMsg;
00058 sensor_msgs::PointCloud2ConstPtr scan3dMsg;
00059 commonStereoCallback(odomMsg, userDataMsg, cv_bridge::toCvShare(leftImageMsg), cv_bridge::toCvShare(rightImageMsg), *leftCamInfoMsg, *rightCamInfoMsg, scan2dMsg, scan3dMsg, odomInfoMsg);
00060 }
00061
00062
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;
00072 sensor_msgs::LaserScanConstPtr scanMsg;
00073 sensor_msgs::PointCloud2ConstPtr scan3dMsg;
00074 rtabmap_ros::OdomInfoConstPtr odomInfoMsg;
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;
00087 sensor_msgs::LaserScanConstPtr scan2dMsg;
00088 sensor_msgs::PointCloud2ConstPtr scan3dMsg;
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 }