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  double approxSyncMaxInterval = 0.0;
92  pnh.param("approx_sync", approxSync, approxSync);
93  if(approxSync)
94  pnh.param("approx_sync_max_interval", approxSyncMaxInterval, approxSyncMaxInterval);
95  pnh.param("queue_size", queueSize, queueSize);
96  pnh.param("compressed_rate", compressedRate_, compressedRate_);
97 
98  NODELET_INFO("%s: approx_sync = %s", getName().c_str(), approxSync?"true":"false");
99  NODELET_INFO("%s: approx_sync_max_interval = %f", getName().c_str(), approxSyncMaxInterval);
100  NODELET_INFO("%s: queue_size = %d", getName().c_str(), queueSize);
101  NODELET_INFO("%s: compressed_rate = %f", getName().c_str(), compressedRate_);
102 
103  rgbdImagePub_ = nh.advertise<rtabmap_ros::RGBDImage>("rgbd_image", 1);
104  rgbdImageCompressedPub_ = nh.advertise<rtabmap_ros::RGBDImage>("rgbd_image/compressed", 1);
105 
106  if(approxSync)
107  {
109  if(approxSyncMaxInterval>0.0)
110  approxSync_->setMaxIntervalDuration(ros::Duration(approxSyncMaxInterval));
111  approxSync_->registerCallback(boost::bind(&StereoSync::callback, this, boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3, boost::placeholders::_4));
112  }
113  else
114  {
116  exactSync_->registerCallback(boost::bind(&StereoSync::callback, this, boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3, boost::placeholders::_4));
117  }
118 
119  ros::NodeHandle left_nh(nh, "left");
120  ros::NodeHandle right_nh(nh, "right");
121  ros::NodeHandle left_pnh(pnh, "left");
122  ros::NodeHandle right_pnh(pnh, "right");
123  image_transport::ImageTransport rgb_it(left_nh);
124  image_transport::ImageTransport depth_it(right_nh);
125  image_transport::TransportHints hintsRgb("raw", ros::TransportHints(), left_pnh);
126  image_transport::TransportHints hintsDepth("raw", ros::TransportHints(), right_pnh);
127 
128  imageLeftSub_.subscribe(rgb_it, left_nh.resolveName("image_rect"), 1, hintsRgb);
129  imageRightSub_.subscribe(depth_it, right_nh.resolveName("image_rect"), 1, hintsDepth);
130  cameraInfoLeftSub_.subscribe(left_nh, "camera_info", 1);
131  cameraInfoRightSub_.subscribe(right_nh, "camera_info", 1);
132 
133  std::string subscribedTopicsMsg = uFormat("\n%s subscribed to (%s sync%s):\n %s \\\n %s \\\n %s \\\n %s",
134  getName().c_str(),
135  approxSync?"approx":"exact",
136  approxSync&&approxSyncMaxInterval!=0.0?uFormat(", max interval=%fs", approxSyncMaxInterval).c_str():"",
137  imageLeftSub_.getTopic().c_str(),
138  imageRightSub_.getTopic().c_str(),
139  cameraInfoLeftSub_.getTopic().c_str(),
140  cameraInfoRightSub_.getTopic().c_str());
141 
142  warningThread_ = new boost::thread(boost::bind(&StereoSync::warningLoop, this, subscribedTopicsMsg, approxSync));
143  NODELET_INFO("%s", subscribedTopicsMsg.c_str());
144  }
145 
146  void warningLoop(const std::string & subscribedTopicsMsg, bool approxSync)
147  {
148  ros::Duration r(5.0);
149  while(!callbackCalled_)
150  {
151  r.sleep();
152  if(!callbackCalled_)
153  {
154  ROS_WARN("%s: Did not receive data since 5 seconds! Make sure the input topics are "
155  "published (\"$ rostopic hz my_topic\") and the timestamps in their "
156  "header are set. %s%s",
157  getName().c_str(),
158  approxSync?"":"Parameter \"approx_sync\" is false, which means that input "
159  "topics should have all the exact timestamp for the callback to be called.",
160  subscribedTopicsMsg.c_str());
161  }
162  }
163  }
164 
165  void callback(
166  const sensor_msgs::ImageConstPtr& imageLeft,
167  const sensor_msgs::ImageConstPtr& imageRight,
168  const sensor_msgs::CameraInfoConstPtr& cameraInfoLeft,
169  const sensor_msgs::CameraInfoConstPtr& cameraInfoRight)
170  {
171  callbackCalled_ = true;
173  {
174  double leftStamp = imageLeft->header.stamp.toSec();
175  double rightStamp = imageRight->header.stamp.toSec();
176  double leftInfoStamp = cameraInfoLeft->header.stamp.toSec();
177  double rightInfoStamp = cameraInfoRight->header.stamp.toSec();
178 
179  double stampDiff = fabs(leftStamp - rightStamp);
180  if(stampDiff > 0.010)
181  {
182  NODELET_WARN("The time difference between left and right frames is "
183  "high (diff=%fs, left=%fs, right=%fs). If your left and right cameras are hardware "
184  "synchronized, use approx_sync:=false. Otherwise, you may want "
185  "to set approx_sync_max_interval lower than 0.01s to reject spurious bad synchronizations.",
186  stampDiff,
187  leftStamp,
188  rightStamp);
189  }
190 
191  rtabmap_ros::RGBDImage msg;
192  msg.header.frame_id = cameraInfoLeft->header.frame_id;
193  msg.header.stamp = imageLeft->header.stamp>imageRight->header.stamp?imageLeft->header.stamp:imageRight->header.stamp;
194  msg.rgb_camera_info = *cameraInfoLeft;
195  msg.depth_camera_info = *cameraInfoRight;
196 
198  {
199  bool publishCompressed = true;
200  if (compressedRate_ > 0.0)
201  {
203  {
204  NODELET_DEBUG("throttle last update at %f skipping", lastCompressedPublished_.toSec());
205  publishCompressed = false;
206  }
207  }
208 
209  if(publishCompressed)
210  {
212 
213  rtabmap_ros::RGBDImage msgCompressed = msg;
214 
215  cv_bridge::CvImageConstPtr imagePtr = cv_bridge::toCvShare(imageLeft);
216  imagePtr->toCompressedImageMsg(msgCompressed.rgb_compressed, cv_bridge::JPG);
217 
218  cv_bridge::CvImageConstPtr imageDepthPtr = cv_bridge::toCvShare(imageRight);
219  imageDepthPtr->toCompressedImageMsg(msgCompressed.depth_compressed, cv_bridge::JPG);
220 
221  rgbdImageCompressedPub_.publish(msgCompressed);
222  }
223  }
224 
226  {
227  msg.rgb = *imageLeft;
228  msg.depth = *imageRight;
229  rgbdImagePub_.publish(msg);
230  }
231 
232  if( leftStamp != imageLeft->header.stamp.toSec() ||
233  rightStamp != imageRight->header.stamp.toSec())
234  {
235  NODELET_ERROR("Input stamps changed between the beginning and the end of the callback! Make "
236  "sure the node publishing the topics doesn't override the same data after publishing them. A "
237  "solution is to use this node within another nodelet manager. Stamps: "
238  "left%f->%f right=%f->%f",
239  leftStamp, imageLeft->header.stamp.toSec(),
240  rightStamp, imageRight->header.stamp.toSec());
241  }
242  }
243  }
244 
245 private:
247  boost::thread * warningThread_;
250 
253 
258 
261 
264 };
265 
267 }
268 
CvImageConstPtr toCvShare(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
virtual void onInit()
Definition: stereo_sync.cpp:84
std::string uFormat(const char *fmt,...)
#define NODELET_ERROR(...)
#define NODELET_WARN(...)
std::string getTopic() const
ros::NodeHandle & getNodeHandle() const
image_transport::SubscriberFilter imageLeftSub_
message_filters::Subscriber< sensor_msgs::CameraInfo > cameraInfoLeftSub_
void warningLoop(const std::string &subscribedTopicsMsg, bool approxSync)
ros::NodeHandle & getPrivateNodeHandle() const
#define ROS_WARN(...)
message_filters::sync_policies::ExactTime< sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo, sensor_msgs::CameraInfo > MyExactSyncPolicy
const std::string & getName() const
bool param(const std::string &param_name, T &param_val, const T &default_val) const
void publish(const boost::shared_ptr< M > &message) const
ros::Publisher rgbdImageCompressedPub_
std::string resolveName(const std::string &name, bool remap=true) const
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
ros::Publisher rgbdImagePub_
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(...)
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)
bool sleep() const
uint32_t getNumSubscribers() const
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(...)
ros::Time lastCompressedPublished_


rtabmap_ros
Author(s): Mathieu Labbe
autogenerated on Tue Jan 24 2023 04:04:40