processor.h
Go to the documentation of this file.
00001 #ifndef STEREO_IMAGE_PROC_PROCESSOR_H
00002 #define STEREO_IMAGE_PROC_PROCESSOR_H
00003 
00004 #include <image_proc/processor.h>
00005 #include <image_geometry/stereo_camera_model.h>
00006 #include <stereo_msgs/DisparityImage.h>
00007 #include <sensor_msgs/PointCloud.h>
00008 #include <sensor_msgs/PointCloud2.h>
00009 
00010 namespace stereo_image_proc {
00011 
00012 struct StereoImageSet
00013 {
00014   image_proc::ImageSet left;
00015   image_proc::ImageSet right;
00016   stereo_msgs::DisparityImage disparity;
00017   sensor_msgs::PointCloud points;
00018   sensor_msgs::PointCloud2 points2;
00019 };
00020 
00021 class StereoProcessor
00022 {
00023 public:
00024   
00025   StereoProcessor()
00026     : block_matcher_(cv::StereoBM::BASIC_PRESET)
00027   {
00028   }
00029 
00030   enum {
00031     LEFT_MONO        = 1 << 0,
00032     LEFT_RECT        = 1 << 1,
00033     LEFT_COLOR       = 1 << 2,
00034     LEFT_RECT_COLOR  = 1 << 3,
00035     RIGHT_MONO       = 1 << 4,
00036     RIGHT_RECT       = 1 << 5,
00037     RIGHT_COLOR      = 1 << 6,
00038     RIGHT_RECT_COLOR = 1 << 7,
00039     DISPARITY        = 1 << 8,
00040     POINT_CLOUD      = 1 << 9,
00041     POINT_CLOUD2     = 1 << 10,
00042 
00043     LEFT_ALL = LEFT_MONO | LEFT_RECT | LEFT_COLOR | LEFT_RECT_COLOR,
00044     RIGHT_ALL = RIGHT_MONO | RIGHT_RECT | RIGHT_COLOR | RIGHT_RECT_COLOR,
00045     STEREO_ALL = DISPARITY | POINT_CLOUD | POINT_CLOUD2,
00046     ALL = LEFT_ALL | RIGHT_ALL | STEREO_ALL
00047   };
00048 
00049   int getInterpolation() const;
00050   void setInterpolation(int interp);
00051 
00052   // Disparity pre-filtering parameters
00053 
00054   int getPreFilterSize() const;
00055   void setPreFilterSize(int size);
00056 
00057   int getPreFilterCap() const;
00058   void setPreFilterCap(int cap);
00059 
00060   // Disparity correlation parameters
00061   
00062   int getCorrelationWindowSize() const;
00063   void setCorrelationWindowSize(int size);
00064 
00065   int getMinDisparity() const;
00066   void setMinDisparity(int min_d);
00067 
00068   int getDisparityRange() const;
00069   void setDisparityRange(int range); // Number of pixels to search
00070 
00071   // Disparity post-filtering parameters
00072   
00073   int getTextureThreshold() const;
00074   void setTextureThreshold(int threshold);
00075 
00076   float getUniquenessRatio() const;
00077   void setUniquenessRatio(float ratio);
00078 
00079   int getSpeckleSize() const;
00080   void setSpeckleSize(int size);
00081 
00082   int getSpeckleRange() const;
00083   void setSpeckleRange(int range);
00084 
00085   // Do all the work!
00086   bool process(const sensor_msgs::ImageConstPtr& left_raw,
00087                const sensor_msgs::ImageConstPtr& right_raw,
00088                const image_geometry::StereoCameraModel& model,
00089                StereoImageSet& output, int flags) const;
00090 
00091   void processDisparity(const cv::Mat& left_rect, const cv::Mat& right_rect,
00092                         const image_geometry::StereoCameraModel& model,
00093                         stereo_msgs::DisparityImage& disparity) const;
00094 
00095   void processPoints(const stereo_msgs::DisparityImage& disparity,
00096                      const cv::Mat& color, const std::string& encoding,
00097                      const image_geometry::StereoCameraModel& model,
00098                      sensor_msgs::PointCloud& points) const;
00099   void processPoints2(const stereo_msgs::DisparityImage& disparity,
00100                       const cv::Mat& color, const std::string& encoding,
00101                       const image_geometry::StereoCameraModel& model,
00102                       sensor_msgs::PointCloud2& points) const;
00103 
00104 private:
00105   image_proc::Processor mono_processor_;
00106   
00107   mutable cv::Mat_<int16_t> disparity16_; // scratch buffer for 16-bit signed disparity image
00108   mutable cv::StereoBM block_matcher_; // contains scratch buffers for block matching
00109   // scratch buffers for speckle filtering
00110   mutable cv::Mat_<uint32_t> labels_;
00111   mutable cv::Mat_<uint32_t> wavefront_;
00112   mutable cv::Mat_<uint8_t> region_types_;
00113   // scratch buffer for dense point cloud
00114   mutable cv::Mat_<cv::Vec3f> dense_points_;
00115 };
00116 
00117 
00118 inline int StereoProcessor::getInterpolation() const
00119 {
00120   return mono_processor_.interpolation_;
00121 }
00122 
00123 inline void StereoProcessor::setInterpolation(int interp)
00124 {
00125   mono_processor_.interpolation_ = interp;
00126 }
00127 
00128 inline int StereoProcessor::getPreFilterSize() const
00129 {
00130   return block_matcher_.state->preFilterSize;
00131 }
00132 
00133 inline void StereoProcessor::setPreFilterSize(int size)
00134 {
00135   block_matcher_.state->preFilterSize = size;
00136 }
00137 
00138 inline int StereoProcessor::getPreFilterCap() const
00139 {
00140   return block_matcher_.state->preFilterCap;
00141 }
00142 
00143 inline void StereoProcessor::setPreFilterCap(int cap)
00144 {
00145   block_matcher_.state->preFilterCap = cap;
00146 }
00147 
00148 inline int StereoProcessor::getCorrelationWindowSize() const
00149 {
00150   return block_matcher_.state->SADWindowSize;
00151 }
00152 
00153 inline void StereoProcessor::setCorrelationWindowSize(int size)
00154 {
00155   block_matcher_.state->SADWindowSize = size;
00156 }
00157 
00158 inline int StereoProcessor::getMinDisparity() const
00159 {
00160   return block_matcher_.state->minDisparity;
00161 }
00162 
00163 inline void StereoProcessor::setMinDisparity(int min_d)
00164 {
00165   block_matcher_.state->minDisparity = min_d;
00166 }
00167 
00168 inline int StereoProcessor::getDisparityRange() const
00169 {
00170   return block_matcher_.state->numberOfDisparities;
00171 }
00172 
00173 inline void StereoProcessor::setDisparityRange(int range)
00174 {
00175   block_matcher_.state->numberOfDisparities = range;
00176 }
00177 
00178 inline int StereoProcessor::getTextureThreshold() const
00179 {
00180   return block_matcher_.state->textureThreshold;
00181 }
00182 
00183 inline void StereoProcessor::setTextureThreshold(int threshold)
00184 {
00185   block_matcher_.state->textureThreshold = threshold;
00186 }
00187 
00188 inline float StereoProcessor::getUniquenessRatio() const
00189 {
00190   return block_matcher_.state->uniquenessRatio;
00191 }
00192 
00193 inline void StereoProcessor::setUniquenessRatio(float ratio)
00194 {
00195   block_matcher_.state->uniquenessRatio = ratio;
00196 }
00197 
00198 inline int StereoProcessor::getSpeckleSize() const
00199 {
00200   return block_matcher_.state->speckleWindowSize;
00201 }
00202 
00203 inline void StereoProcessor::setSpeckleSize(int size)
00204 {
00205   block_matcher_.state->speckleWindowSize = size;
00206 }
00207 
00208 inline int StereoProcessor::getSpeckleRange() const
00209 {
00210   return block_matcher_.state->speckleRange;
00211 }
00212 
00213 inline void StereoProcessor::setSpeckleRange(int range)
00214 {
00215   block_matcher_.state->speckleRange = range;
00216 }
00217 
00218 } //namespace stereo_image_proc
00219 
00220 #endif


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