disparity.cpp
Go to the documentation of this file.
00001 #include <ros/ros.h>
00002 #include <nodelet/nodelet.h>
00003 #include <image_transport/image_transport.h>
00004 #include <image_transport/subscriber_filter.h>
00005 #include <message_filters/subscriber.h>
00006 #include <message_filters/synchronizer.h>
00007 #include <message_filters/sync_policies/exact_time.h>
00008 #include <message_filters/sync_policies/approximate_time.h>
00009 
00010 #include <image_geometry/stereo_camera_model.h>
00011 #include <opencv2/calib3d/calib3d.hpp>
00012 
00013 #include <sensor_msgs/image_encodings.h>
00014 #include <stereo_msgs/DisparityImage.h>
00015 
00016 #include <stereo_image_proc/DisparityConfig.h>
00017 #include <dynamic_reconfigure/server.h>
00018 
00019 namespace stereo_image_proc {
00020 
00021 using namespace sensor_msgs;
00022 using namespace stereo_msgs;
00023 using namespace message_filters::sync_policies;
00024 
00025 class DisparityNodelet : public nodelet::Nodelet
00026 {
00027   boost::shared_ptr<image_transport::ImageTransport> it_;
00028   
00029   // Subscriptions
00030   image_transport::SubscriberFilter sub_l_image_, sub_r_image_;
00031   message_filters::Subscriber<CameraInfo> sub_l_info_, sub_r_info_;
00032   typedef ExactTime<Image, CameraInfo, Image, CameraInfo> ExactPolicy;
00033   typedef ApproximateTime<Image, CameraInfo, Image, CameraInfo> ApproximatePolicy;
00034   typedef message_filters::Synchronizer<ExactPolicy> ExactSync;
00035   typedef message_filters::Synchronizer<ApproximatePolicy> ApproximateSync;
00036   boost::shared_ptr<ExactSync> exact_sync_;
00037   boost::shared_ptr<ApproximateSync> approximate_sync_;
00038 
00039   // Publications
00040   boost::mutex connect_mutex_;
00041   ros::Publisher pub_disparity_;
00042 
00043   // Dynamic reconfigure
00044   boost::recursive_mutex config_mutex_;
00045   typedef stereo_image_proc::DisparityConfig Config;
00046   typedef dynamic_reconfigure::Server<Config> ReconfigureServer;
00047   boost::shared_ptr<ReconfigureServer> reconfigure_server_;
00048   
00049   // Processing state (note: only safe because we're single-threaded!)
00050   image_geometry::StereoCameraModel model_;
00051   cv::StereoBM block_matcher_; // contains scratch buffers for block matching
00052 
00053   virtual void onInit();
00054 
00055   void connectCb();
00056 
00057   void imageCb(const ImageConstPtr& l_image_msg, const CameraInfoConstPtr& l_info_msg,
00058                const ImageConstPtr& r_image_msg, const CameraInfoConstPtr& r_info_msg);
00059 
00060   void configCb(Config &config, uint32_t level);
00061 };
00062 
00063 void DisparityNodelet::onInit()
00064 {
00065   ros::NodeHandle &nh = getNodeHandle();
00066   ros::NodeHandle &private_nh = getPrivateNodeHandle();
00067 
00068   it_.reset(new image_transport::ImageTransport(nh));
00069 
00070   // Synchronize inputs. Topic subscriptions happen on demand in the connection
00071   // callback. Optionally do approximate synchronization.
00072   int queue_size;
00073   private_nh.param("queue_size", queue_size, 5);
00074   bool approx;
00075   private_nh.param("approximate_sync", approx, false);
00076   if (approx)
00077   {
00078     approximate_sync_.reset( new ApproximateSync(ApproximatePolicy(queue_size),
00079                                                  sub_l_image_, sub_l_info_,
00080                                                  sub_r_image_, sub_r_info_) );
00081     approximate_sync_->registerCallback(boost::bind(&DisparityNodelet::imageCb,
00082                                                     this, _1, _2, _3, _4));
00083   }
00084   else
00085   {
00086     exact_sync_.reset( new ExactSync(ExactPolicy(queue_size),
00087                                      sub_l_image_, sub_l_info_,
00088                                      sub_r_image_, sub_r_info_) );
00089     exact_sync_->registerCallback(boost::bind(&DisparityNodelet::imageCb,
00090                                               this, _1, _2, _3, _4));
00091   }
00092 
00093   // Set up dynamic reconfiguration
00094   ReconfigureServer::CallbackType f = boost::bind(&DisparityNodelet::configCb,
00095                                                   this, _1, _2);
00096   reconfigure_server_.reset(new ReconfigureServer(config_mutex_, private_nh));
00097   reconfigure_server_->setCallback(f);
00098 
00099   // Monitor whether anyone is subscribed to the output
00100   ros::SubscriberStatusCallback connect_cb = boost::bind(&DisparityNodelet::connectCb, this);
00101   // Make sure we don't enter connectCb() between advertising and assigning to pub_disparity_
00102   boost::lock_guard<boost::mutex> lock(connect_mutex_);
00103   pub_disparity_ = nh.advertise<DisparityImage>("disparity", 1, connect_cb, connect_cb);
00104 }
00105 
00106 // Handles (un)subscribing when clients (un)subscribe
00107 void DisparityNodelet::connectCb()
00108 {
00109   boost::lock_guard<boost::mutex> lock(connect_mutex_);
00110   if (pub_disparity_.getNumSubscribers() == 0)
00111   {
00112     sub_l_image_.unsubscribe();
00113     sub_l_info_ .unsubscribe();
00114     sub_r_image_.unsubscribe();
00115     sub_r_info_ .unsubscribe();
00116   }
00117   else if (!sub_l_image_.getSubscriber())
00118   {
00119     ros::NodeHandle &nh = getNodeHandle();
00120     // Queue size 1 should be OK; the one that matters is the synchronizer queue size.
00122     image_transport::TransportHints hints("raw", ros::TransportHints(), getPrivateNodeHandle());
00123     sub_l_image_.subscribe(*it_, "left/image_rect", 1, hints);
00124     sub_l_info_ .subscribe(nh,   "left/camera_info", 1);
00125     sub_r_image_.subscribe(*it_, "right/image_rect", 1, hints);
00126     sub_r_info_ .subscribe(nh,   "right/camera_info", 1);
00127   }
00128 }
00129 
00130 void DisparityNodelet::imageCb(const ImageConstPtr& l_image_msg,
00131                                const CameraInfoConstPtr& l_info_msg,
00132                                const ImageConstPtr& r_image_msg,
00133                                const CameraInfoConstPtr& r_info_msg)
00134 {
00136   assert(l_image_msg->encoding == sensor_msgs::image_encodings::MONO8);
00137   assert(r_image_msg->encoding == sensor_msgs::image_encodings::MONO8);
00138 
00139   // Update the camera model
00140   model_.fromCameraInfo(l_info_msg, r_info_msg);
00141   
00142   // Allocate new disparity image message
00143   DisparityImagePtr disp_msg = boost::make_shared<DisparityImage>();
00144   disp_msg->header         = l_info_msg->header;
00145   disp_msg->image.header   = l_info_msg->header;
00146   disp_msg->image.height   = l_image_msg->height;
00147   disp_msg->image.width    = l_image_msg->width;
00148   disp_msg->image.encoding = sensor_msgs::image_encodings::TYPE_32FC1;
00149   disp_msg->image.step     = disp_msg->image.width * sizeof(float);
00150   disp_msg->image.data.resize(disp_msg->image.height * disp_msg->image.step);
00151 
00152   // Stereo parameters
00153   disp_msg->f = model_.right().fx();
00154   disp_msg->T = model_.baseline();
00155 
00156   // Compute window of (potentially) valid disparities
00157   cv::Ptr<CvStereoBMState> params = block_matcher_.state;
00158   int border   = params->SADWindowSize / 2;
00159   int left   = params->numberOfDisparities + params->minDisparity + border - 1;
00160   int wtf = (params->minDisparity >= 0) ? border + params->minDisparity : std::max(border, -params->minDisparity);
00161   int right  = disp_msg->image.width - 1 - wtf;
00162   int top    = border;
00163   int bottom = disp_msg->image.height - 1 - border;
00164   disp_msg->valid_window.x_offset = left;
00165   disp_msg->valid_window.y_offset = top;
00166   disp_msg->valid_window.width    = right - left;
00167   disp_msg->valid_window.height   = bottom - top;
00168 
00169   // Disparity search range
00170   disp_msg->min_disparity = params->minDisparity;
00171   disp_msg->max_disparity = params->minDisparity + params->numberOfDisparities - 1;
00172   disp_msg->delta_d = 1.0 / 16; // OpenCV uses 16 disparities per pixel
00173 
00174   // Create cv::Mat views onto all buffers
00175   const cv::Mat_<uint8_t> l_image(l_image_msg->height, l_image_msg->width,
00176                                   const_cast<uint8_t*>(&l_image_msg->data[0]),
00177                                   l_image_msg->step);
00178   const cv::Mat_<uint8_t> r_image(r_image_msg->height, r_image_msg->width,
00179                                   const_cast<uint8_t*>(&r_image_msg->data[0]),
00180                                   r_image_msg->step);
00181   cv::Mat_<float> disp_image(disp_msg->image.height, disp_msg->image.width,
00182                              reinterpret_cast<float*>(&disp_msg->image.data[0]),
00183                              disp_msg->image.step);
00184 
00185   // Perform block matching to find the disparities
00186   block_matcher_(l_image, r_image, disp_image, CV_32F);
00187 
00188   // Adjust for any x-offset between the principal points: d' = d - (cx_l - cx_r)
00189   double cx_l = model_.left().cx();
00190   double cx_r = model_.right().cx();
00191   if (cx_l != cx_r)
00192     cv::subtract(disp_image, cv::Scalar(cx_l - cx_r), disp_image);
00193 
00194   pub_disparity_.publish(disp_msg);
00195 }
00196 
00197 void DisparityNodelet::configCb(Config &config, uint32_t level)
00198 {
00199   // Tweak all settings to be valid
00200   config.prefilter_size |= 0x1; // must be odd
00201   config.correlation_window_size |= 0x1; // must be odd
00202   config.disparity_range = (config.disparity_range / 16) * 16; // must be multiple of 16
00203 
00204   // Note: With single-threaded NodeHandle, configCb and imageCb can't be called
00205   // concurrently, so this is thread-safe.
00206   block_matcher_.state->preFilterSize       = config.prefilter_size;
00207   block_matcher_.state->preFilterCap        = config.prefilter_cap;
00208   block_matcher_.state->SADWindowSize       = config.correlation_window_size;
00209   block_matcher_.state->minDisparity        = config.min_disparity;
00210   block_matcher_.state->numberOfDisparities = config.disparity_range;
00211   block_matcher_.state->uniquenessRatio     = config.uniqueness_ratio;
00212   block_matcher_.state->textureThreshold    = config.texture_threshold;
00213   block_matcher_.state->speckleWindowSize   = config.speckle_size;
00214   block_matcher_.state->speckleRange        = config.speckle_range;
00215 }
00216 
00217 } // namespace stereo_image_proc
00218 
00219 // Register nodelet
00220 #include <pluginlib/class_list_macros.h>
00221 PLUGINLIB_DECLARE_CLASS(stereo_image_proc, disparity,
00222                         stereo_image_proc::DisparityNodelet, nodelet::Nodelet)


stereo_image_proc
Author(s): Patrick Mihelich, Kurt Konolige, Jeremy Leibs
autogenerated on Fri Jan 3 2014 11:24:49