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_msgs/RGBDImage.h"
50 
53 
55 
56 namespace rtabmap_sync
57 {
58 
60 {
61 public:
63  compressedRate_(0),
64  approxSync_(0),
65  exactSync_(0)
66  {}
67 
68  virtual ~StereoSync()
69  {
70  delete approxSync_;
71  delete exactSync_;
72  }
73 
74 private:
75  virtual void onInit()
76  {
79 
80  int queueSize = 1;
81  int syncQueueSize = 10;
82  bool approxSync = false;
83  double approxSyncMaxInterval = 0.0;
84  pnh.param("approx_sync", approxSync, approxSync);
85  if(approxSync)
86  pnh.param("approx_sync_max_interval", approxSyncMaxInterval, approxSyncMaxInterval);
87  pnh.param("topic_queue_size", queueSize, queueSize);
88  if(pnh.hasParam("queue_size") && !pnh.hasParam("sync_queue_size"))
89  {
90  pnh.param("queue_size", syncQueueSize, syncQueueSize);
91  ROS_WARN("Parameter \"queue_size\" has been renamed "
92  "to \"sync_queue_size\" and will be removed "
93  "in future versions! The value (%d) is still copied to "
94  "\"sync_queue_size\".", syncQueueSize);
95  }
96  else
97  {
98  pnh.param("sync_queue_size", syncQueueSize, syncQueueSize);
99  }
100  pnh.param("compressed_rate", compressedRate_, compressedRate_);
101 
102  NODELET_INFO("%s: approx_sync = %s", getName().c_str(), approxSync?"true":"false");
103  NODELET_INFO("%s: approx_sync_max_interval = %f", getName().c_str(), approxSyncMaxInterval);
104  NODELET_INFO("%s: topic_queue_size = %d", getName().c_str(), queueSize);
105  NODELET_INFO("%s: sync_queue_size = %d", getName().c_str(), syncQueueSize);
106  NODELET_INFO("%s: compressed_rate = %f", getName().c_str(), compressedRate_);
107 
108  rgbdImagePub_ = nh.advertise<rtabmap_msgs::RGBDImage>("rgbd_image", 1);
109  rgbdImageCompressedPub_ = nh.advertise<rtabmap_msgs::RGBDImage>("rgbd_image/compressed", 1);
110 
111  if(approxSync)
112  {
114  if(approxSyncMaxInterval>0.0)
115  approxSync_->setMaxIntervalDuration(ros::Duration(approxSyncMaxInterval));
116  approxSync_->registerCallback(boost::bind(&StereoSync::callback, this, boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3, boost::placeholders::_4));
117  }
118  else
119  {
121  exactSync_->registerCallback(boost::bind(&StereoSync::callback, this, boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3, boost::placeholders::_4));
122  }
123 
124  ros::NodeHandle left_nh(nh, "left");
125  ros::NodeHandle right_nh(nh, "right");
126  ros::NodeHandle left_pnh(pnh, "left");
127  ros::NodeHandle right_pnh(pnh, "right");
128  image_transport::ImageTransport rgb_it(left_nh);
129  image_transport::ImageTransport depth_it(right_nh);
130  image_transport::TransportHints hintsRgb("raw", ros::TransportHints(), left_pnh);
131  image_transport::TransportHints hintsDepth("raw", ros::TransportHints(), right_pnh);
132 
133  imageLeftSub_.subscribe(rgb_it, left_nh.resolveName("image_rect"), queueSize, hintsRgb);
134  imageRightSub_.subscribe(depth_it, right_nh.resolveName("image_rect"), queueSize, hintsDepth);
135  cameraInfoLeftSub_.subscribe(left_nh, "camera_info", queueSize);
136  cameraInfoRightSub_.subscribe(right_nh, "camera_info", queueSize);
137 
138  std::string subscribedTopicsMsg = uFormat("\n%s subscribed to (%s sync%s):\n %s \\\n %s \\\n %s \\\n %s",
139  getName().c_str(),
140  approxSync?"approx":"exact",
141  approxSync&&approxSyncMaxInterval!=0.0?uFormat(", max interval=%fs", approxSyncMaxInterval).c_str():"",
142  imageLeftSub_.getTopic().c_str(),
143  imageRightSub_.getTopic().c_str(),
144  cameraInfoLeftSub_.getTopic().c_str(),
145  cameraInfoRightSub_.getTopic().c_str());
146  NODELET_INFO("%s", subscribedTopicsMsg.c_str());
147 
148  syncDiagnostic_.reset(new SyncDiagnostic(nh, pnh, getName()));
149  syncDiagnostic_->init(left_nh.resolveName("image_rect"),
150  uFormat("%s: Did not receive data since 5 seconds! Make sure the input topics are "
151  "published (\"$ rostopic hz my_topic\") and the timestamps in their "
152  "header are set. %s%s",
153  getName().c_str(),
154  approxSync?"":"Parameter \"approx_sync\" is false, which means that input "
155  "topics should have all the exact timestamp for the callback to be called.",
156  subscribedTopicsMsg.c_str()));
157 
158  }
159 
160  void callback(
161  const sensor_msgs::ImageConstPtr& imageLeft,
162  const sensor_msgs::ImageConstPtr& imageRight,
163  const sensor_msgs::CameraInfoConstPtr& cameraInfoLeft,
164  const sensor_msgs::CameraInfoConstPtr& cameraInfoRight)
165  {
166  syncDiagnostic_->tick(imageLeft->header.stamp);
167 
169  {
170  double leftStamp = imageLeft->header.stamp.toSec();
171  double rightStamp = imageRight->header.stamp.toSec();
172  double leftInfoStamp = cameraInfoLeft->header.stamp.toSec();
173  double rightInfoStamp = cameraInfoRight->header.stamp.toSec();
174 
175  double stampDiff = fabs(leftStamp - rightStamp);
176  if(stampDiff > 0.010)
177  {
178  NODELET_WARN("The time difference between left and right frames is "
179  "high (diff=%fs, left=%fs, right=%fs). If your left and right cameras are hardware "
180  "synchronized, use approx_sync:=false. Otherwise, you may want "
181  "to set approx_sync_max_interval lower than 0.01s to reject spurious bad synchronizations.",
182  stampDiff,
183  leftStamp,
184  rightStamp);
185  }
186 
187  rtabmap_msgs::RGBDImage msg;
188  msg.header.frame_id = cameraInfoLeft->header.frame_id;
189  msg.header.stamp = imageLeft->header.stamp>imageRight->header.stamp?imageLeft->header.stamp:imageRight->header.stamp;
190  msg.rgb_camera_info = *cameraInfoLeft;
191  msg.depth_camera_info = *cameraInfoRight;
192 
194  {
195  bool publishCompressed = true;
196  if (compressedRate_ > 0.0)
197  {
199  {
200  NODELET_DEBUG("throttle last update at %f skipping", lastCompressedPublished_.toSec());
201  publishCompressed = false;
202  }
203  }
204 
205  if(publishCompressed)
206  {
208 
209  rtabmap_msgs::RGBDImage msgCompressed = msg;
210 
211  cv_bridge::CvImageConstPtr imagePtr = cv_bridge::toCvShare(imageLeft);
212  imagePtr->toCompressedImageMsg(msgCompressed.rgb_compressed, cv_bridge::JPG);
213 
214  cv_bridge::CvImageConstPtr imageDepthPtr = cv_bridge::toCvShare(imageRight);
215  imageDepthPtr->toCompressedImageMsg(msgCompressed.depth_compressed, cv_bridge::JPG);
216 
217  rgbdImageCompressedPub_.publish(msgCompressed);
218  }
219  }
220 
222  {
223  msg.rgb = *imageLeft;
224  msg.depth = *imageRight;
226  }
227 
228  if( leftStamp != imageLeft->header.stamp.toSec() ||
229  rightStamp != imageRight->header.stamp.toSec())
230  {
231  NODELET_ERROR("Input stamps changed between the beginning and the end of the callback! Make "
232  "sure the node publishing the topics doesn't override the same data after publishing them. A "
233  "solution is to use this node within another nodelet manager. Stamps: "
234  "left%f->%f right=%f->%f",
235  leftStamp, imageLeft->header.stamp.toSec(),
236  rightStamp, imageRight->header.stamp.toSec());
237  }
238  }
239  }
240 
241 private:
244 
247 
252 
255 
258 
259  std::unique_ptr<SyncDiagnostic> syncDiagnostic_;
260 };
261 
263 }
264 
image_transport::SubscriberFilter
rtabmap_sync::StereoSync::lastCompressedPublished_
ros::Time lastCompressedPublished_
Definition: stereo_sync.cpp:243
NODELET_ERROR
#define NODELET_ERROR(...)
msg
msg
ros::Publisher
nodelet::Nodelet::getNodeHandle
ros::NodeHandle & getNodeHandle() const
image_encodings.h
image_transport::ImageTransport
message_filters::Synchronizer
boost::shared_ptr
rtabmap_sync::StereoSync::imageRightSub_
image_transport::SubscriberFilter imageRightSub_
Definition: stereo_sync.cpp:249
rtabmap_sync
Definition: CommonDataSubscriber.h:59
rtabmap_sync::StereoSync::MyExactSyncPolicy
message_filters::sync_policies::ExactTime< sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo, sensor_msgs::CameraInfo > MyExactSyncPolicy
Definition: stereo_sync.cpp:256
uFormat
std::string uFormat(const char *fmt,...)
ros.h
rtabmap_sync::SyncDiagnostic
Definition: SyncDiagnostic.h:13
Compression.h
rtabmap_sync::StereoSync::callback
void callback(const sensor_msgs::ImageConstPtr &imageLeft, const sensor_msgs::ImageConstPtr &imageRight, const sensor_msgs::CameraInfoConstPtr &cameraInfoLeft, const sensor_msgs::CameraInfoConstPtr &cameraInfoRight)
Definition: stereo_sync.cpp:160
SyncDiagnostic.h
rtabmap_sync::StereoSync::rgbdImageCompressedPub_
ros::Publisher rgbdImageCompressedPub_
Definition: stereo_sync.cpp:246
ros::TransportHints
TimeBase< Time, Duration >::toSec
double toSec() const
NODELET_WARN
#define NODELET_WARN(...)
image_transport::SubscriberFilter::subscribe
void subscribe(ImageTransport &it, const std::string &base_topic, uint32_t queue_size, const TransportHints &transport_hints=TransportHints())
rtabmap_sync::StereoSync::exactSync_
message_filters::Synchronizer< MyExactSyncPolicy > * exactSync_
Definition: stereo_sync.cpp:257
nodelet::Nodelet::getPrivateNodeHandle
ros::NodeHandle & getPrivateNodeHandle() const
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
ros::NodeHandle::advertise
Publisher advertise(AdvertiseOptions &ops)
rtabmap_sync::StereoSync::onInit
virtual void onInit()
Definition: stereo_sync.cpp:75
image_transport::SubscriberFilter::getTopic
std::string getTopic() const
fabs
Real fabs(const Real &a)
message_filters::Subscriber::getTopic
std::string getTopic() const
message_filters::Subscriber< sensor_msgs::CameraInfo >
rtabmap_sync::StereoSync
Definition: stereo_sync.cpp:59
ros::NodeHandle::resolveName
std::string resolveName(const std::string &name, bool remap=true) const
rtabmap_sync::PLUGINLIB_EXPORT_CLASS
PLUGINLIB_EXPORT_CLASS(rtabmap_sync::RgbSync, nodelet::Nodelet)
message_filters::sync_policies::ApproximateTime
rtabmap_sync::StereoSync::compressedRate_
double compressedRate_
Definition: stereo_sync.cpp:242
subscriber_filter.h
rtabmap_sync::StereoSync::MyApproxSyncPolicy
message_filters::sync_policies::ApproximateTime< sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo, sensor_msgs::CameraInfo > MyApproxSyncPolicy
Definition: stereo_sync.cpp:253
rtabmap_sync::StereoSync::StereoSync
StereoSync()
Definition: stereo_sync.cpp:62
subscriber.h
rtabmap_sync::StereoSync::~StereoSync
virtual ~StereoSync()
Definition: stereo_sync.cpp:68
ros::NodeHandle::hasParam
bool hasParam(const std::string &key) const
ROS_WARN
#define ROS_WARN(...)
rtabmap_sync::StereoSync::cameraInfoLeftSub_
message_filters::Subscriber< sensor_msgs::CameraInfo > cameraInfoLeftSub_
Definition: stereo_sync.cpp:250
rtabmap_sync::StereoSync::approxSync_
message_filters::Synchronizer< MyApproxSyncPolicy > * approxSync_
Definition: stereo_sync.cpp:254
image_transport.h
rtabmap_sync::StereoSync::cameraInfoRightSub_
message_filters::Subscriber< sensor_msgs::CameraInfo > cameraInfoRightSub_
Definition: stereo_sync.cpp:251
exact_time.h
message_filters::Subscriber::subscribe
void subscribe()
NODELET_INFO
#define NODELET_INFO(...)
nodelet::Nodelet
ros::Time
nodelet.h
c_str
const char * c_str(Args &&...args)
cv_bridge.h
class_list_macros.hpp
nodelet::Nodelet::getName
const std::string & getName() const
ros::NodeHandle::param
T param(const std::string &param_name, const T &default_val) const
approximate_time.h
ros::Publisher::getNumSubscribers
uint32_t getNumSubscribers() const
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())
message_filters::sync_policies::ExactTime
UConversion.h
cv_bridge::JPG
JPG
rtabmap_sync::StereoSync::syncDiagnostic_
std::unique_ptr< SyncDiagnostic > syncDiagnostic_
Definition: stereo_sync.cpp:259
ros::Duration
ros::NodeHandle
rtabmap_sync::StereoSync::imageLeftSub_
image_transport::SubscriberFilter imageLeftSub_
Definition: stereo_sync.cpp:248
rtabmap_sync::StereoSync::rgbdImagePub_
ros::Publisher rgbdImagePub_
Definition: stereo_sync.cpp:245
NODELET_DEBUG
#define NODELET_DEBUG(...)
ros::Time::now
static Time now()


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