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_msgs/RGBDImage.h"
50 
53 
55 
56 namespace rtabmap_sync
57 {
58 
59 class RgbSync : public nodelet::Nodelet
60 {
61 public:
62  RgbSync() :
63  compressedRate_(0),
64  approxSync_(0),
65  exactSync_(0)
66  {}
67 
68  virtual ~RgbSync()
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  pnh.param("approx_sync_max_interval", approxSyncMaxInterval, approxSyncMaxInterval);
86  pnh.param("topic_queue_size", queueSize, queueSize);
87  if(pnh.hasParam("queue_size") && !pnh.hasParam("sync_queue_size"))
88  {
89  pnh.param("queue_size", syncQueueSize, syncQueueSize);
90  ROS_WARN("Parameter \"queue_size\" has been renamed "
91  "to \"sync_queue_size\" and will be removed "
92  "in future versions! The value (%d) is copied to "
93  "\"sync_queue_size\".", syncQueueSize);
94  }
95  else
96  {
97  pnh.param("sync_queue_size", syncQueueSize, syncQueueSize);
98  }
99  pnh.param("compressed_rate", compressedRate_, compressedRate_);
100 
101  NODELET_INFO("%s: approx_sync = %s", getName().c_str(), approxSync?"true":"false");
102  if(approxSync)
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(&RgbSync::callback, this, boost::placeholders::_1, boost::placeholders::_2));
117  }
118  else
119  {
121  exactSync_->registerCallback(boost::bind(&RgbSync::callback, this, boost::placeholders::_1, boost::placeholders::_2));
122  }
123 
124  ros::NodeHandle rgb_nh(nh, "rgb");
125  ros::NodeHandle rgb_pnh(pnh, "rgb");
126  image_transport::ImageTransport rgb_it(rgb_nh);
127  image_transport::TransportHints hintsRgb("raw", ros::TransportHints(), rgb_pnh);
128 
129  imageSub_.subscribe(rgb_it, rgb_nh.resolveName("image_rect"), queueSize, hintsRgb);
130  cameraInfoSub_.subscribe(rgb_nh, "camera_info", queueSize);
131 
132  std::string subscribedTopicsMsg = uFormat("\n%s subscribed to (%s sync%s):\n %s \\\n %s",
133  getName().c_str(),
134  approxSync?"approx":"exact",
135  approxSync&&approxSyncMaxInterval!=std::numeric_limits<double>::max()?uFormat(", max interval=%fs", approxSyncMaxInterval).c_str():"",
136  imageSub_.getTopic().c_str(),
137  cameraInfoSub_.getTopic().c_str());
138  NODELET_INFO("%s", subscribedTopicsMsg.c_str());
139 
140  syncDiagnostic_.reset(new SyncDiagnostic(nh, pnh, getName()));
141  syncDiagnostic_->init(rgb_nh.resolveName("image_rect"),
142  uFormat("%s: Did not receive data since 5 seconds! Make sure the input topics are "
143  "published (\"$ rostopic hz my_topic\") and the timestamps in their "
144  "header are set. %s%s",
145  getName().c_str(),
146  approxSync?"":"Parameter \"approx_sync\" is false, which means that input "
147  "topics should have all the exact timestamp for the callback to be called.",
148  subscribedTopicsMsg.c_str()));
149  }
150 
151  void callback(
152  const sensor_msgs::ImageConstPtr& image,
153  const sensor_msgs::CameraInfoConstPtr& cameraInfo)
154  {
155  syncDiagnostic_->tick(image->header.stamp);
156 
158  {
159  double stamp = image->header.stamp.toSec();
160 
161  rtabmap_msgs::RGBDImage msg;
162  msg.header.frame_id = cameraInfo->header.frame_id;
163  msg.header.stamp = image->header.stamp;
164  msg.rgb_camera_info = *cameraInfo;
165 
167  {
168  bool publishCompressed = true;
169  if (compressedRate_ > 0.0)
170  {
172  {
173  NODELET_DEBUG("throttle last update at %f skipping", lastCompressedPublished_.toSec());
174  publishCompressed = false;
175  }
176  }
177 
178  if(publishCompressed)
179  {
181 
182  rtabmap_msgs::RGBDImage msgCompressed = msg;
183 
185  imagePtr->toCompressedImageMsg(msgCompressed.rgb_compressed, cv_bridge::JPG);
186 
187  rgbdImageCompressedPub_.publish(msgCompressed);
188  }
189  }
190 
192  {
193  msg.rgb = *image;
195  }
196 
197  if( stamp != image->header.stamp.toSec())
198  {
199  NODELET_ERROR("Input stamps changed between the beginning and the end of the callback! Make "
200  "sure the node publishing the topics doesn't override the same data after publishing them. A "
201  "solution is to use this node within another nodelet manager. Stamps: "
202  "%f->%f",
203  stamp, image->header.stamp.toSec());
204  }
205  }
206  }
207 
208 private:
211 
214 
217 
220 
223 
224  std::unique_ptr<SyncDiagnostic> syncDiagnostic_;
225 };
226 
228 }
229 
rtabmap_sync::RgbSync::compressedRate_
double compressedRate_
Definition: rgb_sync.cpp:209
image_transport::SubscriberFilter
rtabmap_sync::RgbSync::imageSub_
image_transport::SubscriberFilter imageSub_
Definition: rgb_sync.cpp:215
rtabmap_sync::RgbSync::RgbSync
RgbSync()
Definition: rgb_sync.cpp:62
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::RgbSync::~RgbSync
virtual ~RgbSync()
Definition: rgb_sync.cpp:68
rtabmap_sync::RgbSync::lastCompressedPublished_
ros::Time lastCompressedPublished_
Definition: rgb_sync.cpp:210
rtabmap_sync
Definition: CommonDataSubscriber.h:59
uFormat
std::string uFormat(const char *fmt,...)
ros.h
rtabmap_sync::SyncDiagnostic
Definition: SyncDiagnostic.h:13
Compression.h
rtabmap_sync::RgbSync::MyApproxSyncPolicy
message_filters::sync_policies::ApproximateTime< sensor_msgs::Image, sensor_msgs::CameraInfo > MyApproxSyncPolicy
Definition: rgb_sync.cpp:218
rtabmap_sync::RgbSync::cameraInfoSub_
message_filters::Subscriber< sensor_msgs::CameraInfo > cameraInfoSub_
Definition: rgb_sync.cpp:216
SyncDiagnostic.h
ros::TransportHints
TimeBase< Time, Duration >::toSec
double toSec() const
image_transport::SubscriberFilter::subscribe
void subscribe(ImageTransport &it, const std::string &base_topic, uint32_t queue_size, const TransportHints &transport_hints=TransportHints())
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
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
subscriber.h
max
GLM_FUNC_DECL genType max(genType const &x, genType const &y)
rtabmap_sync::RgbSync::MyExactSyncPolicy
message_filters::sync_policies::ExactTime< sensor_msgs::Image, sensor_msgs::CameraInfo > MyExactSyncPolicy
Definition: rgb_sync.cpp:221
ros::NodeHandle::hasParam
bool hasParam(const std::string &key) const
ROS_WARN
#define ROS_WARN(...)
image_transport.h
exact_time.h
message_filters::Subscriber::subscribe
void subscribe()
NODELET_INFO
#define NODELET_INFO(...)
rtabmap_sync::RgbSync::exactSync_
message_filters::Synchronizer< MyExactSyncPolicy > * exactSync_
Definition: rgb_sync.cpp:222
nodelet::Nodelet
rtabmap_sync::RgbSync::syncDiagnostic_
std::unique_ptr< SyncDiagnostic > syncDiagnostic_
Definition: rgb_sync.cpp:224
rtabmap_sync::RgbSync::callback
void callback(const sensor_msgs::ImageConstPtr &image, const sensor_msgs::CameraInfoConstPtr &cameraInfo)
Definition: rgb_sync.cpp:151
ros::Time
nodelet.h
c_str
const char * c_str(Args &&...args)
cv_bridge.h
class_list_macros.hpp
rtabmap_sync::RgbSync::approxSync_
message_filters::Synchronizer< MyApproxSyncPolicy > * approxSync_
Definition: rgb_sync.cpp:219
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
rtabmap_sync::RgbSync::onInit
virtual void onInit()
Definition: rgb_sync.cpp:75
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::RgbSync::rgbdImageCompressedPub_
ros::Publisher rgbdImageCompressedPub_
Definition: rgb_sync.cpp:213
ros::Duration
rtabmap_sync::RgbSync::rgbdImagePub_
ros::Publisher rgbdImagePub_
Definition: rgb_sync.cpp:212
ros::NodeHandle
NODELET_DEBUG
#define NODELET_DEBUG(...)
ros::Time::now
static Time now()
rtabmap_sync::RgbSync
Definition: rgb_sync.cpp:59


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