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 
67 {
69 
70  // Subscriptions
79  // Publications
80  boost::mutex connect_mutex_;
82 
83  // Dynamic reconfigure
84  boost::recursive_mutex config_mutex_;
85  typedef stereo_image_proc::DisparityConfig Config;
86  typedef dynamic_reconfigure::Server<Config> ReconfigureServer;
88 
89  // Processing state (note: only safe because we're single-threaded!)
91  stereo_image_proc::StereoProcessor block_matcher_; // contains scratch buffers for block matching
92 
93  virtual void onInit();
94 
95  void connectCb();
96 
97  void imageCb(const ImageConstPtr& l_image_msg, const CameraInfoConstPtr& l_info_msg,
98  const ImageConstPtr& r_image_msg, const CameraInfoConstPtr& r_info_msg);
99 
100  void configCb(Config &config, uint32_t level);
101 };
102 
104 {
105  ros::NodeHandle &nh = getNodeHandle();
106  ros::NodeHandle &private_nh = getPrivateNodeHandle();
107 
108  it_.reset(new image_transport::ImageTransport(nh));
109 
110  // Synchronize inputs. Topic subscriptions happen on demand in the connection
111  // callback. Optionally do approximate synchronization.
112  int queue_size;
113  private_nh.param("queue_size", queue_size, 5);
114  bool approx;
115  private_nh.param("approximate_sync", approx, false);
116  if (approx)
117  {
118  approximate_sync_.reset( new ApproximateSync(ApproximatePolicy(queue_size),
119  sub_l_image_, sub_l_info_,
120  sub_r_image_, sub_r_info_) );
121  approximate_sync_->registerCallback(boost::bind(&DisparityNodelet::imageCb,
122  this, _1, _2, _3, _4));
123  }
124  else
125  {
126  exact_sync_.reset( new ExactSync(ExactPolicy(queue_size),
127  sub_l_image_, sub_l_info_,
128  sub_r_image_, sub_r_info_) );
129  exact_sync_->registerCallback(boost::bind(&DisparityNodelet::imageCb,
130  this, _1, _2, _3, _4));
131  }
132 
133  // Set up dynamic reconfiguration
134  ReconfigureServer::CallbackType f = boost::bind(&DisparityNodelet::configCb,
135  this, _1, _2);
136  reconfigure_server_.reset(new ReconfigureServer(config_mutex_, private_nh));
137  reconfigure_server_->setCallback(f);
138 
139  // Monitor whether anyone is subscribed to the output
140  ros::SubscriberStatusCallback connect_cb = boost::bind(&DisparityNodelet::connectCb, this);
141  // Make sure we don't enter connectCb() between advertising and assigning to pub_disparity_
142  boost::lock_guard<boost::mutex> lock(connect_mutex_);
143  pub_disparity_ = nh.advertise<DisparityImage>("disparity", 1, connect_cb, connect_cb);
144 }
145 
146 // Handles (un)subscribing when clients (un)subscribe
148 {
149  boost::lock_guard<boost::mutex> lock(connect_mutex_);
150  if (pub_disparity_.getNumSubscribers() == 0)
151  {
152  sub_l_image_.unsubscribe();
153  sub_l_info_ .unsubscribe();
154  sub_r_image_.unsubscribe();
155  sub_r_info_ .unsubscribe();
156  }
157  else if (!sub_l_image_.getSubscriber())
158  {
159  ros::NodeHandle &nh = getNodeHandle();
160  // Queue size 1 should be OK; the one that matters is the synchronizer queue size.
162  image_transport::TransportHints hints("raw", ros::TransportHints(), getPrivateNodeHandle());
163  sub_l_image_.subscribe(*it_, "left/image_rect", 1, hints);
164  sub_l_info_ .subscribe(nh, "left/camera_info", 1);
165  sub_r_image_.subscribe(*it_, "right/image_rect", 1, hints);
166  sub_r_info_ .subscribe(nh, "right/camera_info", 1);
167  }
168 }
169 
170 void DisparityNodelet::imageCb(const ImageConstPtr& l_image_msg,
171  const CameraInfoConstPtr& l_info_msg,
172  const ImageConstPtr& r_image_msg,
173  const CameraInfoConstPtr& r_info_msg)
174 {
175  // Update the camera model
176  model_.fromCameraInfo(l_info_msg, r_info_msg);
177 
178  // Allocate new disparity image message
179  DisparityImagePtr disp_msg = boost::make_shared<DisparityImage>();
180  disp_msg->header = l_info_msg->header;
181  disp_msg->image.header = l_info_msg->header;
182 
183  // Compute window of (potentially) valid disparities
184  int border = block_matcher_.getCorrelationWindowSize() / 2;
185  int left = block_matcher_.getDisparityRange() + block_matcher_.getMinDisparity() + border - 1;
186  int wtf = (block_matcher_.getMinDisparity() >= 0) ? border + block_matcher_.getMinDisparity() : std::max(border, -block_matcher_.getMinDisparity());
187  int right = disp_msg->image.width - 1 - wtf;
188  int top = border;
189  int bottom = disp_msg->image.height - 1 - border;
190  disp_msg->valid_window.x_offset = left;
191  disp_msg->valid_window.y_offset = top;
192  disp_msg->valid_window.width = right - left;
193  disp_msg->valid_window.height = bottom - top;
194 
195  // Create cv::Mat views onto all buffers
196  const cv::Mat_<uint8_t> l_image = cv_bridge::toCvShare(l_image_msg, sensor_msgs::image_encodings::MONO8)->image;
197  const cv::Mat_<uint8_t> r_image = cv_bridge::toCvShare(r_image_msg, sensor_msgs::image_encodings::MONO8)->image;
198 
199  // Perform block matching to find the disparities
200  block_matcher_.processDisparity(l_image, r_image, model_, *disp_msg);
201 
202  // Adjust for any x-offset between the principal points: d' = d - (cx_l - cx_r)
203  double cx_l = model_.left().cx();
204  double cx_r = model_.right().cx();
205  if (cx_l != cx_r) {
206  cv::Mat_<float> disp_image(disp_msg->image.height, disp_msg->image.width,
207  reinterpret_cast<float*>(&disp_msg->image.data[0]),
208  disp_msg->image.step);
209  cv::subtract(disp_image, cv::Scalar(cx_l - cx_r), disp_image);
210  }
211 
212  pub_disparity_.publish(disp_msg);
213 }
214 
215 void DisparityNodelet::configCb(Config &config, uint32_t level)
216 {
217  // Tweak all settings to be valid
218  config.prefilter_size |= 0x1; // must be odd
219  config.correlation_window_size |= 0x1; // must be odd
220  config.disparity_range = (config.disparity_range / 16) * 16; // must be multiple of 16
221 
222  // check stereo method
223  // Note: With single-threaded NodeHandle, configCb and imageCb can't be called
224  // concurrently, so this is thread-safe.
225  block_matcher_.setPreFilterCap(config.prefilter_cap);
226  block_matcher_.setCorrelationWindowSize(config.correlation_window_size);
227  block_matcher_.setMinDisparity(config.min_disparity);
228  block_matcher_.setDisparityRange(config.disparity_range);
229  block_matcher_.setUniquenessRatio(config.uniqueness_ratio);
230  block_matcher_.setSpeckleSize(config.speckle_size);
231  block_matcher_.setSpeckleRange(config.speckle_range);
232  if (config.stereo_algorithm == stereo_image_proc::Disparity_StereoBM) { // StereoBM
233  block_matcher_.setStereoType(StereoProcessor::BM);
234  block_matcher_.setPreFilterSize(config.prefilter_size);
235  block_matcher_.setTextureThreshold(config.texture_threshold);
236  }
237  else if (config.stereo_algorithm == stereo_image_proc::Disparity_StereoSGBM) { // StereoSGBM
238  block_matcher_.setStereoType(StereoProcessor::SGBM);
239  block_matcher_.setSgbmMode(config.fullDP);
240  block_matcher_.setP1(config.P1);
241  block_matcher_.setP2(config.P2);
242  block_matcher_.setDisp12MaxDiff(config.disp12MaxDiff);
243  }
244 }
245 
246 } // namespace stereo_image_proc
247 
248 // Register nodelet
CvImageConstPtr toCvShare(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
ExactTime< Image, CameraInfo, Image, CameraInfo > ExactPolicy
Definition: disparity.cpp:73
boost::shared_ptr< ReconfigureServer > reconfigure_server_
Definition: disparity.cpp:87
boost::function< void(const SingleSubscriberPublisher &)> SubscriberStatusCallback
f
ApproximateTime< Image, CameraInfo, Image, CameraInfo > ApproximatePolicy
Definition: disparity.cpp:74
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:170
boost::shared_ptr< ExactSync > exact_sync_
Definition: disparity.cpp:77
boost::shared_ptr< image_transport::ImageTransport > it_
Definition: disparity.cpp:68
image_geometry::StereoCameraModel model_
Definition: disparity.cpp:90
dynamic_reconfigure::Server< Config > ReconfigureServer
Definition: disparity.cpp:86
message_filters::Synchronizer< ExactPolicy > ExactSync
Definition: disparity.cpp:75
boost::recursive_mutex config_mutex_
Definition: disparity.cpp:84
message_filters::Synchronizer< ApproximatePolicy > ApproximateSync
Definition: disparity.cpp:76
PLUGINLIB_EXPORT_CLASS(image_proc::CropNonZeroNodelet, nodelet::Nodelet)
message_filters::Subscriber< CameraInfo > sub_r_info_
Definition: disparity.cpp:72
bool param(const std::string &param_name, T &param_val, const T &default_val) const
stereo_image_proc::StereoProcessor block_matcher_
Definition: disparity.cpp:91
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
stereo_image_proc::DisparityConfig Config
Definition: disparity.cpp:85
image_transport::SubscriberFilter sub_r_image_
Definition: disparity.cpp:71
boost::shared_ptr< ApproximateSync > approximate_sync_
Definition: disparity.cpp:78
void configCb(Config &config, uint32_t level)
Definition: disparity.cpp:215


stereo_image_proc
Author(s): Patrick Mihelich, Kurt Konolige, Jeremy Leibs
autogenerated on Thu Nov 7 2019 03:45:07