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


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