rgbd_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"
51 
53 #include "rtabmap/core/util2d.h"
55 
57 
58 namespace rtabmap_sync
59 {
60 
61 class RGBDSync : public nodelet::Nodelet
62 {
63 public:
65  depthScale_(1.0),
66  decimation_(1),
67  compressedRate_(0),
70  {}
71 
72  virtual ~RGBDSync()
73  {
74  delete approxSyncDepth_;
75  delete exactSyncDepth_;
76  }
77 
78 private:
79  virtual void onInit()
80  {
83 
84  int queueSize = 1;
85  int syncQueueSize = 10;
86  bool approxSync = true;
87  double approxSyncMaxInterval = 0.0;
88  pnh.param("approx_sync", approxSync, approxSync);
89  pnh.param("approx_sync_max_interval", approxSyncMaxInterval, approxSyncMaxInterval);
90  pnh.param("topic_queue_size", queueSize, queueSize);
91  if(pnh.hasParam("queue_size") && !pnh.hasParam("sync_queue_size"))
92  {
93  pnh.param("queue_size", syncQueueSize, syncQueueSize);
94  ROS_WARN("Parameter \"queue_size\" has been renamed "
95  "to \"sync_queue_size\" and will be removed "
96  "in future versions! The value (%d) is still copied to "
97  "\"sync_queue_size\".", syncQueueSize);
98  }
99  else
100  {
101  pnh.param("sync_queue_size", syncQueueSize, syncQueueSize);
102  }
103  pnh.param("depth_scale", depthScale_, depthScale_);
104  pnh.param("decimation", decimation_, decimation_);
105  pnh.param("compressed_rate", compressedRate_, compressedRate_);
106 
107  if(decimation_<1)
108  {
109  decimation_ = 1;
110  }
111 
112  NODELET_INFO("%s: approx_sync = %s", getName().c_str(), approxSync?"true":"false");
113  if(approxSync)
114  NODELET_INFO("%s: approx_sync_max_interval = %f", getName().c_str(), approxSyncMaxInterval);
115  NODELET_INFO("%s: topic_queue_size = %d", getName().c_str(), queueSize);
116  NODELET_INFO("%s: sync_queue_size = %d", getName().c_str(), syncQueueSize);
117  NODELET_INFO("%s: depth_scale = %f", getName().c_str(), depthScale_);
118  NODELET_INFO("%s: decimation = %d", getName().c_str(), decimation_);
119  NODELET_INFO("%s: compressed_rate = %f", getName().c_str(), compressedRate_);
120 
121  rgbdImagePub_ = nh.advertise<rtabmap_msgs::RGBDImage>("rgbd_image", 1);
122  rgbdImageCompressedPub_ = nh.advertise<rtabmap_msgs::RGBDImage>("rgbd_image/compressed", 1);
123 
124  if(approxSync)
125  {
127  if(approxSyncMaxInterval > 0.0)
128  approxSyncDepth_->setMaxIntervalDuration(ros::Duration(approxSyncMaxInterval));
129  approxSyncDepth_->registerCallback(boost::bind(&RGBDSync::callback, this, boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3));
130  }
131  else
132  {
134  exactSyncDepth_->registerCallback(boost::bind(&RGBDSync::callback, this, boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3));
135  }
136 
137  ros::NodeHandle rgb_nh(nh, "rgb");
138  ros::NodeHandle depth_nh(nh, "depth");
139  ros::NodeHandle rgb_pnh(pnh, "rgb");
140  ros::NodeHandle depth_pnh(pnh, "depth");
141  image_transport::ImageTransport rgb_it(rgb_nh);
142  image_transport::ImageTransport depth_it(depth_nh);
143  image_transport::TransportHints hintsRgb("raw", ros::TransportHints(), rgb_pnh);
144  image_transport::TransportHints hintsDepth("raw", ros::TransportHints(), depth_pnh);
145 
146  imageSub_.subscribe(rgb_it, rgb_nh.resolveName("image"), queueSize, hintsRgb);
147  imageDepthSub_.subscribe(depth_it, depth_nh.resolveName("image"), queueSize, hintsDepth);
148  cameraInfoSub_.subscribe(rgb_nh, "camera_info", queueSize);
149 
150  std::string subscribedTopicsMsg = uFormat("\n%s subscribed to (%s sync%s):\n %s \\\n %s \\\n %s",
151  getName().c_str(),
152  approxSync?"approx":"exact",
153  approxSync&&approxSyncMaxInterval!=0.0?uFormat(", max interval=%fs", approxSyncMaxInterval).c_str():"",
154  imageSub_.getTopic().c_str(),
155  imageDepthSub_.getTopic().c_str(),
156  cameraInfoSub_.getTopic().c_str());
157  NODELET_INFO("%s", subscribedTopicsMsg.c_str());
158 
159  syncDiagnostic_.reset(new SyncDiagnostic(nh, pnh, getName()));
160  syncDiagnostic_->init(rgb_nh.resolveName("image"),
161  uFormat("%s: Did not receive data since 5 seconds! Make sure the input topics are "
162  "published (\"$ rostopic hz my_topic\") and the timestamps in their "
163  "header are set. %s%s",
164  getName().c_str(),
165  approxSync?"":"Parameter \"approx_sync\" is false, which means that input "
166  "topics should have all the exact timestamp for the callback to be called.",
167  subscribedTopicsMsg.c_str()));
168  }
169 
170  void callback(
171  const sensor_msgs::ImageConstPtr& image,
172  const sensor_msgs::ImageConstPtr& depth,
173  const sensor_msgs::CameraInfoConstPtr& cameraInfo)
174  {
175  syncDiagnostic_->tick(image->header.stamp);
176 
178  {
179  double rgbStamp = image->header.stamp.toSec();
180  double depthStamp = depth->header.stamp.toSec();
181  double infoStamp = cameraInfo->header.stamp.toSec();
182 
183  double stampDiff = fabs(rgbStamp - depthStamp);
184  if(stampDiff > 0.010)
185  {
186  NODELET_WARN("The time difference between rgb and depth frames is "
187  "high (diff=%fs, rgb=%fs, depth=%fs). You may want "
188  "to set approx_sync_max_interval lower than 0.01s to reject spurious bad synchronizations or use "
189  "approx_sync=false if streams have all the exact same timestamp.",
190  stampDiff,
191  rgbStamp,
192  depthStamp);
193  }
194 
195  rtabmap_msgs::RGBDImage msg;
196  msg.header.frame_id = cameraInfo->header.frame_id;
197  msg.header.stamp = image->header.stamp>depth->header.stamp?image->header.stamp:depth->header.stamp;
198  if(decimation_>1 && !(depth->width % decimation_ == 0 && depth->height % decimation_ == 0))
199  {
200  ROS_WARN("Decimation of depth images should be exact (decimation=%d, size=(%d,%d))! "
201  "Images won't be resized.", decimation_, depth->width, depth->height);
202  decimation_ = 1;
203  }
204  if(decimation_>1)
205  {
207  sensor_msgs::CameraInfo info;
209  info.header = cameraInfo->header;
210  msg.rgb_camera_info = info;
211  msg.depth_camera_info = info;
212  }
213  else
214  {
215  msg.rgb_camera_info = *cameraInfo;
216  msg.depth_camera_info = *cameraInfo;
217  }
218 
219  cv::Mat rgbMat;
220  cv::Mat depthMat;
222  cv_bridge::CvImageConstPtr imageDepthPtr = cv_bridge::toCvShare(depth);
223  rgbMat = imagePtr->image;
224  depthMat = imageDepthPtr->image;
225 
226  if(decimation_>1)
227  {
228  rgbMat = rtabmap::util2d::decimate(rgbMat, decimation_);
229  depthMat = rtabmap::util2d::decimate(depthMat, decimation_);
230  }
231 
232  if(depthScale_ != 1.0)
233  {
234  depthMat*=depthScale_;
235  }
236 
238  {
239  bool publishCompressed = true;
240  if (compressedRate_ > 0.0)
241  {
243  {
244  NODELET_DEBUG("throttle last update at %f skipping", lastCompressedPublished_.toSec());
245  publishCompressed = false;
246  }
247  }
248 
249  if(publishCompressed)
250  {
252 
253  rtabmap_msgs::RGBDImage msgCompressed;
254  msgCompressed.header = msg.header;
255  msgCompressed.rgb_camera_info = msg.rgb_camera_info;
256  msgCompressed.depth_camera_info = msg.depth_camera_info;
257 
258  cv_bridge::CvImage cvImg;
259  cvImg.header = image->header;
260  cvImg.image = rgbMat;
261  cvImg.encoding = image->encoding;
262  cvImg.toCompressedImageMsg(msgCompressed.rgb_compressed, cv_bridge::JPG);
263 
264  msgCompressed.depth_compressed.header = imageDepthPtr->header;
265  msgCompressed.depth_compressed.data = rtabmap::compressImage(depthMat, ".png");
266 
267  msgCompressed.depth_compressed.format = "png";
268 
269  rgbdImageCompressedPub_.publish(msgCompressed);
270  }
271  }
272 
274  {
275  cv_bridge::CvImage cvImg;
276  cvImg.header = image->header;
277  cvImg.image = rgbMat;
278  cvImg.encoding = image->encoding;
279  cvImg.toImageMsg(msg.rgb);
280 
281  cv_bridge::CvImage cvDepth;
282  cvDepth.header = depth->header;
283  cvDepth.image = depthMat;
284  cvDepth.encoding = depth->encoding;
285  cvDepth.toImageMsg(msg.depth);
286 
288  }
289 
290  if( rgbStamp != image->header.stamp.toSec() ||
291  depthStamp != depth->header.stamp.toSec())
292  {
293  NODELET_ERROR("Input stamps changed between the beginning and the end of the callback! Make "
294  "sure the node publishing the topics doesn't override the same data after publishing them. A "
295  "solution is to use this node within another nodelet manager. Stamps: "
296  "rgb=%f->%f depth=%f->%f",
297  rgbStamp, image->header.stamp.toSec(),
298  depthStamp, depth->header.stamp.toSec());
299  }
300  }
301  }
302 
303 private:
304  double depthScale_;
307 
309 
312 
316 
319 
322 
323  std::unique_ptr<SyncDiagnostic> syncDiagnostic_;
324 };
325 
327 }
328 
image_transport::SubscriberFilter
rtabmap_sync::RGBDSync::syncDiagnostic_
std::unique_ptr< SyncDiagnostic > syncDiagnostic_
Definition: rgbd_sync.cpp:323
NODELET_ERROR
#define NODELET_ERROR(...)
rtabmap_sync::RGBDSync
Definition: rgbd_sync.cpp:61
msg
msg
ros::Publisher
nodelet::Nodelet::getNodeHandle
ros::NodeHandle & getNodeHandle() const
image_encodings.h
cv_bridge::CvImage::toCompressedImageMsg
sensor_msgs::CompressedImagePtr toCompressedImageMsg(const Format dst_format=JPG) const
image_transport::ImageTransport
message_filters::Synchronizer
boost::shared_ptr
cv_bridge::CvImage::toImageMsg
sensor_msgs::ImagePtr toImageMsg() const
rtabmap_sync
Definition: CommonDataSubscriber.h:59
uFormat
std::string uFormat(const char *fmt,...)
ros.h
rtabmap::CameraModel
rtabmap_sync::SyncDiagnostic
Definition: SyncDiagnostic.h:13
Compression.h
SyncDiagnostic.h
rtabmap_sync::RGBDSync::rgbdImageCompressedPub_
ros::Publisher rgbdImageCompressedPub_
Definition: rgbd_sync.cpp:311
rtabmap_conversions::cameraModelToROS
void cameraModelToROS(const rtabmap::CameraModel &model, sensor_msgs::CameraInfo &camInfo)
rtabmap_conversions::cameraModelFromROS
rtabmap::CameraModel cameraModelFromROS(const sensor_msgs::CameraInfo &camInfo, const rtabmap::Transform &localTransform=rtabmap::Transform::getIdentity())
ros::TransportHints
rtabmap_sync::RGBDSync::RGBDSync
RGBDSync()
Definition: rgbd_sync.cpp:64
rtabmap_sync::RGBDSync::lastCompressedPublished_
ros::Time lastCompressedPublished_
Definition: rgbd_sync.cpp:308
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::compressImage
std::vector< unsigned char > RTABMAP_CORE_EXPORT compressImage(const cv::Mat &image, const std::string &format=".png")
rtabmap_sync::RGBDSync::compressedRate_
double compressedRate_
Definition: rgbd_sync.cpp:306
rtabmap::util2d::decimate
cv::Mat RTABMAP_CORE_EXPORT decimate(const cv::Mat &image, int d)
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)
image_transport::SubscriberFilter::getTopic
std::string getTopic() const
fabs
Real fabs(const Real &a)
rtabmap_sync::RGBDSync::~RGBDSync
virtual ~RGBDSync()
Definition: rgbd_sync.cpp:72
message_filters::Subscriber::getTopic
std::string getTopic() const
message_filters::Subscriber< sensor_msgs::CameraInfo >
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
subscriber_filter.h
rtabmap_sync::RGBDSync::depthScale_
double depthScale_
Definition: rgbd_sync.cpp:304
cv_bridge::CvImage::header
std_msgs::Header header
rtabmap_sync::RGBDSync::imageSub_
image_transport::SubscriberFilter imageSub_
Definition: rgbd_sync.cpp:313
subscriber.h
rtabmap_sync::RGBDSync::rgbdImagePub_
ros::Publisher rgbdImagePub_
Definition: rgbd_sync.cpp:310
rtabmap_sync::RGBDSync::imageDepthSub_
image_transport::SubscriberFilter imageDepthSub_
Definition: rgbd_sync.cpp:314
rtabmap_sync::RGBDSync::exactSyncDepth_
message_filters::Synchronizer< MyExactSyncDepthPolicy > * exactSyncDepth_
Definition: rgbd_sync.cpp:321
info
else if n * info
ros::NodeHandle::hasParam
bool hasParam(const std::string &key) const
ROS_WARN
#define ROS_WARN(...)
rtabmap_sync::RGBDSync::decimation_
int decimation_
Definition: rgbd_sync.cpp:305
model
noiseModel::Diagonal::shared_ptr model
image_transport.h
rtabmap_sync::RGBDSync::callback
void callback(const sensor_msgs::ImageConstPtr &image, const sensor_msgs::ImageConstPtr &depth, const sensor_msgs::CameraInfoConstPtr &cameraInfo)
Definition: rgbd_sync.cpp:170
exact_time.h
rtabmap_sync::RGBDSync::cameraInfoSub_
message_filters::Subscriber< sensor_msgs::CameraInfo > cameraInfoSub_
Definition: rgbd_sync.cpp:315
message_filters::Subscriber::subscribe
void subscribe()
NODELET_INFO
#define NODELET_INFO(...)
nodelet::Nodelet
ros::Time
cv_bridge::CvImage::encoding
std::string encoding
nodelet.h
c_str
const char * c_str(Args &&...args)
cv_bridge.h
cv_bridge::CvImage
class_list_macros.hpp
rtabmap_sync::RGBDSync::MyExactSyncDepthPolicy
message_filters::sync_policies::ExactTime< sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo > MyExactSyncDepthPolicy
Definition: rgbd_sync.cpp:320
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())
rtabmap_sync::RGBDSync::onInit
virtual void onInit()
Definition: rgbd_sync.cpp:79
message_filters::sync_policies::ExactTime
UConversion.h
MsgConversion.h
cv_bridge::JPG
JPG
rtabmap_sync::RGBDSync::MyApproxSyncDepthPolicy
message_filters::sync_policies::ApproximateTime< sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo > MyApproxSyncDepthPolicy
Definition: rgbd_sync.cpp:317
cv_bridge::CvImage::image
cv::Mat image
ros::Duration
ros::NodeHandle
rtabmap_sync::RGBDSync::approxSyncDepth_
message_filters::Synchronizer< MyApproxSyncDepthPolicy > * approxSyncDepth_
Definition: rgbd_sync.cpp:318
NODELET_DEBUG
#define NODELET_DEBUG(...)
util2d.h
ros::Time::now
static Time now()


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