stereo_sync.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 
28 #include <ros/ros.h>
30 #include <nodelet/nodelet.h>
31 
32 #include <sensor_msgs/Image.h>
33 #include <sensor_msgs/CompressedImage.h>
35 #include <sensor_msgs/CameraInfo.h>
36 
39 
43 
44 #include <cv_bridge/cv_bridge.h>
45 #include <opencv2/highgui/highgui.hpp>
46 
47 #include <boost/thread.hpp>
48 
49 #include "rtabmap_ros/RGBDImage.h"
50 
53 
54 namespace rtabmap_ros
55 {
56 
58 {
59 public:
61  warningThread_(0),
63  approxSync_(0),
64  exactSync_(0)
65  {}
66 
67  virtual ~StereoSync()
68  {
69  if(approxSync_)
70  delete approxSync_;
71  if(exactSync_)
72  delete exactSync_;
73 
74  if(warningThread_)
75  {
76  callbackCalled_=true;
77  warningThread_->join();
78  delete warningThread_;
79  }
80  }
81 
82 private:
83  virtual void onInit()
84  {
87 
88  int queueSize = 10;
89  bool approxSync = false;
90  pnh.param("approx_sync", approxSync, approxSync);
91  pnh.param("queue_size", queueSize, queueSize);
92 
93  NODELET_INFO("%s: approx_sync = %s", getName().c_str(), approxSync?"true":"false");
94  NODELET_INFO("%s: queue_size = %d", getName().c_str(), queueSize);
95 
96  rgbdImagePub_ = nh.advertise<rtabmap_ros::RGBDImage>("rgbd_image", 1);
97  rgbdImageCompressedPub_ = nh.advertise<rtabmap_ros::RGBDImage>("rgbd_image/compressed", 1);
98 
99  if(approxSync)
100  {
102  approxSync_->registerCallback(boost::bind(&StereoSync::callback, this, _1, _2, _3, _4));
103  }
104  else
105  {
107  exactSync_->registerCallback(boost::bind(&StereoSync::callback, this, _1, _2, _3, _4));
108  }
109 
110  ros::NodeHandle left_nh(nh, "left");
111  ros::NodeHandle right_nh(nh, "right");
112  ros::NodeHandle left_pnh(pnh, "left");
113  ros::NodeHandle right_pnh(pnh, "right");
114  image_transport::ImageTransport rgb_it(left_nh);
115  image_transport::ImageTransport depth_it(right_nh);
116  image_transport::TransportHints hintsRgb("raw", ros::TransportHints(), left_pnh);
117  image_transport::TransportHints hintsDepth("raw", ros::TransportHints(), right_pnh);
118 
119  imageLeftSub_.subscribe(rgb_it, left_nh.resolveName("image_rect"), 1, hintsRgb);
120  imageRightSub_.subscribe(depth_it, right_nh.resolveName("image_rect"), 1, hintsDepth);
121  cameraInfoLeftSub_.subscribe(left_nh, "camera_info", 1);
122  cameraInfoRightSub_.subscribe(right_nh, "camera_info", 1);
123 
124  std::string subscribedTopicsMsg = uFormat("\n%s subscribed to (%s sync):\n %s,\n %s,\n %s,\n %s",
125  getName().c_str(),
126  approxSync?"approx":"exact",
127  imageLeftSub_.getTopic().c_str(),
128  imageRightSub_.getTopic().c_str(),
129  cameraInfoLeftSub_.getTopic().c_str(),
130  cameraInfoRightSub_.getTopic().c_str());
131 
132  warningThread_ = new boost::thread(boost::bind(&StereoSync::warningLoop, this, subscribedTopicsMsg, approxSync));
133  NODELET_INFO("%s", subscribedTopicsMsg.c_str());
134  }
135 
136  void warningLoop(const std::string & subscribedTopicsMsg, bool approxSync)
137  {
138  ros::Duration r(5.0);
139  while(!callbackCalled_)
140  {
141  r.sleep();
142  if(!callbackCalled_)
143  {
144  ROS_WARN("%s: Did not receive data since 5 seconds! Make sure the input topics are "
145  "published (\"$ rostopic hz my_topic\") and the timestamps in their "
146  "header are set. %s%s",
147  getName().c_str(),
148  approxSync?"":"Parameter \"approx_sync\" is false, which means that input "
149  "topics should have all the exact timestamp for the callback to be called.",
150  subscribedTopicsMsg.c_str());
151  }
152  }
153  }
154 
155  void callback(
156  const sensor_msgs::ImageConstPtr& imageLeft,
157  const sensor_msgs::ImageConstPtr& imageRight,
158  const sensor_msgs::CameraInfoConstPtr& cameraInfoLeft,
159  const sensor_msgs::CameraInfoConstPtr& cameraInfoRight)
160  {
161  callbackCalled_ = true;
163  {
164  rtabmap_ros::RGBDImage msg;
165  msg.header.frame_id = cameraInfoLeft->header.frame_id;
166  msg.header.stamp = imageLeft->header.stamp>imageRight->header.stamp?imageLeft->header.stamp:imageRight->header.stamp;
167  msg.rgbCameraInfo = *cameraInfoLeft;
168  msg.depthCameraInfo = *cameraInfoRight;
169 
171  {
172  rtabmap_ros::RGBDImage msgCompressed = msg;
173 
174  cv_bridge::CvImageConstPtr imagePtr = cv_bridge::toCvShare(imageLeft);
175  imagePtr->toCompressedImageMsg(msgCompressed.rgbCompressed, cv_bridge::JPG);
176 
177  cv_bridge::CvImageConstPtr imageDepthPtr = cv_bridge::toCvShare(imageRight);
178  imageDepthPtr->toCompressedImageMsg(msgCompressed.depthCompressed, cv_bridge::JPG);
179 
180  rgbdImageCompressedPub_.publish(msgCompressed);
181  }
182 
184  {
185  msg.rgb = *imageLeft;
186  msg.depth = *imageRight;
187  rgbdImagePub_.publish(msg);
188  }
189  }
190  }
191 
192 private:
193  boost::thread * warningThread_;
195 
198 
203 
206 
209 };
210 
212 }
213 
CvImageConstPtr toCvShare(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
std::string getTopic() const
virtual void onInit()
Definition: stereo_sync.cpp:83
std::string uFormat(const char *fmt,...)
void publish(const boost::shared_ptr< M > &message) const
std::string resolveName(const std::string &name, bool remap=true) const
bool sleep() const
image_transport::SubscriberFilter imageLeftSub_
const std::string & getName() const
message_filters::Subscriber< sensor_msgs::CameraInfo > cameraInfoLeftSub_
void warningLoop(const std::string &subscribedTopicsMsg, bool approxSync)
#define ROS_WARN(...)
ros::NodeHandle & getPrivateNodeHandle() const
message_filters::sync_policies::ExactTime< sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo, sensor_msgs::CameraInfo > MyExactSyncPolicy
ros::Publisher rgbdImageCompressedPub_
bool param(const std::string &param_name, T &param_val, const T &default_val) const
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
ros::Publisher rgbdImagePub_
ros::NodeHandle & getNodeHandle() const
message_filters::Synchronizer< MyExactSyncPolicy > * exactSync_
message_filters::Subscriber< sensor_msgs::CameraInfo > cameraInfoRightSub_
void subscribe(ImageTransport &it, const std::string &base_topic, uint32_t queue_size, const TransportHints &transport_hints=TransportHints())
#define false
message_filters::sync_policies::ApproximateTime< sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo, sensor_msgs::CameraInfo > MyApproxSyncPolicy
#define NODELET_INFO(...)
uint32_t getNumSubscribers() const
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)
boost::thread * warningThread_
PLUGINLIB_EXPORT_CLASS(rtabmap_ros::CoreWrapper, nodelet::Nodelet)
void callback(const sensor_msgs::ImageConstPtr &imageLeft, const sensor_msgs::ImageConstPtr &imageRight, const sensor_msgs::CameraInfoConstPtr &cameraInfoLeft, const sensor_msgs::CameraInfoConstPtr &cameraInfoRight)
message_filters::Synchronizer< MyApproxSyncPolicy > * approxSync_
r
image_transport::SubscriberFilter imageRightSub_
std::string getTopic() const


rtabmap_ros
Author(s): Mathieu Labbe
autogenerated on Fri Jun 7 2019 21:55:04