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  compressedRate_(0),
62  warningThread_(0),
64  approxSync_(0),
65  exactSync_(0)
66  {}
67 
68  virtual ~StereoSync()
69  {
70  if(approxSync_)
71  delete approxSync_;
72  if(exactSync_)
73  delete exactSync_;
74 
75  if(warningThread_)
76  {
77  callbackCalled_=true;
78  warningThread_->join();
79  delete warningThread_;
80  }
81  }
82 
83 private:
84  virtual void onInit()
85  {
88 
89  int queueSize = 10;
90  bool approxSync = false;
91  pnh.param("approx_sync", approxSync, approxSync);
92  pnh.param("queue_size", queueSize, queueSize);
93  pnh.param("compressed_rate", compressedRate_, compressedRate_);
94 
95  NODELET_INFO("%s: approx_sync = %s", getName().c_str(), approxSync?"true":"false");
96  NODELET_INFO("%s: queue_size = %d", getName().c_str(), queueSize);
97  NODELET_INFO("%s: compressed_rate = %f", getName().c_str(), compressedRate_);
98 
99  rgbdImagePub_ = nh.advertise<rtabmap_ros::RGBDImage>("rgbd_image", 1);
100  rgbdImageCompressedPub_ = nh.advertise<rtabmap_ros::RGBDImage>("rgbd_image/compressed", 1);
101 
102  if(approxSync)
103  {
105  approxSync_->registerCallback(boost::bind(&StereoSync::callback, this, _1, _2, _3, _4));
106  }
107  else
108  {
110  exactSync_->registerCallback(boost::bind(&StereoSync::callback, this, _1, _2, _3, _4));
111  }
112 
113  ros::NodeHandle left_nh(nh, "left");
114  ros::NodeHandle right_nh(nh, "right");
115  ros::NodeHandle left_pnh(pnh, "left");
116  ros::NodeHandle right_pnh(pnh, "right");
117  image_transport::ImageTransport rgb_it(left_nh);
118  image_transport::ImageTransport depth_it(right_nh);
119  image_transport::TransportHints hintsRgb("raw", ros::TransportHints(), left_pnh);
120  image_transport::TransportHints hintsDepth("raw", ros::TransportHints(), right_pnh);
121 
122  imageLeftSub_.subscribe(rgb_it, left_nh.resolveName("image_rect"), 1, hintsRgb);
123  imageRightSub_.subscribe(depth_it, right_nh.resolveName("image_rect"), 1, hintsDepth);
124  cameraInfoLeftSub_.subscribe(left_nh, "camera_info", 1);
125  cameraInfoRightSub_.subscribe(right_nh, "camera_info", 1);
126 
127  std::string subscribedTopicsMsg = uFormat("\n%s subscribed to (%s sync):\n %s \\\n %s \\\n %s \\\n %s",
128  getName().c_str(),
129  approxSync?"approx":"exact",
130  imageLeftSub_.getTopic().c_str(),
131  imageRightSub_.getTopic().c_str(),
132  cameraInfoLeftSub_.getTopic().c_str(),
133  cameraInfoRightSub_.getTopic().c_str());
134 
135  warningThread_ = new boost::thread(boost::bind(&StereoSync::warningLoop, this, subscribedTopicsMsg, approxSync));
136  NODELET_INFO("%s", subscribedTopicsMsg.c_str());
137  }
138 
139  void warningLoop(const std::string & subscribedTopicsMsg, bool approxSync)
140  {
141  ros::Duration r(5.0);
142  while(!callbackCalled_)
143  {
144  r.sleep();
145  if(!callbackCalled_)
146  {
147  ROS_WARN("%s: Did not receive data since 5 seconds! Make sure the input topics are "
148  "published (\"$ rostopic hz my_topic\") and the timestamps in their "
149  "header are set. %s%s",
150  getName().c_str(),
151  approxSync?"":"Parameter \"approx_sync\" is false, which means that input "
152  "topics should have all the exact timestamp for the callback to be called.",
153  subscribedTopicsMsg.c_str());
154  }
155  }
156  }
157 
158  void callback(
159  const sensor_msgs::ImageConstPtr& imageLeft,
160  const sensor_msgs::ImageConstPtr& imageRight,
161  const sensor_msgs::CameraInfoConstPtr& cameraInfoLeft,
162  const sensor_msgs::CameraInfoConstPtr& cameraInfoRight)
163  {
164  callbackCalled_ = true;
166  {
167  double leftStamp = imageLeft->header.stamp.toSec();
168  double rightStamp = imageRight->header.stamp.toSec();
169  double leftInfoStamp = cameraInfoLeft->header.stamp.toSec();
170  double rightInfoStamp = cameraInfoRight->header.stamp.toSec();
171 
172  rtabmap_ros::RGBDImage msg;
173  msg.header.frame_id = cameraInfoLeft->header.frame_id;
174  msg.header.stamp = imageLeft->header.stamp>imageRight->header.stamp?imageLeft->header.stamp:imageRight->header.stamp;
175  msg.rgb_camera_info = *cameraInfoLeft;
176  msg.depth_camera_info = *cameraInfoRight;
177 
179  {
180  bool publishCompressed = true;
181  if (compressedRate_ > 0.0)
182  {
184  {
185  NODELET_DEBUG("throttle last update at %f skipping", lastCompressedPublished_.toSec());
186  publishCompressed = false;
187  }
188  }
189 
190  if(publishCompressed)
191  {
193 
194  rtabmap_ros::RGBDImage msgCompressed = msg;
195 
196  cv_bridge::CvImageConstPtr imagePtr = cv_bridge::toCvShare(imageLeft);
197  imagePtr->toCompressedImageMsg(msgCompressed.rgb_compressed, cv_bridge::JPG);
198 
199  cv_bridge::CvImageConstPtr imageDepthPtr = cv_bridge::toCvShare(imageRight);
200  imageDepthPtr->toCompressedImageMsg(msgCompressed.depth_compressed, cv_bridge::JPG);
201 
202  rgbdImageCompressedPub_.publish(msgCompressed);
203  }
204  }
205 
207  {
208  msg.rgb = *imageLeft;
209  msg.depth = *imageRight;
210  rgbdImagePub_.publish(msg);
211  }
212 
213  if( leftStamp != imageLeft->header.stamp.toSec() ||
214  rightStamp != imageRight->header.stamp.toSec())
215  {
216  NODELET_ERROR("Input stamps changed between the beginning and the end of the callback! Make "
217  "sure the node publishing the topics doesn't override the same data after publishing them. A "
218  "solution is to use this node within another nodelet manager. Stamps: "
219  "left%f->%f right=%f->%f",
220  leftStamp, imageLeft->header.stamp.toSec(),
221  rightStamp, imageRight->header.stamp.toSec());
222  }
223  }
224  }
225 
226 private:
228  boost::thread * warningThread_;
231 
234 
239 
242 
245 };
246 
248 }
249 
CvImageConstPtr toCvShare(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
std::string getTopic() const
virtual void onInit()
Definition: stereo_sync.cpp:84
std::string uFormat(const char *fmt,...)
#define NODELET_ERROR(...)
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_
static Time now()
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_
#define NODELET_DEBUG(...)
std::string getTopic() const
ros::Time lastCompressedPublished_


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