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"
50 
53 
54 namespace rtabmap_ros
55 {
56 
57 class RGBDSync : public nodelet::Nodelet
58 {
59 public:
61  depthScale_(1.0),
62  warningThread_(0),
66  {}
67 
68  virtual ~RGBDSync()
69  {
71  delete approxSyncDepth_;
72  if(exactSyncDepth_)
73  delete exactSyncDepth_;
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 = true;
91  pnh.param("approx_sync", approxSync, approxSync);
92  pnh.param("queue_size", queueSize, queueSize);
93  pnh.param("depth_scale", depthScale_, depthScale_);
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: depth_scale = %f", getName().c_str(), depthScale_);
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  approxSyncDepth_->registerCallback(boost::bind(&RGBDSync::callback, this, _1, _2, _3));
106  }
107  else
108  {
110  exactSyncDepth_->registerCallback(boost::bind(&RGBDSync::callback, this, _1, _2, _3));
111  }
112 
113  ros::NodeHandle rgb_nh(nh, "rgb");
114  ros::NodeHandle depth_nh(nh, "depth");
115  ros::NodeHandle rgb_pnh(pnh, "rgb");
116  ros::NodeHandle depth_pnh(pnh, "depth");
117  image_transport::ImageTransport rgb_it(rgb_nh);
118  image_transport::ImageTransport depth_it(depth_nh);
119  image_transport::TransportHints hintsRgb("raw", ros::TransportHints(), rgb_pnh);
120  image_transport::TransportHints hintsDepth("raw", ros::TransportHints(), depth_pnh);
121 
122  imageSub_.subscribe(rgb_it, rgb_nh.resolveName("image"), 1, hintsRgb);
123  imageDepthSub_.subscribe(depth_it, depth_nh.resolveName("image"), 1, hintsDepth);
124  cameraInfoSub_.subscribe(rgb_nh, "camera_info", 1);
125 
126  std::string subscribedTopicsMsg = uFormat("\n%s subscribed to (%s sync):\n %s,\n %s,\n %s",
127  getName().c_str(),
128  approxSync?"approx":"exact",
129  imageSub_.getTopic().c_str(),
130  imageDepthSub_.getTopic().c_str(),
131  cameraInfoSub_.getTopic().c_str());
132 
133  warningThread_ = new boost::thread(boost::bind(&RGBDSync::warningLoop, this, subscribedTopicsMsg, approxSync));
134  NODELET_INFO("%s", subscribedTopicsMsg.c_str());
135  }
136 
137  void warningLoop(const std::string & subscribedTopicsMsg, bool approxSync)
138  {
139  ros::Duration r(5.0);
140  while(!callbackCalled_)
141  {
142  r.sleep();
143  if(!callbackCalled_)
144  {
145  ROS_WARN("%s: Did not receive data since 5 seconds! Make sure the input topics are "
146  "published (\"$ rostopic hz my_topic\") and the timestamps in their "
147  "header are set. %s%s",
148  getName().c_str(),
149  approxSync?"":"Parameter \"approx_sync\" is false, which means that input "
150  "topics should have all the exact timestamp for the callback to be called.",
151  subscribedTopicsMsg.c_str());
152  }
153  }
154  }
155 
156  void callback(
157  const sensor_msgs::ImageConstPtr& image,
158  const sensor_msgs::ImageConstPtr& depth,
159  const sensor_msgs::CameraInfoConstPtr& cameraInfo)
160  {
161  callbackCalled_ = true;
163  {
164  rtabmap_ros::RGBDImage msg;
165  msg.header.frame_id = cameraInfo->header.frame_id;
166  msg.header.stamp = image->header.stamp>depth->header.stamp?image->header.stamp:depth->header.stamp;
167  msg.rgbCameraInfo = *cameraInfo;
168  msg.depthCameraInfo = *cameraInfo;
169 
171  {
172  rtabmap_ros::RGBDImage msgCompressed = msg;
173 
175  imagePtr->toCompressedImageMsg(msgCompressed.rgbCompressed, cv_bridge::JPG);
176 
177  cv_bridge::CvImageConstPtr imageDepthPtr = cv_bridge::toCvShare(depth);
178  msgCompressed.depthCompressed.header = imageDepthPtr->header;
179  if(depthScale_ != 1.0)
180  {
181  msgCompressed.depthCompressed.data = rtabmap::compressImage(imageDepthPtr->image*depthScale_, ".png");
182  }
183  else
184  {
185  msgCompressed.depthCompressed.data = rtabmap::compressImage(imageDepthPtr->image, ".png");
186  }
187  msgCompressed.depthCompressed.format = "png";
188 
189  rgbdImageCompressedPub_.publish(msgCompressed);
190  }
191 
193  {
194  msg.rgb = *image;
195  if(depthScale_ != 1.0)
196  {
197  cv_bridge::CvImagePtr imageDepthPtr = cv_bridge::toCvCopy(depth);
198  imageDepthPtr->image*=depthScale_;
199  msg.depth = *imageDepthPtr->toImageMsg();
200  }
201  else
202  {
203  msg.depth = *depth;
204  }
205  rgbdImagePub_.publish(msg);
206  }
207  }
208  }
209 
210 private:
211  double depthScale_;
212  boost::thread * warningThread_;
214 
217 
221 
224 
227 };
228 
230 }
231 
CvImageConstPtr toCvShare(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
std::string getTopic() const
std::string uFormat(const char *fmt,...)
message_filters::Synchronizer< MyApproxSyncDepthPolicy > * approxSyncDepth_
Definition: rgbd_sync.cpp:223
message_filters::sync_policies::ExactTime< sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo > MyExactSyncDepthPolicy
Definition: rgbd_sync.cpp:225
void publish(const boost::shared_ptr< M > &message) const
std::string resolveName(const std::string &name, bool remap=true) const
message_filters::sync_policies::ApproximateTime< sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo > MyApproxSyncDepthPolicy
Definition: rgbd_sync.cpp:222
bool sleep() const
const std::string & getName() const
void callback(const sensor_msgs::ImageConstPtr &image, const sensor_msgs::ImageConstPtr &depth, const sensor_msgs::CameraInfoConstPtr &cameraInfo)
Definition: rgbd_sync.cpp:156
image_transport::SubscriberFilter imageSub_
Definition: rgbd_sync.cpp:218
virtual void onInit()
Definition: rgbd_sync.cpp:84
#define ROS_WARN(...)
ros::Publisher rgbdImagePub_
Definition: rgbd_sync.cpp:215
message_filters::Synchronizer< MyExactSyncDepthPolicy > * exactSyncDepth_
Definition: rgbd_sync.cpp:226
ros::NodeHandle & getPrivateNodeHandle() const
std::vector< unsigned char > RTABMAP_EXP compressImage(const cv::Mat &image, const std::string &format=".png")
bool param(const std::string &param_name, T &param_val, const T &default_val) const
void warningLoop(const std::string &subscribedTopicsMsg, bool approxSync)
Definition: rgbd_sync.cpp:137
CvImagePtr toCvCopy(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
ros::NodeHandle & getNodeHandle() const
void subscribe(ImageTransport &it, const std::string &base_topic, uint32_t queue_size, const TransportHints &transport_hints=TransportHints())
#define false
#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)
image_transport::SubscriberFilter imageDepthSub_
Definition: rgbd_sync.cpp:219
PLUGINLIB_EXPORT_CLASS(rtabmap_ros::CoreWrapper, nodelet::Nodelet)
boost::thread * warningThread_
Definition: rgbd_sync.cpp:212
message_filters::Subscriber< sensor_msgs::CameraInfo > cameraInfoSub_
Definition: rgbd_sync.cpp:220
r
std::string getTopic() const
ros::Publisher rgbdImageCompressedPub_
Definition: rgbd_sync.cpp:216


rtabmap_ros
Author(s): Mathieu Labbe
autogenerated on Fri Jun 7 2019 21:55:04