disparity.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002 * Software License Agreement (BSD License)
00003 * 
00004 *  Copyright (c) 2008, Willow Garage, Inc.
00005 *  All rights reserved.
00006 * 
00007 *  Redistribution and use in source and binary forms, with or without
00008 *  modification, are permitted provided that the following conditions
00009 *  are met:
00010 * 
00011 *   * Redistributions of source code must retain the above copyright
00012 *     notice, this list of conditions and the following disclaimer.
00013 *   * Redistributions in binary form must reproduce the above
00014 *     copyright notice, this list of conditions and the following
00015 *     disclaimer in the documentation and/or other materials provided
00016 *     with the distribution.
00017 *   * Neither the name of the Willow Garage nor the names of its
00018 *     contributors may be used to endorse or promote products derived
00019 *     from this software without specific prior written permission.
00020 * 
00021 *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022 *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023 *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024 *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025 *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026 *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027 *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028 *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029 *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030 *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031 *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032 *  POSSIBILITY OF SUCH DAMAGE.
00033 *********************************************************************/
00034 #include <boost/version.hpp>
00035 #if ((BOOST_VERSION / 100) % 1000) >= 53
00036 #include <boost/thread/lock_guard.hpp>
00037 #endif
00038 
00039 #include <ros/ros.h>
00040 #include <nodelet/nodelet.h>
00041 #include <image_transport/image_transport.h>
00042 #include <image_transport/subscriber_filter.h>
00043 #include <message_filters/subscriber.h>
00044 #include <message_filters/synchronizer.h>
00045 #include <message_filters/sync_policies/exact_time.h>
00046 #include <message_filters/sync_policies/approximate_time.h>
00047 
00048 #include <image_geometry/stereo_camera_model.h>
00049 #include <opencv2/calib3d/calib3d.hpp>
00050 #include <cv_bridge/cv_bridge.h>
00051 
00052 #include <sensor_msgs/image_encodings.h>
00053 #include <stereo_msgs/DisparityImage.h>
00054 
00055 #include <stereo_image_proc/DisparityConfig.h>
00056 #include <dynamic_reconfigure/server.h>
00057 
00058 #include <stereo_image_proc/processor.h>
00059 
00060 namespace stereo_image_proc {
00061 
00062 using namespace sensor_msgs;
00063 using namespace stereo_msgs;
00064 using namespace message_filters::sync_policies;
00065 
00066 class DisparityNodelet : public nodelet::Nodelet
00067 {
00068   boost::shared_ptr<image_transport::ImageTransport> it_;
00069   
00070   // Subscriptions
00071   image_transport::SubscriberFilter sub_l_image_, sub_r_image_;
00072   message_filters::Subscriber<CameraInfo> sub_l_info_, sub_r_info_;
00073   typedef ExactTime<Image, CameraInfo, Image, CameraInfo> ExactPolicy;
00074   typedef ApproximateTime<Image, CameraInfo, Image, CameraInfo> ApproximatePolicy;
00075   typedef message_filters::Synchronizer<ExactPolicy> ExactSync;
00076   typedef message_filters::Synchronizer<ApproximatePolicy> ApproximateSync;
00077   boost::shared_ptr<ExactSync> exact_sync_;
00078   boost::shared_ptr<ApproximateSync> approximate_sync_;
00079   // Publications
00080   boost::mutex connect_mutex_;
00081   ros::Publisher pub_disparity_;
00082 
00083   // Dynamic reconfigure
00084   boost::recursive_mutex config_mutex_;
00085   typedef stereo_image_proc::DisparityConfig Config;
00086   typedef dynamic_reconfigure::Server<Config> ReconfigureServer;
00087   boost::shared_ptr<ReconfigureServer> reconfigure_server_;
00088   
00089   // Processing state (note: only safe because we're single-threaded!)
00090   image_geometry::StereoCameraModel model_;
00091   stereo_image_proc::StereoProcessor block_matcher_; // contains scratch buffers for block matching
00092 
00093   virtual void onInit();
00094 
00095   void connectCb();
00096 
00097   void imageCb(const ImageConstPtr& l_image_msg, const CameraInfoConstPtr& l_info_msg,
00098                const ImageConstPtr& r_image_msg, const CameraInfoConstPtr& r_info_msg);
00099 
00100   void configCb(Config &config, uint32_t level);
00101 };
00102 
00103 void DisparityNodelet::onInit()
00104 {
00105   ros::NodeHandle &nh = getNodeHandle();
00106   ros::NodeHandle &private_nh = getPrivateNodeHandle();
00107 
00108   it_.reset(new image_transport::ImageTransport(nh));
00109 
00110   // Synchronize inputs. Topic subscriptions happen on demand in the connection
00111   // callback. Optionally do approximate synchronization.
00112   int queue_size;
00113   private_nh.param("queue_size", queue_size, 5);
00114   bool approx;
00115   private_nh.param("approximate_sync", approx, false);
00116   if (approx)
00117   {
00118     approximate_sync_.reset( new ApproximateSync(ApproximatePolicy(queue_size),
00119                                                  sub_l_image_, sub_l_info_,
00120                                                  sub_r_image_, sub_r_info_) );
00121     approximate_sync_->registerCallback(boost::bind(&DisparityNodelet::imageCb,
00122                                                     this, _1, _2, _3, _4));
00123   }
00124   else
00125   {
00126     exact_sync_.reset( new ExactSync(ExactPolicy(queue_size),
00127                                      sub_l_image_, sub_l_info_,
00128                                      sub_r_image_, sub_r_info_) );
00129     exact_sync_->registerCallback(boost::bind(&DisparityNodelet::imageCb,
00130                                               this, _1, _2, _3, _4));
00131   }
00132 
00133   // Set up dynamic reconfiguration
00134   ReconfigureServer::CallbackType f = boost::bind(&DisparityNodelet::configCb,
00135                                                   this, _1, _2);
00136   reconfigure_server_.reset(new ReconfigureServer(config_mutex_, private_nh));
00137   reconfigure_server_->setCallback(f);
00138 
00139   // Monitor whether anyone is subscribed to the output
00140   ros::SubscriberStatusCallback connect_cb = boost::bind(&DisparityNodelet::connectCb, this);
00141   // Make sure we don't enter connectCb() between advertising and assigning to pub_disparity_
00142   boost::lock_guard<boost::mutex> lock(connect_mutex_);
00143   pub_disparity_ = nh.advertise<DisparityImage>("disparity", 1, connect_cb, connect_cb);
00144 }
00145 
00146 // Handles (un)subscribing when clients (un)subscribe
00147 void DisparityNodelet::connectCb()
00148 {
00149   boost::lock_guard<boost::mutex> lock(connect_mutex_);
00150   if (pub_disparity_.getNumSubscribers() == 0)
00151   {
00152     sub_l_image_.unsubscribe();
00153     sub_l_info_ .unsubscribe();
00154     sub_r_image_.unsubscribe();
00155     sub_r_info_ .unsubscribe();
00156   }
00157   else if (!sub_l_image_.getSubscriber())
00158   {
00159     ros::NodeHandle &nh = getNodeHandle();
00160     // Queue size 1 should be OK; the one that matters is the synchronizer queue size.
00162     image_transport::TransportHints hints("raw", ros::TransportHints(), getPrivateNodeHandle());
00163     sub_l_image_.subscribe(*it_, "left/image_rect", 1, hints);
00164     sub_l_info_ .subscribe(nh,   "left/camera_info", 1);
00165     sub_r_image_.subscribe(*it_, "right/image_rect", 1, hints);
00166     sub_r_info_ .subscribe(nh,   "right/camera_info", 1);
00167   }
00168 }
00169 
00170 void DisparityNodelet::imageCb(const ImageConstPtr& l_image_msg,
00171                                const CameraInfoConstPtr& l_info_msg,
00172                                const ImageConstPtr& r_image_msg,
00173                                const CameraInfoConstPtr& r_info_msg)
00174 {
00175   // Update the camera model
00176   model_.fromCameraInfo(l_info_msg, r_info_msg);
00177 
00178   // Allocate new disparity image message
00179   DisparityImagePtr disp_msg = boost::make_shared<DisparityImage>();
00180   disp_msg->header         = l_info_msg->header;
00181   disp_msg->image.header   = l_info_msg->header;
00182 
00183   // Compute window of (potentially) valid disparities
00184   int border   = block_matcher_.getCorrelationWindowSize() / 2;
00185   int left   = block_matcher_.getDisparityRange() + block_matcher_.getMinDisparity() + border - 1;
00186   int wtf = (block_matcher_.getMinDisparity() >= 0) ? border + block_matcher_.getMinDisparity() : std::max(border, -block_matcher_.getMinDisparity());
00187   int right  = disp_msg->image.width - 1 - wtf;
00188   int top    = border;
00189   int bottom = disp_msg->image.height - 1 - border;
00190   disp_msg->valid_window.x_offset = left;
00191   disp_msg->valid_window.y_offset = top;
00192   disp_msg->valid_window.width    = right - left;
00193   disp_msg->valid_window.height   = bottom - top;
00194 
00195   // Create cv::Mat views onto all buffers
00196   const cv::Mat_<uint8_t> l_image = cv_bridge::toCvShare(l_image_msg, sensor_msgs::image_encodings::MONO8)->image;
00197   const cv::Mat_<uint8_t> r_image = cv_bridge::toCvShare(r_image_msg, sensor_msgs::image_encodings::MONO8)->image;
00198 
00199   // Perform block matching to find the disparities
00200   block_matcher_.processDisparity(l_image, r_image, model_, *disp_msg);
00201 
00202   // Adjust for any x-offset between the principal points: d' = d - (cx_l - cx_r)
00203   double cx_l = model_.left().cx();
00204   double cx_r = model_.right().cx();
00205   if (cx_l != cx_r) {
00206     cv::Mat_<float> disp_image(disp_msg->image.height, disp_msg->image.width,
00207                               reinterpret_cast<float*>(&disp_msg->image.data[0]),
00208                               disp_msg->image.step);
00209     cv::subtract(disp_image, cv::Scalar(cx_l - cx_r), disp_image);
00210   }
00211 
00212   pub_disparity_.publish(disp_msg);
00213 }
00214 
00215 void DisparityNodelet::configCb(Config &config, uint32_t level)
00216 {
00217   // Tweak all settings to be valid
00218   config.prefilter_size |= 0x1; // must be odd
00219   config.correlation_window_size |= 0x1; // must be odd
00220   config.disparity_range = (config.disparity_range / 16) * 16; // must be multiple of 16
00221   
00222   // check stereo method
00223   // Note: With single-threaded NodeHandle, configCb and imageCb can't be called
00224   // concurrently, so this is thread-safe.
00225   block_matcher_.setPreFilterCap(config.prefilter_cap);
00226   block_matcher_.setCorrelationWindowSize(config.correlation_window_size);
00227   block_matcher_.setMinDisparity(config.min_disparity);
00228   block_matcher_.setDisparityRange(config.disparity_range);
00229   block_matcher_.setUniquenessRatio(config.uniqueness_ratio);
00230   block_matcher_.setSpeckleSize(config.speckle_size);
00231   block_matcher_.setSpeckleRange(config.speckle_range);
00232   if (config.stereo_algorithm == stereo_image_proc::Disparity_StereoBM) { // StereoBM
00233     block_matcher_.setStereoType(StereoProcessor::BM);
00234     block_matcher_.setPreFilterSize(config.prefilter_size);
00235     block_matcher_.setTextureThreshold(config.texture_threshold);
00236   }
00237   else if (config.stereo_algorithm == stereo_image_proc::Disparity_StereoSGBM) { // StereoSGBM
00238     block_matcher_.setStereoType(StereoProcessor::SGBM);
00239     block_matcher_.setSgbmMode(config.fullDP);
00240     block_matcher_.setP1(config.P1);
00241     block_matcher_.setP2(config.P2);
00242     block_matcher_.setDisp12MaxDiff(config.disp12MaxDiff);
00243   }
00244 }
00245 
00246 } // namespace stereo_image_proc
00247 
00248 // Register nodelet
00249 #include <pluginlib/class_list_macros.h>
00250 PLUGINLIB_EXPORT_CLASS(stereo_image_proc::DisparityNodelet,nodelet::Nodelet)


stereo_image_proc
Author(s): Patrick Mihelich, Kurt Konolige, Jeremy Leibs
autogenerated on Wed May 1 2019 02:51:55