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  if(private_nh.getParam("max_rate", rate_))
93  {
94  NODELET_WARN("\"max_rate\" is now known as \"rate\".");
95  }
96  private_nh.param("rate", rate_, rate_);
97  private_nh.param("queue_size", queueSize, queueSize);
98  private_nh.param("approx_sync", approxSync, approxSync);
99  private_nh.param("decimation", decimation_, decimation_);
100  ROS_ASSERT(decimation_ >= 1);
101  NODELET_INFO("Rate=%f Hz", rate_);
102  NODELET_INFO("Decimation=%d", decimation_);
103  NODELET_INFO("Approximate time sync = %s", approxSync?"true":"false");
104 
105  if(approxSync)
106  {
108  approxSync_->registerCallback(boost::bind(&DataThrottleNodelet::callback, this, _1, _2, _3));
109  }
110  else
111  {
113  exactSync_->registerCallback(boost::bind(&DataThrottleNodelet::callback, this, _1, _2, _3));
114  }
115 
116  image_sub_.subscribe(rgb_it, rgb_nh.resolveName("image_in"), 1, hintsRgb);
117  image_depth_sub_.subscribe(depth_it, depth_nh.resolveName("image_in"), 1, hintsDepth);
118  info_sub_.subscribe(rgb_nh, "camera_info_in", 1);
119 
120  imagePub_ = rgb_it.advertise("image_out", 1);
121  imageDepthPub_ = depth_it.advertise("image_out", 1);
122  infoPub_ = rgb_nh.advertise<sensor_msgs::CameraInfo>("camera_info_out", 1);
123  };
124 
125  void callback(const sensor_msgs::ImageConstPtr& image,
126  const sensor_msgs::ImageConstPtr& imageDepth,
127  const sensor_msgs::CameraInfoConstPtr& camInfo)
128  {
129  if (rate_ > 0.0)
130  {
131  NODELET_DEBUG("update set to %f", rate_);
132  if ( last_update_ + ros::Duration(1.0/rate_) > ros::Time::now())
133  {
134  NODELET_DEBUG("throttle last update at %f skipping", last_update_.toSec());
135  return;
136  }
137  }
138  else
139  NODELET_DEBUG("rate unset continuing");
140 
141  last_update_ = ros::Time::now();
142 
144  {
145  if(decimation_ > 1)
146  {
148  cv_bridge::CvImage out;
149  out.header = imagePtr->header;
150  out.encoding = imagePtr->encoding;
151  out.image = rtabmap::util2d::decimate(imagePtr->image, decimation_);
153  }
154  else
155  {
156  imagePub_.publish(image);
157  }
158  }
160  {
161  if(decimation_ > 1)
162  {
163  cv_bridge::CvImageConstPtr imagePtr = cv_bridge::toCvShare(imageDepth);
164  cv_bridge::CvImage out;
165  out.header = imagePtr->header;
166  out.encoding = imagePtr->encoding;
167  out.image = rtabmap::util2d::decimate(imagePtr->image, decimation_);
169  }
170  else
171  {
172  imageDepthPub_.publish(imageDepth);
173  }
174  }
176  {
177  if(decimation_ > 1)
178  {
179  sensor_msgs::CameraInfo info = *camInfo;
180  info.height /= decimation_;
181  info.width /= decimation_;
182  info.roi.height /= decimation_;
183  info.roi.width /= decimation_;
184  info.K[2]/=float(decimation_); // cx
185  info.K[5]/=float(decimation_); // cy
186  info.K[0]/=float(decimation_); // fx
187  info.K[4]/=float(decimation_); // fy
188  info.P[2]/=float(decimation_); // cx
189  info.P[6]/=float(decimation_); // cy
190  info.P[0]/=float(decimation_); // fx
191  info.P[5]/=float(decimation_); // fy
192  infoPub_.publish(info);
193  }
194  else
195  {
196  infoPub_.publish(camInfo);
197  }
198  }
199  }
200 
204 
208 
213 
215 
216 };
217 
218 
220 }
CvImageConstPtr toCvShare(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
#define NODELET_WARN(...)
void publish(const boost::shared_ptr< M > &message) const
message_filters::Synchronizer< MyApproxSyncPolicy > * approxSync_
image_transport::Publisher imagePub_
std::string resolveName(const std::string &name, bool remap=true) 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_
uint32_t getNumSubscribers() const
ros::NodeHandle & getPrivateNodeHandle() const
void callback(const sensor_msgs::ImageConstPtr &image, const sensor_msgs::ImageConstPtr &imageDepth, const sensor_msgs::CameraInfoConstPtr &camInfo)
void publish(const sensor_msgs::Image &message) const
cv::Mat RTABMAP_EXP decimate(const cv::Mat &image, int d)
image_transport::SubscriberFilter image_sub_
bool param(const std::string &param_name, T &param_val, const T &default_val) 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)
ros::NodeHandle & getNodeHandle() 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(...)
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)
bool getParam(const std::string &key, std::string &s) const
static Time now()
PLUGINLIB_EXPORT_CLASS(rtabmap_ros::CoreWrapper, nodelet::Nodelet)
#define ROS_ASSERT(cond)
#define NODELET_DEBUG(...)
sensor_msgs::ImagePtr toImageMsg() const
std_msgs::Header header


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