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 <opencv2/opencv.hpp>
00051 #include <cv_bridge/cv_bridge.h>
00052 
00053 #include <sensor_msgs/image_encodings.h>
00054 #include <stereo_msgs/DisparityImage.h>
00055 
00056 #include <stereo_image_proc/DisparityConfig.h>
00057 #include <dynamic_reconfigure/server.h>
00058 
00059 namespace stereo_image_proc {
00060 
00061 using namespace sensor_msgs;
00062 using namespace stereo_msgs;
00063 using namespace message_filters::sync_policies;
00064 
00065 enum StereoType
00066 {
00067   BM, SGBM
00068 };
00069   
00070 class DisparityNodelet : public nodelet::Nodelet
00071 {
00072   boost::shared_ptr<image_transport::ImageTransport> it_;
00073   
00074   // Subscriptions
00075   image_transport::SubscriberFilter sub_l_image_, sub_r_image_;
00076   message_filters::Subscriber<CameraInfo> sub_l_info_, sub_r_info_;
00077   typedef ExactTime<Image, CameraInfo, Image, CameraInfo> ExactPolicy;
00078   typedef ApproximateTime<Image, CameraInfo, Image, CameraInfo> ApproximatePolicy;
00079   typedef message_filters::Synchronizer<ExactPolicy> ExactSync;
00080   typedef message_filters::Synchronizer<ApproximatePolicy> ApproximateSync;
00081   boost::shared_ptr<ExactSync> exact_sync_;
00082   boost::shared_ptr<ApproximateSync> approximate_sync_;
00083   StereoType current_stereo_algorithm_;
00084   // Publications
00085   boost::mutex connect_mutex_;
00086   ros::Publisher pub_disparity_;
00087 
00088   // Dynamic reconfigure
00089   boost::recursive_mutex config_mutex_;
00090   typedef stereo_image_proc::DisparityConfig Config;
00091   typedef dynamic_reconfigure::Server<Config> ReconfigureServer;
00092   boost::shared_ptr<ReconfigureServer> reconfigure_server_;
00093   
00094   // Processing state (note: only safe because we're single-threaded!)
00095   image_geometry::StereoCameraModel model_;
00096   cv::StereoBM block_matcher_; // contains scratch buffers for block matching
00097   cv::StereoSGBM sg_block_matcher_;
00098   virtual void onInit();
00099 
00100   void connectCb();
00101 
00102   void imageCb(const ImageConstPtr& l_image_msg, const CameraInfoConstPtr& l_info_msg,
00103                const ImageConstPtr& r_image_msg, const CameraInfoConstPtr& r_info_msg);
00104 
00105   void configCb(Config &config, uint32_t level);
00106 };
00107 
00108 void DisparityNodelet::onInit()
00109 {
00110   ros::NodeHandle &nh = getNodeHandle();
00111   ros::NodeHandle &private_nh = getPrivateNodeHandle();
00112 
00113   it_.reset(new image_transport::ImageTransport(nh));
00114 
00115   // Synchronize inputs. Topic subscriptions happen on demand in the connection
00116   // callback. Optionally do approximate synchronization.
00117   int queue_size;
00118   private_nh.param("queue_size", queue_size, 5);
00119   bool approx;
00120   private_nh.param("approximate_sync", approx, false);
00121   if (approx)
00122   {
00123     approximate_sync_.reset( new ApproximateSync(ApproximatePolicy(queue_size),
00124                                                  sub_l_image_, sub_l_info_,
00125                                                  sub_r_image_, sub_r_info_) );
00126     approximate_sync_->registerCallback(boost::bind(&DisparityNodelet::imageCb,
00127                                                     this, _1, _2, _3, _4));
00128   }
00129   else
00130   {
00131     exact_sync_.reset( new ExactSync(ExactPolicy(queue_size),
00132                                      sub_l_image_, sub_l_info_,
00133                                      sub_r_image_, sub_r_info_) );
00134     exact_sync_->registerCallback(boost::bind(&DisparityNodelet::imageCb,
00135                                               this, _1, _2, _3, _4));
00136   }
00137 
00138   // Set up dynamic reconfiguration
00139   ReconfigureServer::CallbackType f = boost::bind(&DisparityNodelet::configCb,
00140                                                   this, _1, _2);
00141   reconfigure_server_.reset(new ReconfigureServer(config_mutex_, private_nh));
00142   reconfigure_server_->setCallback(f);
00143 
00144   // Monitor whether anyone is subscribed to the output
00145   ros::SubscriberStatusCallback connect_cb = boost::bind(&DisparityNodelet::connectCb, this);
00146   // Make sure we don't enter connectCb() between advertising and assigning to pub_disparity_
00147   boost::lock_guard<boost::mutex> lock(connect_mutex_);
00148   pub_disparity_ = nh.advertise<DisparityImage>("disparity", 1, connect_cb, connect_cb);
00149 }
00150 
00151 // Handles (un)subscribing when clients (un)subscribe
00152 void DisparityNodelet::connectCb()
00153 {
00154   boost::lock_guard<boost::mutex> lock(connect_mutex_);
00155   if (pub_disparity_.getNumSubscribers() == 0)
00156   {
00157     sub_l_image_.unsubscribe();
00158     sub_l_info_ .unsubscribe();
00159     sub_r_image_.unsubscribe();
00160     sub_r_info_ .unsubscribe();
00161   }
00162   else if (!sub_l_image_.getSubscriber())
00163   {
00164     ros::NodeHandle &nh = getNodeHandle();
00165     // Queue size 1 should be OK; the one that matters is the synchronizer queue size.
00167     image_transport::TransportHints hints("raw", ros::TransportHints(), getPrivateNodeHandle());
00168     sub_l_image_.subscribe(*it_, "left/image_rect", 1, hints);
00169     sub_l_info_ .subscribe(nh,   "left/camera_info", 1);
00170     sub_r_image_.subscribe(*it_, "right/image_rect", 1, hints);
00171     sub_r_info_ .subscribe(nh,   "right/camera_info", 1);
00172   }
00173 }
00174 
00175 void DisparityNodelet::imageCb(const ImageConstPtr& l_image_msg,
00176                                const CameraInfoConstPtr& l_info_msg,
00177                                const ImageConstPtr& r_image_msg,
00178                                const CameraInfoConstPtr& r_info_msg)
00179 {
00180   // Update the camera model
00181   model_.fromCameraInfo(l_info_msg, r_info_msg);
00182 
00183   // Allocate new disparity image message
00184   DisparityImagePtr disp_msg = boost::make_shared<DisparityImage>();
00185   disp_msg->header         = l_info_msg->header;
00186   disp_msg->image.header   = l_info_msg->header;
00187   disp_msg->image.height   = l_image_msg->height;
00188   disp_msg->image.width    = l_image_msg->width;
00189   disp_msg->image.encoding = sensor_msgs::image_encodings::TYPE_32FC1;
00190   disp_msg->image.step     = disp_msg->image.width * sizeof(float);
00191   disp_msg->image.data.resize(disp_msg->image.height * disp_msg->image.step);
00192 
00193   // Stereo parameters
00194   disp_msg->f = model_.right().fx();
00195   disp_msg->T = model_.baseline();
00196   
00197   // Create cv::Mat views onto all buffers
00198   const cv::Mat_<uint8_t> l_image = cv_bridge::toCvShare(l_image_msg, sensor_msgs::image_encodings::MONO8)->image;
00199   const cv::Mat_<uint8_t> r_image = cv_bridge::toCvShare(r_image_msg, sensor_msgs::image_encodings::MONO8)->image;
00200   cv::Mat_<float> disp_image(disp_msg->image.height, disp_msg->image.width,
00201                              reinterpret_cast<float*>(&disp_msg->image.data[0]),
00202                              disp_msg->image.step);
00203 
00204   // Compute window of (potentially) valid disparities
00205   int border, left, wtf;
00206   if (current_stereo_algorithm_ == BM) {
00207     cv::Ptr<CvStereoBMState> params = block_matcher_.state;
00208     int border   = params->SADWindowSize / 2;
00209     int left   = params->numberOfDisparities + params->minDisparity + border - 1;
00210     int wtf = (params->minDisparity >= 0) ? border + params->minDisparity : std::max(border, -params->minDisparity);
00211     disp_msg->min_disparity = params->minDisparity;
00212     disp_msg->max_disparity = params->minDisparity + params->numberOfDisparities - 1;
00213   }
00214   else if (current_stereo_algorithm_ == SGBM) {
00215     int border   = sg_block_matcher_.SADWindowSize / 2;
00216     int left   = sg_block_matcher_.numberOfDisparities + sg_block_matcher_.minDisparity + border - 1;
00217     int wtf = (sg_block_matcher_.minDisparity >= 0) ? border + sg_block_matcher_.minDisparity : std::max(border, -sg_block_matcher_.minDisparity);
00218     disp_msg->min_disparity = sg_block_matcher_.minDisparity;
00219     disp_msg->max_disparity = sg_block_matcher_.minDisparity + sg_block_matcher_.numberOfDisparities - 1;
00220   }
00221   // Disparity search range
00222   int right  = disp_msg->image.width - 1 - wtf;
00223   int top    = border;
00224   int bottom = disp_msg->image.height - 1 - border;
00225   disp_msg->valid_window.x_offset = left;
00226   disp_msg->valid_window.y_offset = top;
00227   disp_msg->valid_window.width    = right - left;
00228   disp_msg->valid_window.height   = bottom - top;
00229   disp_msg->delta_d = 1.0 / 16; // OpenCV uses 16 disparities per pixel
00230 
00231   // Perform block matching to find the disparities
00232   if (current_stereo_algorithm_ == BM) {
00233     block_matcher_(l_image, r_image, disp_image, CV_32F);
00234   }
00235   else if (current_stereo_algorithm_ == SGBM) {
00236     cv::Mat disp;
00237     sg_block_matcher_(l_image, r_image, disp);
00238     disp.convertTo(disp_image, CV_32F);
00239     disp_image = disp_image / 16;
00240   }
00241 
00242 
00243   
00244 
00245   // Adjust for any x-offset between the principal points: d' = d - (cx_l - cx_r)
00246   double cx_l = model_.left().cx();
00247   double cx_r = model_.right().cx();
00248   if (cx_l != cx_r)
00249     cv::subtract(disp_image, cv::Scalar(cx_l - cx_r), disp_image);
00250 
00251   pub_disparity_.publish(disp_msg);
00252 }
00253 
00254 void DisparityNodelet::configCb(Config &config, uint32_t level)
00255 {
00256   // Tweak all settings to be valid
00257   config.prefilter_size |= 0x1; // must be odd
00258   config.correlation_window_size |= 0x1; // must be odd
00259   config.disparity_range = (config.disparity_range / 16) * 16; // must be multiple of 16
00260   
00261   // check stereo method
00262   // Note: With single-threaded NodeHandle, configCb and imageCb can't be called
00263   // concurrently, so this is thread-safe.
00264   if (config.stereo_algorithm == 0) { // StereoBM
00265     current_stereo_algorithm_ = BM;
00266     block_matcher_.state->preFilterSize       = config.prefilter_size;
00267     block_matcher_.state->preFilterCap        = config.prefilter_cap;
00268     block_matcher_.state->SADWindowSize       = config.correlation_window_size;
00269     block_matcher_.state->minDisparity        = config.min_disparity;
00270     block_matcher_.state->numberOfDisparities = config.disparity_range;
00271     block_matcher_.state->uniquenessRatio     = config.uniqueness_ratio;
00272     block_matcher_.state->textureThreshold    = config.texture_threshold;
00273     block_matcher_.state->speckleWindowSize   = config.speckle_size;
00274     block_matcher_.state->speckleRange        = config.speckle_range;
00275   }
00276   else if (config.stereo_algorithm == 1) { // StereoSGBM
00277     current_stereo_algorithm_ = SGBM;
00278     sg_block_matcher_.preFilterCap        = config.prefilter_cap;
00279     sg_block_matcher_.SADWindowSize       = config.correlation_window_size;
00280     sg_block_matcher_.minDisparity        = config.min_disparity;
00281     sg_block_matcher_.numberOfDisparities = config.disparity_range;
00282     sg_block_matcher_.uniquenessRatio     = config.uniqueness_ratio;
00283     sg_block_matcher_.speckleWindowSize   = config.speckle_size;
00284     sg_block_matcher_.speckleRange        = config.speckle_range;
00285     sg_block_matcher_.fullDP              = config.fullDP;
00286     sg_block_matcher_.P1                  = config.P1;
00287     sg_block_matcher_.P2                  = config.P2;
00288     sg_block_matcher_.disp12MaxDiff       = config.disp12MaxDiff;
00289   }
00290   
00291   
00292   
00293   
00294 }
00295 
00296 } // namespace stereo_image_proc
00297 
00298 // Register nodelet
00299 #include <pluginlib/class_list_macros.h>
00300 PLUGINLIB_EXPORT_CLASS(stereo_image_proc::DisparityNodelet,nodelet::Nodelet)


stereo_image_proc
Author(s): Patrick Mihelich, Kurt Konolige, Jeremy Leibs
autogenerated on Wed Aug 26 2015 11:57:43