stereo_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 
35 
38 
39 #include <sensor_msgs/CameraInfo.h>
40 
41 #include <cv_bridge/cv_bridge.h>
42 
43 #include <rtabmap/core/util2d.h>
44 
45 namespace rtabmap_ros
46 {
47 
49 {
50 public:
51  //Constructor
53  rate_(0),
54  approxSync_(0),
55  exactSync_(0),
56  decimation_(1)
57  {
58  }
59 
61  {
62  if(approxSync_)
63  {
64  delete approxSync_;
65  }
66  if(exactSync_)
67  {
68  delete exactSync_;
69  }
70  }
71 
72 private:
74  double rate_;
75  virtual void onInit()
76  {
79 
80  ros::NodeHandle left_nh(nh, "left");
81  ros::NodeHandle right_nh(nh, "right");
82  ros::NodeHandle left_pnh(pnh, "left");
83  ros::NodeHandle right_pnh(pnh, "right");
84  image_transport::ImageTransport left_it(left_nh);
85  image_transport::ImageTransport right_it(right_nh);
86  image_transport::TransportHints hintsLeft("raw", ros::TransportHints(), left_pnh);
87  image_transport::TransportHints hintsRight("raw", ros::TransportHints(), right_pnh);
88 
89  int queueSize = 5;
90  bool approxSync = false;
91  double approxSyncMaxInterval = 0.0;
92  pnh.param("approx_sync", approxSync, approxSync);
93  pnh.param("approx_sync_max_interval", approxSyncMaxInterval, approxSyncMaxInterval);
94  pnh.param("rate", rate_, rate_);
95  pnh.param("queue_size", queueSize, queueSize);
96  pnh.param("decimation", decimation_, decimation_);
97  ROS_ASSERT(decimation_ >= 1);
98  NODELET_INFO("rate=%f Hz", rate_);
99  NODELET_INFO("decimation=%d", decimation_);
100  NODELET_INFO("approx_sync = %s", approxSync?"true":"false");
101  if(approxSync)
102  NODELET_INFO("approx_sync_max_interval = %f", approxSyncMaxInterval);
103 
104  if(approxSync)
105  {
107  if(approxSyncMaxInterval>0.0)
108  approxSync_->setMaxIntervalDuration(ros::Duration(approxSyncMaxInterval));
109  approxSync_->registerCallback(boost::bind(&StereoThrottleNodelet::callback, this, boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3, boost::placeholders::_4));
110  }
111  else
112  {
114  exactSync_->registerCallback(boost::bind(&StereoThrottleNodelet::callback, this, boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3, boost::placeholders::_4));
115  }
116 
117  imageLeft_.subscribe(left_it, left_nh.resolveName("image"), 1, hintsLeft);
118  imageRight_.subscribe(right_it, right_nh.resolveName("image"), 1, hintsRight);
119  cameraInfoLeft_.subscribe(left_nh, "camera_info", 1);
120  cameraInfoRight_.subscribe(right_nh, "camera_info", 1);
121 
122  imageLeftPub_ = left_it.advertise(left_nh.resolveName("image")+"_throttle", 1);
123  imageRightPub_ = right_it.advertise(right_nh.resolveName("image")+"_throttle", 1);
124  infoLeftPub_ = left_nh.advertise<sensor_msgs::CameraInfo>(left_nh.resolveName("camera_info")+"_throttle", 1);
125  infoRightPub_ = right_nh.advertise<sensor_msgs::CameraInfo>(right_nh.resolveName("camera_info")+"_throttle", 1);
126  };
127 
128  void callback(const sensor_msgs::ImageConstPtr& imageLeft,
129  const sensor_msgs::ImageConstPtr& imageRight,
130  const sensor_msgs::CameraInfoConstPtr& camInfoLeft,
131  const sensor_msgs::CameraInfoConstPtr& camInfoRight)
132  {
133  if (rate_ > 0.0)
134  {
135  NODELET_DEBUG("update set to %f", rate_);
136  if ( last_update_ + ros::Duration(1.0/rate_) > ros::Time::now())
137  {
138  NODELET_DEBUG("throttle last update at %f skipping", last_update_.toSec());
139  return;
140  }
141  }
142  else
143  NODELET_DEBUG("rate unset continuing");
144 
145  last_update_ = ros::Time::now();
146 
147  double leftStamp = imageLeft->header.stamp.toSec();
148  double rightStamp = imageRight->header.stamp.toSec();
149  double leftInfoStamp = camInfoLeft->header.stamp.toSec();
150  double rightInfoStamp = camInfoRight->header.stamp.toSec();
151 
153  {
154  if(decimation_ > 1)
155  {
156  sensor_msgs::CameraInfo info = *camInfoLeft;
157  info.height /= decimation_;
158  info.width /= decimation_;
159  info.roi.height /= decimation_;
160  info.roi.width /= decimation_;
161  info.K[2]/=float(decimation_); // cx
162  info.K[5]/=float(decimation_); // cy
163  info.K[0]/=float(decimation_); // fx
164  info.K[4]/=float(decimation_); // fy
165  info.P[2]/=float(decimation_); // cx
166  info.P[6]/=float(decimation_); // cy
167  info.P[0]/=float(decimation_); // fx
168  info.P[5]/=float(decimation_); // fy
169  info.P[3]/=float(decimation_); // Tx
170  infoLeftPub_.publish(info);
171  }
172  else
173  {
174  infoLeftPub_.publish(camInfoLeft);
175  }
176  }
178  {
179  if(decimation_ > 1)
180  {
181  sensor_msgs::CameraInfo info = *camInfoRight;
182  info.height /= decimation_;
183  info.width /= decimation_;
184  info.roi.height /= decimation_;
185  info.roi.width /= decimation_;
186  info.K[2]/=float(decimation_); // cx
187  info.K[5]/=float(decimation_); // cy
188  info.K[0]/=float(decimation_); // fx
189  info.K[4]/=float(decimation_); // fy
190  info.P[2]/=float(decimation_); // cx
191  info.P[6]/=float(decimation_); // cy
192  info.P[0]/=float(decimation_); // fx
193  info.P[5]/=float(decimation_); // fy
194  info.P[3]/=float(decimation_); // Tx
195  infoRightPub_.publish(info);
196  }
197  else
198  {
199  infoRightPub_.publish(camInfoRight);
200  }
201  }
202 
203 
205  {
206  if(decimation_ > 1)
207  {
208  cv_bridge::CvImageConstPtr imagePtr = cv_bridge::toCvShare(imageLeft);
209  cv_bridge::CvImage out;
210  out.header = imagePtr->header;
211  out.encoding = imagePtr->encoding;
212  out.image = rtabmap::util2d::decimate(imagePtr->image, decimation_);
214  }
215  else
216  {
217  imageLeftPub_.publish(imageLeft);
218  }
219  }
221  {
222  if(decimation_ > 1)
223  {
224  cv_bridge::CvImageConstPtr imagePtr = cv_bridge::toCvShare(imageRight);
225  cv_bridge::CvImage out;
226  out.header = imagePtr->header;
227  out.encoding = imagePtr->encoding;
228  out.image = rtabmap::util2d::decimate(imagePtr->image, decimation_);
230  }
231  else
232  {
233  imageRightPub_.publish(imageRight);
234  }
235  }
236 
237  if( leftStamp != imageLeft->header.stamp.toSec() ||
238  rightStamp != imageRight->header.stamp.toSec())
239  {
240  NODELET_ERROR("Input stamps changed between the beginning and the end of the callback! Make "
241  "sure the node publishing the topics doesn't override the same data after publishing them. A "
242  "solution is to use this node within another nodelet manager. Stamps: "
243  "left%f->%f right=%f->%f",
244  leftStamp, imageLeft->header.stamp.toSec(),
245  rightStamp, imageRight->header.stamp.toSec());
246  }
247  }
248 
253 
258 
263 
265 
266 };
267 
268 
270 }
CvImageConstPtr toCvShare(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
#define NODELET_ERROR(...)
image_transport::Publisher imageLeftPub_
uint32_t getNumSubscribers() const
message_filters::Subscriber< sensor_msgs::CameraInfo > cameraInfoRight_
image_transport::SubscriberFilter imageRight_
ros::NodeHandle & getNodeHandle() const
std::string encoding
Publisher advertise(const std::string &base_topic, uint32_t queue_size, bool latch=false)
ros::NodeHandle & getPrivateNodeHandle() const
message_filters::sync_policies::ExactTime< sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo, sensor_msgs::CameraInfo > MyExactSyncPolicy
image_transport::SubscriberFilter imageLeft_
image_transport::Publisher imageRightPub_
void callback(const sensor_msgs::ImageConstPtr &imageLeft, const sensor_msgs::ImageConstPtr &imageRight, const sensor_msgs::CameraInfoConstPtr &camInfoLeft, const sensor_msgs::CameraInfoConstPtr &camInfoRight)
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
cv::Mat RTABMAP_EXP decimate(const cv::Mat &image, int d)
std::string resolveName(const std::string &name, bool remap=true) const
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
void publish(const sensor_msgs::Image &message) const
void subscribe(ImageTransport &it, const std::string &base_topic, uint32_t queue_size, const TransportHints &transport_hints=TransportHints())
#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)
message_filters::sync_policies::ApproximateTime< sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo, sensor_msgs::CameraInfo > MyApproxSyncPolicy
static Time now()
PLUGINLIB_EXPORT_CLASS(rtabmap_ros::CoreWrapper, nodelet::Nodelet)
message_filters::Synchronizer< MyApproxSyncPolicy > * approxSync_
#define ROS_ASSERT(cond)
message_filters::Subscriber< sensor_msgs::CameraInfo > cameraInfoLeft_
uint32_t getNumSubscribers() const
#define NODELET_DEBUG(...)
message_filters::Synchronizer< MyExactSyncPolicy > * exactSync_
std_msgs::Header header


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