disparity.cpp
Go to the documentation of this file.
1 /*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2008, Willow Garage, Inc.
5 * All rights reserved.
6 *
7 * Redistribution and use in source and binary forms, with or without
8 * modification, are permitted provided that the following conditions
9 * are met:
10 *
11 * * Redistributions of source code must retain the above copyright
12 * notice, this list of conditions and the following disclaimer.
13 * * Redistributions in binary form must reproduce the above
14 * copyright notice, this list of conditions and the following
15 * disclaimer in the documentation and/or other materials provided
16 * with the distribution.
17 * * Neither the name of the Willow Garage nor the names of its
18 * contributors may be used to endorse or promote products derived
19 * from this software without specific prior written permission.
20 *
21 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32 * POSSIBILITY OF SUCH DAMAGE.
33 *********************************************************************/
34 #include <boost/version.hpp>
35 #if ((BOOST_VERSION / 100) % 1000) >= 53
36 #include <boost/thread/lock_guard.hpp>
37 #endif
38 
39 #include <ros/ros.h>
40 #include <nodelet/nodelet.h>
47 
49 #include <opencv2/calib3d/calib3d.hpp>
50 #include <cv_bridge/cv_bridge.h>
51 
53 #include <stereo_msgs/DisparityImage.h>
54 
55 #include <stereo_image_proc/DisparityConfig.h>
56 #include <dynamic_reconfigure/server.h>
57 
59 
60 namespace stereo_image_proc {
61 
62 using namespace sensor_msgs;
63 using namespace stereo_msgs;
64 using namespace message_filters::sync_policies;
65 
66 class DisparityNodelet : public nodelet::Nodelet
67 {
69 
70  // Subscriptions
71  image_transport::SubscriberFilter sub_l_image_, sub_r_image_;
72  message_filters::Subscriber<CameraInfo> sub_l_info_, sub_r_info_;
77  boost::shared_ptr<ExactSync> exact_sync_;
78  boost::shared_ptr<ApproximateSync> approximate_sync_;
79  // Publications
80  boost::mutex connect_mutex_;
81  ros::Publisher pub_disparity_;
82 
83  // Dynamic reconfigure
84  boost::recursive_mutex config_mutex_;
85  typedef stereo_image_proc::DisparityConfig Config;
86  typedef dynamic_reconfigure::Server<Config> ReconfigureServer;
87  boost::shared_ptr<ReconfigureServer> reconfigure_server_;
88  int downsampling_factor_;
89 
90  // Processing state (note: only safe because we're single-threaded!)
92  stereo_image_proc::StereoProcessor block_matcher_; // contains scratch buffers for block matching
93 
94  virtual void onInit();
95 
96  void connectCb();
97 
98  void imageCb(const ImageConstPtr& l_image_msg, const CameraInfoConstPtr& l_info_msg,
99  const ImageConstPtr& r_image_msg, const CameraInfoConstPtr& r_info_msg);
100 
101  void configCb(Config &config, uint32_t level);
102 };
103 
105 {
106  ros::NodeHandle &nh = getNodeHandle();
107  ros::NodeHandle &private_nh = getPrivateNodeHandle();
108 
110 
111  // Synchronize inputs. Topic subscriptions happen on demand in the connection
112  // callback. Optionally do approximate synchronization.
113  int queue_size;
114  private_nh.param("queue_size", queue_size, 5);
115  bool approx;
116  private_nh.param("approximate_sync", approx, false);
117  private_nh.param("downsampling_factor", downsampling_factor_, 1);
118  if (approx)
119  {
120  approximate_sync_.reset( new ApproximateSync(ApproximatePolicy(queue_size),
121  sub_l_image_, sub_l_info_,
122  sub_r_image_, sub_r_info_) );
123  approximate_sync_->registerCallback(boost::bind(&DisparityNodelet::imageCb,
124  this, boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3, boost::placeholders::_4));
125  }
126  else
127  {
128  exact_sync_.reset( new ExactSync(ExactPolicy(queue_size),
129  sub_l_image_, sub_l_info_,
130  sub_r_image_, sub_r_info_) );
131  exact_sync_->registerCallback(boost::bind(&DisparityNodelet::imageCb,
132  this, boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3, boost::placeholders::_4));
133  }
134 
135  // Set up dynamic reconfiguration
136  ReconfigureServer::CallbackType f = boost::bind(&DisparityNodelet::configCb,
137  this, boost::placeholders::_1, boost::placeholders::_2);
138  reconfigure_server_.reset(new ReconfigureServer(config_mutex_, private_nh));
139  reconfigure_server_->setCallback(f);
140 
141  // Monitor whether anyone is subscribed to the output
142  ros::SubscriberStatusCallback connect_cb = boost::bind(&DisparityNodelet::connectCb, this);
143  // Make sure we don't enter connectCb() between advertising and assigning to pub_disparity_
144  boost::lock_guard<boost::mutex> lock(connect_mutex_);
145  pub_disparity_ = nh.advertise<DisparityImage>("disparity", 1, connect_cb, connect_cb);
146 }
147 
148 // Handles (un)subscribing when clients (un)subscribe
150 {
151  boost::lock_guard<boost::mutex> lock(connect_mutex_);
152  if (pub_disparity_.getNumSubscribers() == 0)
153  {
154  sub_l_image_.unsubscribe();
155  sub_l_info_ .unsubscribe();
156  sub_r_image_.unsubscribe();
157  sub_r_info_ .unsubscribe();
158  }
159  else if (!sub_l_image_.getSubscriber())
160  {
161  ros::NodeHandle &nh = getNodeHandle();
162  // Queue size 1 should be OK; the one that matters is the synchronizer queue size.
164  image_transport::TransportHints hints("raw", ros::TransportHints(), getPrivateNodeHandle());
165  sub_l_image_.subscribe(*it_, "left/image_rect", 1, hints);
166  sub_l_info_ .subscribe(nh, "left/camera_info", 1);
167  sub_r_image_.subscribe(*it_, "right/image_rect", 1, hints);
168  sub_r_info_ .subscribe(nh, "right/camera_info", 1);
169  }
170 }
171 
172 cv::Mat subsampleTheImage(
173  const cv::Mat& input_image,
174  const uint32_t downsample_factor_per_dimension) {
175  cv::Mat blurred_image;
176  const int32_t kernel_size = 2 * downsample_factor_per_dimension + 1;
177  cv::GaussianBlur(
178  input_image, blurred_image, cv::Size(kernel_size, kernel_size),
179  downsample_factor_per_dimension);
180 
181  // To avoid computational effort of bilinear interpolation, perform
182  // interpolation manually.
183  uint32_t downsampled_height = std::ceil(
184  input_image.size().height /
185  static_cast<double>(downsample_factor_per_dimension));
186  uint32_t downsampled_width = std::ceil(
187  input_image.size().width /
188  static_cast<double>(downsample_factor_per_dimension));
189  cv::Mat downsampled_image(
190  downsampled_height, downsampled_width, input_image.type());
191 
192  for (uint32_t destination_row = 0u;
193  destination_row < downsampled_image.size().height; destination_row++) {
194  for (uint32_t destination_col = 0u;
195  destination_col < downsampled_image.size().width; destination_col++) {
196  downsampled_image.at<uint8_t>(destination_row, destination_col) =
197  blurred_image.at<uint8_t>(
198  destination_row * downsample_factor_per_dimension,
199  destination_col * downsample_factor_per_dimension);
200  }
201  }
202  return downsampled_image;
203 }
204 
206  const cv::Mat& disparity, const cv::Size& destination_size,
207  const uint32_t upsample_factor_per_dimension) {
208  cv::Mat upsampled_disparity(destination_size, disparity.type(), -1.);
209 
210  for (uint32_t destination_row = 0u;
211  destination_row < upsampled_disparity.size().height; destination_row++) {
212  for (uint32_t destination_col = 0u;
213  destination_col < upsampled_disparity.size().width;
214  destination_col++) {
215  upsampled_disparity.at<float>(destination_row, destination_col) =
216  upsample_factor_per_dimension *
217  disparity.at<float>(
218  destination_row / upsample_factor_per_dimension,
219  destination_col / upsample_factor_per_dimension);
220  }
221  }
222  return upsampled_disparity;
223 }
224 
225 void DisparityNodelet::imageCb(const ImageConstPtr& l_image_msg,
226  const CameraInfoConstPtr& l_info_msg,
227  const ImageConstPtr& r_image_msg,
228  const CameraInfoConstPtr& r_info_msg)
229 {
230  // Update the camera model
231  model_.fromCameraInfo(l_info_msg, r_info_msg);
232 
233  // Allocate new disparity image message
234  DisparityImagePtr disp_msg = boost::make_shared<DisparityImage>();
235  disp_msg->header = l_info_msg->header;
236  disp_msg->header.frame_id = l_image_msg->header.frame_id;
237  disp_msg->image.header = l_info_msg->header;
238  disp_msg->image.header.frame_id = l_image_msg->header.frame_id;
239 
240  // Compute window of (potentially) valid disparities
241  int border = block_matcher_.getCorrelationWindowSize() / 2;
242  int left = block_matcher_.getDisparityRange() + block_matcher_.getMinDisparity() + border - 1;
243  int wtf = (block_matcher_.getMinDisparity() >= 0) ? border + block_matcher_.getMinDisparity() : std::max(border, -block_matcher_.getMinDisparity());
244  int right = disp_msg->image.width - 1 - wtf;
245  int top = border;
246  int bottom = disp_msg->image.height - 1 - border;
247  disp_msg->valid_window.x_offset = left;
248  disp_msg->valid_window.y_offset = top;
249  disp_msg->valid_window.width = right - left;
250  disp_msg->valid_window.height = bottom - top;
251 
252  // Create cv::Mat views onto all buffers
253  const cv::Mat_<uint8_t> l_image = cv_bridge::toCvShare(l_image_msg, sensor_msgs::image_encodings::MONO8)->image;
254  const cv::Mat_<uint8_t> r_image = cv_bridge::toCvShare(r_image_msg, sensor_msgs::image_encodings::MONO8)->image;
255 
256  cv::Mat_<uint8_t> l_sub_image;
257  cv::Mat_<uint8_t> r_sub_image;
258 
259  if (downsampling_factor_ != 1) {
260  l_sub_image = subsampleTheImage(l_image, downsampling_factor_);
261  r_sub_image = subsampleTheImage(r_image, downsampling_factor_);
262  } else {
263  l_sub_image = l_image;
264  r_sub_image = r_image;
265  }
266 
267  // Perform block matching to find the disparities
268  block_matcher_.processDisparity(l_sub_image, r_sub_image, model_, *disp_msg);
269 
270  // Upsampling
271  if (downsampling_factor_ != 1) {
272  const cv::Mat disp_subsampled_image =
274  disp_msg->image, disp_msg, sensor_msgs::image_encodings::TYPE_32FC1)
275  ->image;
276  const cv::Mat disp_upsampled_image =
278  disp_subsampled_image, l_image.size(), downsampling_factor_);
279  const cv_bridge::CvImage disp_image_container = cv_bridge::CvImage(
281  disp_upsampled_image);
282  disp_image_container.toImageMsg(disp_msg->image);
283  }
284 
285  // Adjust for any x-offset between the principal points: d' = d - (cx_l - cx_r)
286  double cx_l = model_.left().cx();
287  double cx_r = model_.right().cx();
288  if (cx_l != cx_r) {
289  cv::Mat_<float> disp_image(disp_msg->image.height, disp_msg->image.width,
290  reinterpret_cast<float*>(&disp_msg->image.data[0]),
291  disp_msg->image.step);
292  cv::subtract(disp_image, cv::Scalar(cx_l - cx_r), disp_image);
293  }
294 
295  pub_disparity_.publish(disp_msg);
296 }
297 
298 void DisparityNodelet::configCb(Config &config, uint32_t level)
299 {
300  // Tweak all settings to be valid
301  config.prefilter_size |= 0x1; // must be odd
302  config.correlation_window_size |= 0x1; // must be odd
303  config.disparity_range = (config.disparity_range / 16) * 16; // must be multiple of 16
304 
305  // check stereo method
306  // Note: With single-threaded NodeHandle, configCb and imageCb can't be called
307  // concurrently, so this is thread-safe.
308  block_matcher_.setPreFilterCap(config.prefilter_cap);
309  block_matcher_.setCorrelationWindowSize(config.correlation_window_size);
310  block_matcher_.setMinDisparity(config.min_disparity);
311  block_matcher_.setDisparityRange(config.disparity_range);
312  block_matcher_.setUniquenessRatio(config.uniqueness_ratio);
313  block_matcher_.setSpeckleSize(config.speckle_size);
314  block_matcher_.setSpeckleRange(config.speckle_range);
315  if (config.stereo_algorithm == stereo_image_proc::Disparity_StereoBM) { // StereoBM
316  block_matcher_.setStereoType(StereoProcessor::BM);
317  block_matcher_.setPreFilterSize(config.prefilter_size);
318  block_matcher_.setTextureThreshold(config.texture_threshold);
319  }
320  else if (config.stereo_algorithm == stereo_image_proc::Disparity_StereoSGBM) { // StereoSGBM
321  block_matcher_.setStereoType(StereoProcessor::SGBM);
322  block_matcher_.setSgbmMode(config.fullDP);
323  block_matcher_.setP1(config.P1);
324  block_matcher_.setP2(config.P2);
325  block_matcher_.setDisp12MaxDiff(config.disp12MaxDiff);
326  }
327 }
328 
329 } // namespace stereo_image_proc
330 
331 // Register nodelet
image_transport::SubscriberFilter
ros::Publisher
image_encodings.h
image_transport::ImageTransport
message_filters::Synchronizer
boost::shared_ptr< image_transport::ImageTransport >
cv_bridge::CvImage::toImageMsg
sensor_msgs::ImagePtr toImageMsg() const
ros.h
ros::TransportHints
stereo_image_proc::upsampleTheDisparityImageWithoutInterpolation
cv::Mat upsampleTheDisparityImageWithoutInterpolation(const cv::Mat &disparity, const cv::Size &destination_size, const uint32_t upsample_factor_per_dimension)
Definition: disparity.cpp:237
ros::SubscriberStatusCallback
boost::function< void(const SingleSubscriberPublisher &)> SubscriberStatusCallback
stereo_image_proc::subsampleTheImage
cv::Mat subsampleTheImage(const cv::Mat &input_image, const uint32_t downsample_factor_per_dimension)
Definition: disparity.cpp:204
ros::NodeHandle::advertise
Publisher advertise(AdvertiseOptions &ops)
stereo_camera_model.h
f
f
message_filters::Subscriber< CameraInfo >
message_filters::sync_policies::ApproximateTime
stereo_image_proc::DisparityNodelet::imageCb
void imageCb(const ImageConstPtr &l_image_msg, const CameraInfoConstPtr &l_info_msg, const ImageConstPtr &r_image_msg, const CameraInfoConstPtr &r_info_msg)
Definition: disparity.cpp:257
subscriber_filter.h
stereo_image_proc::StereoProcessor::BM
@ BM
Definition: processor.h:105
stereo_image_proc::StereoProcessor
Definition: processor.h:87
subscriber.h
processor.h
image_geometry::StereoCameraModel
stereo_image_proc::DisparityNodelet::configCb
void configCb(Config &config, uint32_t level)
Definition: disparity.cpp:330
image_transport.h
stereo_image_proc::DisparityNodelet::Config
stereo_image_proc::DisparityConfig Config
Definition: disparity.cpp:117
exact_time.h
stereo_image_proc::StereoProcessor::SGBM
@ SGBM
Definition: processor.h:105
message_filters::sync_policies
stereo_image_proc
Definition: processor.h:44
nodelet::Nodelet
sensor_msgs::image_encodings::TYPE_32FC1
const std::string TYPE_32FC1
PLUGINLIB_EXPORT_CLASS
PLUGINLIB_EXPORT_CLASS(image_proc::CropNonZeroNodelet, nodelet::Nodelet)
nodelet.h
sensor_msgs::image_encodings::MONO8
const std::string MONO8
stereo_image_proc::DisparityNodelet::ReconfigureServer
dynamic_reconfigure::Server< Config > ReconfigureServer
Definition: disparity.cpp:118
cv_bridge.h
stereo_image_proc::DisparityNodelet
Definition: disparity.cpp:98
cv_bridge::CvImage
class_list_macros.hpp
ros::NodeHandle::param
T param(const std::string &param_name, const T &default_val) const
stereo_image_proc::DisparityNodelet::onInit
virtual void onInit()
Definition: disparity.cpp:136
stereo_image_proc::DisparityNodelet::connectCb
void connectCb()
Definition: disparity.cpp:181
synchronizer.h
approximate_time.h
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
sensor_msgs
ros::NodeHandle


stereo_image_proc
Author(s): Patrick Mihelich, Kurt Konolige, Jeremy Leibs
autogenerated on Wed Jan 24 2024 03:57:24