rgb_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 RgbSync : public nodelet::Nodelet
58 {
59 public:
60  RgbSync() :
61  compressedRate_(0),
62  warningThread_(0),
64  approxSync_(0),
65  exactSync_(0)
66  {}
67 
68  virtual ~RgbSync()
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  pnh.param("approx_sync", approxSync, approxSync);
92  pnh.param("queue_size", queueSize, queueSize);
93  pnh.param("compressed_rate", compressedRate_, compressedRate_);
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: compressed_rate = %f", getName().c_str(), compressedRate_);
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  approxSync_->registerCallback(boost::bind(&RgbSync::callback, this, _1, _2));
106  }
107  else
108  {
110  exactSync_->registerCallback(boost::bind(&RgbSync::callback, this, _1, _2));
111  }
112 
113  ros::NodeHandle rgb_nh(nh, "rgb");
114  ros::NodeHandle rgb_pnh(pnh, "rgb");
115  image_transport::ImageTransport rgb_it(rgb_nh);
116  image_transport::TransportHints hintsRgb("raw", ros::TransportHints(), rgb_pnh);
117 
118  imageSub_.subscribe(rgb_it, rgb_nh.resolveName("image_rect"), 1, hintsRgb);
119  cameraInfoSub_.subscribe(rgb_nh, "camera_info", 1);
120 
121  std::string subscribedTopicsMsg = uFormat("\n%s subscribed to (%s sync):\n %s \\\n %s",
122  getName().c_str(),
123  approxSync?"approx":"exact",
124  imageSub_.getTopic().c_str(),
125  cameraInfoSub_.getTopic().c_str());
126 
127  warningThread_ = new boost::thread(boost::bind(&RgbSync::warningLoop, this, subscribedTopicsMsg, approxSync));
128  NODELET_INFO("%s", subscribedTopicsMsg.c_str());
129  }
130 
131  void warningLoop(const std::string & subscribedTopicsMsg, bool approxSync)
132  {
133  ros::Duration r(5.0);
134  while(!callbackCalled_)
135  {
136  r.sleep();
137  if(!callbackCalled_)
138  {
139  ROS_WARN("%s: Did not receive data since 5 seconds! Make sure the input topics are "
140  "published (\"$ rostopic hz my_topic\") and the timestamps in their "
141  "header are set. %s%s",
142  getName().c_str(),
143  approxSync?"":"Parameter \"approx_sync\" is false, which means that input "
144  "topics should have all the exact timestamp for the callback to be called.",
145  subscribedTopicsMsg.c_str());
146  }
147  }
148  }
149 
150  void callback(
151  const sensor_msgs::ImageConstPtr& image,
152  const sensor_msgs::CameraInfoConstPtr& cameraInfo)
153  {
154  callbackCalled_ = true;
156  {
157  double stamp = image->header.stamp.toSec();
158 
159  rtabmap_ros::RGBDImage msg;
160  msg.header.frame_id = cameraInfo->header.frame_id;
161  msg.header.stamp = image->header.stamp;
162  msg.rgb_camera_info = *cameraInfo;
163 
165  {
166  bool publishCompressed = true;
167  if (compressedRate_ > 0.0)
168  {
170  {
171  NODELET_DEBUG("throttle last update at %f skipping", lastCompressedPublished_.toSec());
172  publishCompressed = false;
173  }
174  }
175 
176  if(publishCompressed)
177  {
179 
180  rtabmap_ros::RGBDImage msgCompressed = msg;
181 
183  imagePtr->toCompressedImageMsg(msgCompressed.rgb_compressed, cv_bridge::JPG);
184 
185  rgbdImageCompressedPub_.publish(msgCompressed);
186  }
187  }
188 
190  {
191  msg.rgb = *image;
192  rgbdImagePub_.publish(msg);
193  }
194 
195  if( stamp != image->header.stamp.toSec())
196  {
197  NODELET_ERROR("Input stamps changed between the beginning and the end of the callback! Make "
198  "sure the node publishing the topics doesn't override the same data after publishing them. A "
199  "solution is to use this node within another nodelet manager. Stamps: "
200  "%f->%f",
201  stamp, image->header.stamp.toSec());
202  }
203  }
204  }
205 
206 private:
208  boost::thread * warningThread_;
211 
214 
217 
220 
223 };
224 
226 }
227 
boost::thread * warningThread_
Definition: rgb_sync.cpp:208
message_filters::sync_policies::ApproximateTime< sensor_msgs::Image, sensor_msgs::CameraInfo > MyApproxSyncPolicy
Definition: rgb_sync.cpp:218
CvImageConstPtr toCvShare(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
std::string getTopic() const
std::string uFormat(const char *fmt,...)
#define NODELET_ERROR(...)
void publish(const boost::shared_ptr< M > &message) const
void callback(const sensor_msgs::ImageConstPtr &image, const sensor_msgs::CameraInfoConstPtr &cameraInfo)
Definition: rgb_sync.cpp:150
message_filters::sync_policies::ExactTime< sensor_msgs::Image, sensor_msgs::CameraInfo > MyExactSyncPolicy
Definition: rgb_sync.cpp:221
message_filters::Synchronizer< MyExactSyncPolicy > * exactSync_
Definition: rgb_sync.cpp:222
std::string resolveName(const std::string &name, bool remap=true) const
void warningLoop(const std::string &subscribedTopicsMsg, bool approxSync)
Definition: rgb_sync.cpp:131
bool sleep() const
const std::string & getName() const
#define ROS_WARN(...)
virtual ~RgbSync()
Definition: rgb_sync.cpp:68
message_filters::Subscriber< sensor_msgs::CameraInfo > cameraInfoSub_
Definition: rgb_sync.cpp:216
ros::NodeHandle & getPrivateNodeHandle() const
bool param(const std::string &param_name, T &param_val, const T &default_val) const
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
image_transport::SubscriberFilter imageSub_
Definition: rgb_sync.cpp:215
#define NODELET_INFO(...)
uint32_t getNumSubscribers() const
ros::Time lastCompressedPublished_
Definition: rgb_sync.cpp:210
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)
message_filters::Synchronizer< MyApproxSyncPolicy > * approxSync_
Definition: rgb_sync.cpp:219
static Time now()
PLUGINLIB_EXPORT_CLASS(rtabmap_ros::CoreWrapper, nodelet::Nodelet)
virtual void onInit()
Definition: rgb_sync.cpp:84
r
#define NODELET_DEBUG(...)
std::string getTopic() const
ros::Publisher rgbdImageCompressedPub_
Definition: rgb_sync.cpp:213
ros::Publisher rgbdImagePub_
Definition: rgb_sync.cpp:212


rtabmap_ros
Author(s): Mathieu Labbe
autogenerated on Mon Dec 14 2020 03:42:19