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_sync {
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 {
39  nav_msgs::OdometryConstPtr odomMsg; // Null
40  rtabmap_msgs::UserDataConstPtr userDataMsg; // Null
41  sensor_msgs::LaserScan scanMsg; // null
42  sensor_msgs::PointCloud2 scan3dMsg; // null
43  rtabmap_msgs::OdomInfoConstPtr odomInfoMsg; // null
44  commonSingleCameraCallback(odomMsg, userDataMsg, cv_bridge::toCvShare(leftImageMsg), cv_bridge::toCvShare(rightImageMsg), *leftCamInfoMsg, *rightCamInfoMsg, scanMsg, scan3dMsg, odomInfoMsg);
45 }
46 void CommonDataSubscriber::stereoInfoCallback(
47  const sensor_msgs::ImageConstPtr& leftImageMsg,
48  const sensor_msgs::ImageConstPtr& rightImageMsg,
49  const sensor_msgs::CameraInfoConstPtr& leftCamInfoMsg,
50  const sensor_msgs::CameraInfoConstPtr& rightCamInfoMsg,
51  const rtabmap_msgs::OdomInfoConstPtr& odomInfoMsg)
52 {
53  nav_msgs::OdometryConstPtr odomMsg; // Null
54  rtabmap_msgs::UserDataConstPtr userDataMsg; // Null
55  sensor_msgs::LaserScan scan2dMsg; // null
56  sensor_msgs::PointCloud2 scan3dMsg; // null
57  commonSingleCameraCallback(odomMsg, userDataMsg, cv_bridge::toCvShare(leftImageMsg), cv_bridge::toCvShare(rightImageMsg), *leftCamInfoMsg, *rightCamInfoMsg, scan2dMsg, scan3dMsg, odomInfoMsg);
58 }
59 
60 // Stereo + Odom
61 void CommonDataSubscriber::stereoOdomCallback(
62  const nav_msgs::OdometryConstPtr & odomMsg,
63  const sensor_msgs::ImageConstPtr& leftImageMsg,
64  const sensor_msgs::ImageConstPtr& rightImageMsg,
65  const sensor_msgs::CameraInfoConstPtr& leftCamInfoMsg,
66  const sensor_msgs::CameraInfoConstPtr& rightCamInfoMsg)
67 {
68  rtabmap_msgs::UserDataConstPtr userDataMsg; // Null
69  sensor_msgs::LaserScan scanMsg; // Null
70  sensor_msgs::PointCloud2 scan3dMsg; // null
71  rtabmap_msgs::OdomInfoConstPtr odomInfoMsg; // null
72  commonSingleCameraCallback(odomMsg, userDataMsg, cv_bridge::toCvShare(leftImageMsg), cv_bridge::toCvShare(rightImageMsg), *leftCamInfoMsg, *rightCamInfoMsg, scanMsg, scan3dMsg, odomInfoMsg);
73 }
74 void CommonDataSubscriber::stereoOdomInfoCallback(
75  const nav_msgs::OdometryConstPtr & odomMsg,
76  const sensor_msgs::ImageConstPtr& leftImageMsg,
77  const sensor_msgs::ImageConstPtr& rightImageMsg,
78  const sensor_msgs::CameraInfoConstPtr& leftCamInfoMsg,
79  const sensor_msgs::CameraInfoConstPtr& rightCamInfoMsg,
80  const rtabmap_msgs::OdomInfoConstPtr & odomInfoMsg)
81 {
82  rtabmap_msgs::UserDataConstPtr userDataMsg; // Null
83  sensor_msgs::LaserScan scan2dMsg; // Null
84  sensor_msgs::PointCloud2 scan3dMsg; // Null
85  commonSingleCameraCallback(odomMsg, userDataMsg, cv_bridge::toCvShare(leftImageMsg), cv_bridge::toCvShare(rightImageMsg), *leftCamInfoMsg, *rightCamInfoMsg, scan2dMsg, scan3dMsg, odomInfoMsg);
86 }
87 
89  ros::NodeHandle & nh,
90  ros::NodeHandle & pnh,
91  bool subscribeOdom,
92  bool subscribeOdomInfo)
93 {
94  ROS_INFO("Setup stereo callback");
95 
96  ros::NodeHandle left_nh(nh, "left");
97  ros::NodeHandle right_nh(nh, "right");
98  ros::NodeHandle left_pnh(pnh, "left");
99  ros::NodeHandle right_pnh(pnh, "right");
100  image_transport::ImageTransport left_it(left_nh);
101  image_transport::ImageTransport right_it(right_nh);
102  image_transport::TransportHints hintsLeft("raw", ros::TransportHints(), left_pnh);
103  image_transport::TransportHints hintsRight("raw", ros::TransportHints(), right_pnh);
104 
105  imageRectLeft_.subscribe(left_it, left_nh.resolveName("image_rect"), syncQueueSize_, hintsLeft);
106  imageRectRight_.subscribe(right_it, right_nh.resolveName("image_rect"), syncQueueSize_, hintsRight);
107  cameraInfoLeft_.subscribe(left_nh, "camera_info", topicQueueSize_);
108  cameraInfoRight_.subscribe(right_nh, "camera_info", topicQueueSize_);
109 
110  if(subscribeOdom)
111  {
112  odomSub_.subscribe(nh, "odom", topicQueueSize_);
113 
114  if(subscribeOdomInfo)
115  {
116  subscribedToOdomInfo_ = true;
117  odomInfoSub_.subscribe(nh, "odom_info", topicQueueSize_);
119  }
120  else
121  {
123  }
124  }
125  else
126  {
127  if(subscribeOdomInfo)
128  {
129  subscribedToOdomInfo_ = true;
130  odomInfoSub_.subscribe(nh, "odom_info", topicQueueSize_);
132  }
133  else
134  {
136  }
137  }
138 }
139 
140 } /* namespace rtabmap_sync */
SYNC_DECL6
#define SYNC_DECL6(CLASS, PREFIX, APPROX, QUEUE_SIZE, SUB0, SUB1, SUB2, SUB3, SUB4, SUB5)
Definition: CommonDataSubscriberDefines.h:190
rtabmap_sync::CommonDataSubscriber::imageRectLeft_
image_transport::SubscriberFilter imageRectLeft_
Definition: CommonDataSubscriber.h:278
image_transport::ImageTransport
rtabmap_sync
Definition: CommonDataSubscriber.h:59
rtabmap_sync::CommonDataSubscriber::setupStereoCallbacks
void setupStereoCallbacks(ros::NodeHandle &nh, ros::NodeHandle &pnh, bool subscribeOdom, bool subscribeOdomInfo)
Definition: CommonDataSubscriberStereo.cpp:88
ros::TransportHints
image_transport::SubscriberFilter::subscribe
void subscribe(ImageTransport &it, const std::string &base_topic, uint32_t queue_size, const TransportHints &transport_hints=TransportHints())
rtabmap_sync::CommonDataSubscriber::commonSingleCameraCallback
void commonSingleCameraCallback(const nav_msgs::OdometryConstPtr &odomMsg, const rtabmap_msgs::UserDataConstPtr &userDataMsg, const cv_bridge::CvImageConstPtr &imageMsg, const cv_bridge::CvImageConstPtr &depthMsg, const sensor_msgs::CameraInfo &rgbCameraInfoMsg, const sensor_msgs::CameraInfo &depthCameraInfoMsg, const sensor_msgs::LaserScan &scanMsg, const sensor_msgs::PointCloud2 &scan3dMsg, const rtabmap_msgs::OdomInfoConstPtr &odomInfoMsg, const std::vector< rtabmap_msgs::GlobalDescriptor > &globalDescriptorMsgs=std::vector< rtabmap_msgs::GlobalDescriptor >(), const std::vector< rtabmap_msgs::KeyPoint > &localKeyPoints=std::vector< rtabmap_msgs::KeyPoint >(), const std::vector< rtabmap_msgs::Point3f > &localPoints3d=std::vector< rtabmap_msgs::Point3f >(), const cv::Mat &localDescriptors=cv::Mat())
Definition: CommonDataSubscriber.cpp:1048
rtabmap_sync::CommonDataSubscriber::imageRectRight_
image_transport::SubscriberFilter imageRectRight_
Definition: CommonDataSubscriber.h:279
rtabmap_sync::CommonDataSubscriber::odomInfoSub_
message_filters::Subscriber< rtabmap_msgs::OdomInfo > odomInfoSub_
Definition: CommonDataSubscriber.h:288
CommonDataSubscriber.h
rtabmap_sync::CommonDataSubscriber::syncQueueSize_
int syncQueueSize_
Definition: CommonDataSubscriber.h:246
rtabmap_sync::CommonDataSubscriber::topicQueueSize_
int topicQueueSize_
Definition: CommonDataSubscriber.h:245
ros::NodeHandle::resolveName
std::string resolveName(const std::string &name, bool remap=true) const
rtabmap_sync::CommonDataSubscriber::cameraInfoLeft_
message_filters::Subscriber< sensor_msgs::CameraInfo > cameraInfoLeft_
Definition: CommonDataSubscriber.h:280
SYNC_DECL5
#define SYNC_DECL5(CLASS, PREFIX, APPROX, QUEUE_SIZE, SUB0, SUB1, SUB2, SUB3, SUB4)
Definition: CommonDataSubscriberDefines.h:168
message_filters::Subscriber::subscribe
void subscribe()
rtabmap_sync::CommonDataSubscriber::approxSync_
bool approxSync_
Definition: CommonDataSubscriber.h:249
rtabmap_sync::CommonDataSubscriber::cameraInfoRight_
message_filters::Subscriber< sensor_msgs::CameraInfo > cameraInfoRight_
Definition: CommonDataSubscriber.h:281
rtabmap_sync::CommonDataSubscriber::odomSub_
message_filters::Subscriber< nav_msgs::Odometry > odomSub_
Definition: CommonDataSubscriber.h:283
SYNC_DECL4
#define SYNC_DECL4(CLASS, PREFIX, APPROX, QUEUE_SIZE, SUB0, SUB1, SUB2, SUB3)
Definition: CommonDataSubscriberDefines.h:147
rtabmap_sync::CommonDataSubscriber::subscribedToOdomInfo_
bool subscribedToOdomInfo_
Definition: CommonDataSubscriber.h:259
image_transport::TransportHints
cv_bridge::toCvShare
CvImageConstPtr toCvShare(const sensor_msgs::Image &source, const boost::shared_ptr< void const > &tracked_object, const std::string &encoding=std::string())
ROS_INFO
#define ROS_INFO(...)
rtabmap_sync::CommonDataSubscriber
Definition: CommonDataSubscriber.h:61
ros::NodeHandle


rtabmap_sync
Author(s): Mathieu Labbe
autogenerated on Mon Apr 28 2025 02:39:12