CommonDataSubscriberStereo.cpp
Go to the documentation of this file.
1 /*
2 Copyright (c) 2010-2016, Mathieu Labbe - IntRoLab - Universite de Sherbrooke
3 All rights reserved.
4 
5 Redistribution and use in source and binary forms, with or without
6 modification, are permitted provided that the following conditions are met:
7  * Redistributions of source code must retain the above copyright
8  notice, this list of conditions and the following disclaimer.
9  * Redistributions in binary form must reproduce the above copyright
10  notice, this list of conditions and the following disclaimer in the
11  documentation and/or other materials provided with the distribution.
12  * Neither the name of the Universite de Sherbrooke nor the
13  names of its contributors may be used to endorse or promote products
14  derived from this software without specific prior written permission.
15 
16 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
17 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
18 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
19 DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY
20 DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
21 (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
22 LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
23 ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
24 (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
25 SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
26 */
27 
29 
30 namespace rtabmap_ros {
31 
32 // Stereo
33 void CommonDataSubscriber::stereoCallback(
34  const sensor_msgs::ImageConstPtr& leftImageMsg,
35  const sensor_msgs::ImageConstPtr& rightImageMsg,
36  const sensor_msgs::CameraInfoConstPtr& leftCamInfoMsg,
37  const sensor_msgs::CameraInfoConstPtr& rightCamInfoMsg)
38 {
40  nav_msgs::OdometryConstPtr odomMsg; // Null
41  rtabmap_ros::UserDataConstPtr userDataMsg; // Null
42  sensor_msgs::LaserScan scanMsg; // null
43  sensor_msgs::PointCloud2 scan3dMsg; // null
44  rtabmap_ros::OdomInfoConstPtr odomInfoMsg; // null
45  commonStereoCallback(odomMsg, userDataMsg, cv_bridge::toCvShare(leftImageMsg), cv_bridge::toCvShare(rightImageMsg), *leftCamInfoMsg, *rightCamInfoMsg, scanMsg, scan3dMsg, odomInfoMsg);
46 }
47 void CommonDataSubscriber::stereoInfoCallback(
48  const sensor_msgs::ImageConstPtr& leftImageMsg,
49  const sensor_msgs::ImageConstPtr& rightImageMsg,
50  const sensor_msgs::CameraInfoConstPtr& leftCamInfoMsg,
51  const sensor_msgs::CameraInfoConstPtr& rightCamInfoMsg,
52  const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg)
53 {
55  nav_msgs::OdometryConstPtr odomMsg; // Null
56  rtabmap_ros::UserDataConstPtr userDataMsg; // Null
57  sensor_msgs::LaserScan scan2dMsg; // null
58  sensor_msgs::PointCloud2 scan3dMsg; // null
59  commonStereoCallback(odomMsg, userDataMsg, cv_bridge::toCvShare(leftImageMsg), cv_bridge::toCvShare(rightImageMsg), *leftCamInfoMsg, *rightCamInfoMsg, scan2dMsg, scan3dMsg, odomInfoMsg);
60 }
61 
62 // Stereo + Odom
63 void CommonDataSubscriber::stereoOdomCallback(
64  const nav_msgs::OdometryConstPtr & odomMsg,
65  const sensor_msgs::ImageConstPtr& leftImageMsg,
66  const sensor_msgs::ImageConstPtr& rightImageMsg,
67  const sensor_msgs::CameraInfoConstPtr& leftCamInfoMsg,
68  const sensor_msgs::CameraInfoConstPtr& rightCamInfoMsg)
69 {
71  rtabmap_ros::UserDataConstPtr userDataMsg; // Null
72  sensor_msgs::LaserScan scanMsg; // Null
73  sensor_msgs::PointCloud2 scan3dMsg; // null
74  rtabmap_ros::OdomInfoConstPtr odomInfoMsg; // null
75  commonStereoCallback(odomMsg, userDataMsg, cv_bridge::toCvShare(leftImageMsg), cv_bridge::toCvShare(rightImageMsg), *leftCamInfoMsg, *rightCamInfoMsg, scanMsg, scan3dMsg, odomInfoMsg);
76 }
77 void CommonDataSubscriber::stereoOdomInfoCallback(
78  const nav_msgs::OdometryConstPtr & odomMsg,
79  const sensor_msgs::ImageConstPtr& leftImageMsg,
80  const sensor_msgs::ImageConstPtr& rightImageMsg,
81  const sensor_msgs::CameraInfoConstPtr& leftCamInfoMsg,
82  const sensor_msgs::CameraInfoConstPtr& rightCamInfoMsg,
83  const rtabmap_ros::OdomInfoConstPtr & odomInfoMsg)
84 {
86  rtabmap_ros::UserDataConstPtr userDataMsg; // Null
87  sensor_msgs::LaserScan scan2dMsg; // Null
88  sensor_msgs::PointCloud2 scan3dMsg; // Null
89  commonStereoCallback(odomMsg, userDataMsg, cv_bridge::toCvShare(leftImageMsg), cv_bridge::toCvShare(rightImageMsg), *leftCamInfoMsg, *rightCamInfoMsg, scan2dMsg, scan3dMsg, odomInfoMsg);
90 }
91 
93  ros::NodeHandle & nh,
94  ros::NodeHandle & pnh,
95  bool subscribeOdom,
96  bool subscribeOdomInfo,
97  int queueSize,
98  bool approxSync)
99 {
100  ROS_INFO("Setup stereo callback");
101 
102  ros::NodeHandle left_nh(nh, "left");
103  ros::NodeHandle right_nh(nh, "right");
104  ros::NodeHandle left_pnh(pnh, "left");
105  ros::NodeHandle right_pnh(pnh, "right");
106  image_transport::ImageTransport left_it(left_nh);
107  image_transport::ImageTransport right_it(right_nh);
108  image_transport::TransportHints hintsLeft("raw", ros::TransportHints(), left_pnh);
109  image_transport::TransportHints hintsRight("raw", ros::TransportHints(), right_pnh);
110 
111  imageRectLeft_.subscribe(left_it, left_nh.resolveName("image_rect"), queueSize, hintsLeft);
112  imageRectRight_.subscribe(right_it, right_nh.resolveName("image_rect"), queueSize, hintsRight);
113  cameraInfoLeft_.subscribe(left_nh, "camera_info", queueSize);
114  cameraInfoRight_.subscribe(right_nh, "camera_info", queueSize);
115 
116  if(subscribeOdom)
117  {
118  odomSub_.subscribe(nh, "odom", queueSize);
119 
120  if(subscribeOdomInfo)
121  {
122  subscribedToOdomInfo_ = true;
123  odomInfoSub_.subscribe(nh, "odom_info", queueSize);
125  }
126  else
127  {
128  SYNC_DECL5(stereoOdom, approxSync, queueSize, odomSub_, imageRectLeft_, imageRectRight_, cameraInfoLeft_, cameraInfoRight_);
129  }
130  }
131  else
132  {
133  if(subscribeOdomInfo)
134  {
135  subscribedToOdomInfo_ = true;
136  odomInfoSub_.subscribe(nh, "odom_info", queueSize);
138  }
139  else
140  {
141  SYNC_DECL4(stereo, approxSync, queueSize, imageRectLeft_, imageRectRight_, cameraInfoLeft_, cameraInfoRight_);
142  }
143  }
144 }
145 
146 } /* namespace rtabmap_ros */
CvImageConstPtr toCvShare(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
#define SYNC_DECL5(PREFIX, APPROX, QUEUE_SIZE, SUB0, SUB1, SUB2, SUB3, SUB4)
std::string resolveName(const std::string &name, bool remap=true) const
message_filters::Subscriber< sensor_msgs::CameraInfo > cameraInfoLeft_
#define SYNC_DECL6(PREFIX, APPROX, QUEUE_SIZE, SUB0, SUB1, SUB2, SUB3, SUB4, SUB5)
message_filters::Subscriber< rtabmap_ros::OdomInfo > odomInfoSub_
#define ROS_INFO(...)
virtual void commonStereoCallback(const nav_msgs::OdometryConstPtr &odomMsg, const rtabmap_ros::UserDataConstPtr &userDataMsg, const cv_bridge::CvImageConstPtr &leftImageMsg, const cv_bridge::CvImageConstPtr &rightImageMsg, const sensor_msgs::CameraInfo &leftCamInfoMsg, const sensor_msgs::CameraInfo &rightCamInfoMsg, const sensor_msgs::LaserScan &scanMsg, const sensor_msgs::PointCloud2 &scan3dMsg, const rtabmap_ros::OdomInfoConstPtr &odomInfoMsg, const std::vector< rtabmap_ros::GlobalDescriptor > &globalDescriptorMsgs=std::vector< rtabmap_ros::GlobalDescriptor >(), const std::vector< rtabmap_ros::KeyPoint > &localKeyPoints=std::vector< rtabmap_ros::KeyPoint >(), const std::vector< rtabmap_ros::Point3f > &localPoints3d=std::vector< rtabmap_ros::Point3f >(), const cv::Mat &localDescriptors=cv::Mat())=0
#define SYNC_DECL4(PREFIX, APPROX, QUEUE_SIZE, SUB0, SUB1, SUB2, SUB3)
message_filters::Subscriber< nav_msgs::Odometry > odomSub_
void subscribe(ImageTransport &it, const std::string &base_topic, uint32_t queue_size, const TransportHints &transport_hints=TransportHints())
void subscribe(ros::NodeHandle &nh, const std::string &topic, uint32_t queue_size, const ros::TransportHints &transport_hints=ros::TransportHints(), ros::CallbackQueueInterface *callback_queue=0)
image_transport::SubscriberFilter imageRectLeft_
image_transport::SubscriberFilter imageRectRight_
void setupStereoCallbacks(ros::NodeHandle &nh, ros::NodeHandle &pnh, bool subscribeOdom, bool subscribeOdomInfo, int queueSize, bool approxSync)
message_filters::Subscriber< sensor_msgs::CameraInfo > cameraInfoRight_


rtabmap_ros
Author(s): Mathieu Labbe
autogenerated on Mon Dec 14 2020 03:42:18