data_throttle.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 
36 
39 
40 #include <sensor_msgs/CameraInfo.h>
41 
42 #include <cv_bridge/cv_bridge.h>
43 
44 #include <rtabmap/core/util2d.h>
45 
46 namespace rtabmap_ros
47 {
48 
50 {
51 public:
52  //Constructor
54  rate_(0),
55  approxSync_(0),
56  exactSync_(0),
57  decimation_(1)
58  {
59  }
60 
62  {
63  if(approxSync_)
64  {
65  delete approxSync_;
66  }
67  if(exactSync_)
68  {
69  delete exactSync_;
70  }
71  }
72 
73 private:
75  double rate_;
76  virtual void onInit()
77  {
79  ros::NodeHandle& private_nh = getPrivateNodeHandle();
80 
81  ros::NodeHandle rgb_nh(nh, "rgb");
82  ros::NodeHandle depth_nh(nh, "depth");
83  ros::NodeHandle rgb_pnh(private_nh, "rgb");
84  ros::NodeHandle depth_pnh(private_nh, "depth");
85  image_transport::ImageTransport rgb_it(rgb_nh);
86  image_transport::ImageTransport depth_it(depth_nh);
87  image_transport::TransportHints hintsRgb("raw", ros::TransportHints(), rgb_pnh);
88  image_transport::TransportHints hintsDepth("raw", ros::TransportHints(), depth_pnh);
89 
90  int queueSize = 10;
91  bool approxSync = true;
92  double approxSyncMaxInterval = 0.0;
93  if(private_nh.getParam("max_rate", rate_))
94  {
95  NODELET_WARN("\"max_rate\" is now known as \"rate\".");
96  }
97  private_nh.param("rate", rate_, rate_);
98  private_nh.param("queue_size", queueSize, queueSize);
99  private_nh.param("approx_sync", approxSync, approxSync);
100  private_nh.param("approx_sync_max_interval", approxSyncMaxInterval, approxSyncMaxInterval);
101  private_nh.param("decimation", decimation_, decimation_);
102  ROS_ASSERT(decimation_ >= 1);
103  NODELET_INFO("rate=%f Hz", rate_);
104  NODELET_INFO("decimation=%d", decimation_);
105  NODELET_INFO("approx_sync = %s", approxSync?"true":"false");
106  if(approxSync)
107  NODELET_INFO("approx_sync_max_interval = %f", approxSyncMaxInterval);
108 
109  if(approxSync)
110  {
112  if(approxSyncMaxInterval > 0.0)
113  approxSync_->setMaxIntervalDuration(ros::Duration(approxSyncMaxInterval));
114  approxSync_->registerCallback(boost::bind(&DataThrottleNodelet::callback, this, boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3));
115  }
116  else
117  {
119  exactSync_->registerCallback(boost::bind(&DataThrottleNodelet::callback, this, boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3));
120  }
121 
122  image_sub_.subscribe(rgb_it, rgb_nh.resolveName("image_in"), 1, hintsRgb);
123  image_depth_sub_.subscribe(depth_it, depth_nh.resolveName("image_in"), 1, hintsDepth);
124  info_sub_.subscribe(rgb_nh, "camera_info_in", 1);
125 
126  imagePub_ = rgb_it.advertise("image_out", 1);
127  imageDepthPub_ = depth_it.advertise("image_out", 1);
128  infoPub_ = rgb_nh.advertise<sensor_msgs::CameraInfo>("camera_info_out", 1);
129  };
130 
131  void callback(const sensor_msgs::ImageConstPtr& image,
132  const sensor_msgs::ImageConstPtr& imageDepth,
133  const sensor_msgs::CameraInfoConstPtr& camInfo)
134  {
135  if (rate_ > 0.0)
136  {
137  NODELET_DEBUG("update set to %f", rate_);
138  if ( last_update_ + ros::Duration(1.0/rate_) > ros::Time::now())
139  {
140  NODELET_DEBUG("throttle last update at %f skipping", last_update_.toSec());
141  return;
142  }
143  }
144  else
145  NODELET_DEBUG("rate unset continuing");
146 
147  last_update_ = ros::Time::now();
148 
149  double rgbStamp = image->header.stamp.toSec();
150  double depthStamp = imageDepth->header.stamp.toSec();
151  double infoStamp = camInfo->header.stamp.toSec();
152 
154  {
155  if(decimation_ > 1)
156  {
157  sensor_msgs::CameraInfo info = *camInfo;
158  info.height /= decimation_;
159  info.width /= decimation_;
160  info.roi.height /= decimation_;
161  info.roi.width /= decimation_;
162  info.K[2]/=float(decimation_); // cx
163  info.K[5]/=float(decimation_); // cy
164  info.K[0]/=float(decimation_); // fx
165  info.K[4]/=float(decimation_); // fy
166  info.P[2]/=float(decimation_); // cx
167  info.P[6]/=float(decimation_); // cy
168  info.P[0]/=float(decimation_); // fx
169  info.P[5]/=float(decimation_); // fy
170  infoPub_.publish(info);
171  }
172  else
173  {
174  infoPub_.publish(camInfo);
175  }
176  }
178  {
179  if(decimation_ > 1)
180  {
182  cv_bridge::CvImage out;
183  out.header = imagePtr->header;
184  out.encoding = imagePtr->encoding;
185  out.image = rtabmap::util2d::decimate(imagePtr->image, decimation_);
187  }
188  else
189  {
190  imagePub_.publish(image);
191  }
192  }
193 
195  {
196  if(decimation_ > 1)
197  {
198  cv_bridge::CvImageConstPtr imagePtr = cv_bridge::toCvShare(imageDepth);
199  cv_bridge::CvImage out;
200  out.header = imagePtr->header;
201  out.encoding = imagePtr->encoding;
202  out.image = rtabmap::util2d::decimate(imagePtr->image, decimation_);
204  }
205  else
206  {
207  imageDepthPub_.publish(imageDepth);
208  }
209  }
210 
211  if( rgbStamp != image->header.stamp.toSec() ||
212  depthStamp != imageDepth->header.stamp.toSec())
213  {
214  NODELET_ERROR("Input stamps changed between the beginning and the end of the callback! Make "
215  "sure the node publishing the topics doesn't override the same data after publishing them. A "
216  "solution is to use this node within another nodelet manager. Stamps: "
217  "rgb=%f->%f depth=%f->%f",
218  rgbStamp, image->header.stamp.toSec(),
219  depthStamp, imageDepth->header.stamp.toSec());
220  }
221  }
222 
226 
230 
235 
237 
238 };
239 
240 
242 }
CvImageConstPtr toCvShare(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
#define NODELET_ERROR(...)
#define NODELET_WARN(...)
message_filters::Synchronizer< MyApproxSyncPolicy > * approxSync_
uint32_t getNumSubscribers() const
image_transport::Publisher imagePub_
ros::NodeHandle & getNodeHandle() const
std::string encoding
Publisher advertise(const std::string &base_topic, uint32_t queue_size, bool latch=false)
message_filters::Synchronizer< MyExactSyncPolicy > * exactSync_
message_filters::Subscriber< sensor_msgs::CameraInfo > info_sub_
ros::NodeHandle & getPrivateNodeHandle() 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
void callback(const sensor_msgs::ImageConstPtr &image, const sensor_msgs::ImageConstPtr &imageDepth, const sensor_msgs::CameraInfoConstPtr &camInfo)
cv::Mat RTABMAP_EXP decimate(const cv::Mat &image, int d)
image_transport::SubscriberFilter image_sub_
bool getParam(const std::string &key, std::string &s) 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 > MyApproxSyncPolicy
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
void publish(const sensor_msgs::Image &message) const
image_transport::Publisher imageDepthPub_
void subscribe(ImageTransport &it, const std::string &base_topic, uint32_t queue_size, const TransportHints &transport_hints=TransportHints())
image_transport::SubscriberFilter image_depth_sub_
message_filters::sync_policies::ExactTime< sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo > MyExactSyncPolicy
#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)
static Time now()
PLUGINLIB_EXPORT_CLASS(rtabmap_ros::CoreWrapper, nodelet::Nodelet)
#define ROS_ASSERT(cond)
uint32_t getNumSubscribers() const
#define NODELET_DEBUG(...)
std_msgs::Header header


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