processor.h
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 #ifndef STEREO_IMAGE_PROC_PROCESSOR_H
35 #define STEREO_IMAGE_PROC_PROCESSOR_H
36 
37 #include <image_proc/processor.h>
39 #include <opencv2/calib3d/calib3d.hpp>
40 #include <stereo_msgs/DisparityImage.h>
41 #include <sensor_msgs/PointCloud.h>
42 #include <sensor_msgs/PointCloud2.h>
43 
44 namespace stereo_image_proc {
45 
46 struct StereoImageSet
47 {
50  stereo_msgs::DisparityImage disparity;
51  sensor_msgs::PointCloud points;
52  sensor_msgs::PointCloud2 points2;
53 };
54 
55 class StereoProcessor
56 {
57 public:
58 
60 #if CV_MAJOR_VERSION >= 3
61  {
62  block_matcher_ = cv::StereoBM::create();
63  sg_block_matcher_ = cv::StereoSGBM::create(1, 1, 10);
64 #else
65  : block_matcher_(cv::StereoBM::BASIC_PRESET),
67  {
68 #endif
69  }
70 
71  enum StereoType
72  {
73  BM, SGBM
74  };
75 
76  enum {
77  LEFT_MONO = 1 << 0,
78  LEFT_RECT = 1 << 1,
79  LEFT_COLOR = 1 << 2,
80  LEFT_RECT_COLOR = 1 << 3,
81  RIGHT_MONO = 1 << 4,
82  RIGHT_RECT = 1 << 5,
83  RIGHT_COLOR = 1 << 6,
84  RIGHT_RECT_COLOR = 1 << 7,
85  DISPARITY = 1 << 8,
86  POINT_CLOUD = 1 << 9,
87  POINT_CLOUD2 = 1 << 10,
88 
93  };
94 
95  inline
97  inline
99 
100  int getInterpolation() const;
101  void setInterpolation(int interp);
102 
103  // Disparity pre-filtering parameters
104 
105  int getPreFilterSize() const;
106  void setPreFilterSize(int size);
107 
108  int getPreFilterCap() const;
109  void setPreFilterCap(int cap);
110 
111  // Disparity correlation parameters
112 
114  void setCorrelationWindowSize(int size);
115 
116  int getMinDisparity() const;
117  void setMinDisparity(int min_d);
118 
119  int getDisparityRange() const;
120  void setDisparityRange(int range); // Number of pixels to search
121 
122  // Disparity post-filtering parameters
123 
124  int getTextureThreshold() const;
125  void setTextureThreshold(int threshold);
126 
127  float getUniquenessRatio() const;
128  void setUniquenessRatio(float ratio);
129 
130  int getSpeckleSize() const;
131  void setSpeckleSize(int size);
132 
133  int getSpeckleRange() const;
134  void setSpeckleRange(int range);
135 
136  // SGBM only
137  int getSgbmMode() const;
138  void setSgbmMode(int fullDP);
139 
140  int getP1() const;
141  void setP1(int P1);
142 
143  int getP2() const;
144  void setP2(int P2);
145 
146  int getDisp12MaxDiff() const;
147  void setDisp12MaxDiff(int disp12MaxDiff);
148 
149  // Do all the work!
150  bool process(const sensor_msgs::ImageConstPtr& left_raw,
151  const sensor_msgs::ImageConstPtr& right_raw,
153  StereoImageSet& output, int flags) const;
154 
155  void processDisparity(const cv::Mat& left_rect, const cv::Mat& right_rect,
157  stereo_msgs::DisparityImage& disparity) const;
158 
159  void processPoints(const stereo_msgs::DisparityImage& disparity,
160  const cv::Mat& color, const std::string& encoding,
162  sensor_msgs::PointCloud& points) const;
163  void processPoints2(const stereo_msgs::DisparityImage& disparity,
164  const cv::Mat& color, const std::string& encoding,
166  sensor_msgs::PointCloud2& points) const;
167 
168 private:
170 
171  mutable cv::Mat_<int16_t> disparity16_; // scratch buffer for 16-bit signed disparity image
172 #if CV_MAJOR_VERSION >= 3
173  mutable cv::Ptr<cv::StereoBM> block_matcher_; // contains scratch buffers for block matching
174  mutable cv::Ptr<cv::StereoSGBM> sg_block_matcher_;
175 #else
176  mutable cv::StereoBM block_matcher_; // contains scratch buffers for block matching
177  mutable cv::StereoSGBM sg_block_matcher_;
178 #endif
180  // scratch buffer for dense point cloud
181  mutable cv::Mat_<cv::Vec3f> dense_points_;
182 };
183 
184 
185 inline int StereoProcessor::getInterpolation() const
186 {
188 }
189 
190 inline void StereoProcessor::setInterpolation(int interp)
191 {
193 }
194 
195 // For once, a macro is used just to avoid errors
196 #define STEREO_IMAGE_PROC_OPENCV2(GET, SET, TYPE, PARAM) \
197 inline TYPE StereoProcessor::GET() const \
198 { \
199  if (current_stereo_algorithm_ == BM) \
200  return block_matcher_.state->PARAM; \
201  return sg_block_matcher_.PARAM; \
202 } \
203  \
204 inline void StereoProcessor::SET(TYPE param) \
205 { \
206  block_matcher_.state->PARAM = param; \
207  sg_block_matcher_.PARAM = param; \
208 }
209 
210 #define STEREO_IMAGE_PROC_OPENCV3(GET, SET, TYPE, GET_OPENCV, SET_OPENCV) \
211 inline TYPE StereoProcessor::GET() const \
212 { \
213  if (current_stereo_algorithm_ == BM) \
214  return block_matcher_->GET_OPENCV(); \
215  return sg_block_matcher_->GET_OPENCV(); \
216 } \
217 \
218 inline void StereoProcessor::SET(TYPE param) \
219 { \
220  block_matcher_->SET_OPENCV(param); \
221  sg_block_matcher_->SET_OPENCV(param); \
222 }
223 
224 #if CV_MAJOR_VERSION >= 3
228 STEREO_IMAGE_PROC_OPENCV3(getDisparityRange, setDisparityRange, int, getNumDisparities, setNumDisparities)
230 STEREO_IMAGE_PROC_OPENCV3(getSpeckleSize, setSpeckleSize, int, getSpeckleWindowSize, setSpeckleWindowSize)
232 #else
240 #endif
241 
242 #define STEREO_IMAGE_PROC_BM_ONLY_OPENCV2(GET, SET, TYPE, PARAM) \
243 inline TYPE StereoProcessor::GET() const \
244 { \
245  return block_matcher_.state->PARAM; \
246 } \
247 \
248 inline void StereoProcessor::SET(TYPE param) \
249 { \
250  block_matcher_.state->PARAM = param; \
251 }
252 
253 #define STEREO_IMAGE_PROC_SGBM_ONLY_OPENCV2(GET, SET, TYPE, PARAM) \
254 inline TYPE StereoProcessor::GET() const \
255 { \
256  return sg_block_matcher_.PARAM; \
257 } \
258 \
259 inline void StereoProcessor::SET(TYPE param) \
260 { \
261  sg_block_matcher_.PARAM = param; \
262 }
263 
264 #define STEREO_IMAGE_PROC_ONLY_OPENCV3(MEMBER, GET, SET, TYPE, GET_OPENCV, SET_OPENCV) \
265 inline TYPE StereoProcessor::GET() const \
266 { \
267  return MEMBER->GET_OPENCV(); \
268 } \
269 \
270 inline void StereoProcessor::SET(TYPE param) \
271 { \
272  MEMBER->SET_OPENCV(param); \
273 }
274 
275 // BM only
276 #if CV_MAJOR_VERSION >= 3
279 #else
282 #endif
283 
284 // SGBM specific
285 #if CV_MAJOR_VERSION >= 3
286 // getSgbmMode can return MODE_SGBM = 0, MODE_HH = 1. FullDP == 1 was MODE_HH so we're good
291 #else
296 #endif
297 
298 } //namespace stereo_image_proc
299 
300 #endif
stereo_image_proc::StereoProcessor::POINT_CLOUD
@ POINT_CLOUD
Definition: processor.h:118
stereo_image_proc::StereoProcessor::getP2
int getP2() const
stereo_image_proc::StereoProcessor::setSgbmMode
void setSgbmMode(int fullDP)
stereo_image_proc::StereoProcessor::POINT_CLOUD2
@ POINT_CLOUD2
Definition: processor.h:119
stereo_image_proc::StereoProcessor::RIGHT_RECT_COLOR
@ RIGHT_RECT_COLOR
Definition: processor.h:116
stereo_image_proc::StereoProcessor::setPreFilterCap
void setPreFilterCap(int cap)
stereo_image_proc::StereoImageSet::disparity
stereo_msgs::DisparityImage disparity
Definition: processor.h:114
STEREO_IMAGE_PROC_SGBM_ONLY_OPENCV2
#define STEREO_IMAGE_PROC_SGBM_ONLY_OPENCV2(GET, SET, TYPE, PARAM)
Definition: processor.h:285
stereo_image_proc::StereoImageSet::left
image_proc::ImageSet left
Definition: processor.h:112
stereo_image_proc::StereoProcessor::setPreFilterSize
void setPreFilterSize(int size)
stereo_image_proc::StereoProcessor::LEFT_COLOR
@ LEFT_COLOR
Definition: processor.h:111
STEREO_IMAGE_PROC_ONLY_OPENCV3
#define STEREO_IMAGE_PROC_ONLY_OPENCV3(MEMBER, GET, SET, TYPE, GET_OPENCV, SET_OPENCV)
Definition: processor.h:296
STEREO_IMAGE_PROC_BM_ONLY_OPENCV2
#define STEREO_IMAGE_PROC_BM_ONLY_OPENCV2(GET, SET, TYPE, PARAM)
Definition: processor.h:274
stereo_image_proc::StereoProcessor::sg_block_matcher_
cv::StereoSGBM sg_block_matcher_
Definition: processor.h:209
stereo_image_proc::StereoProcessor::StereoProcessor
StereoProcessor()
Definition: processor.h:91
stereo_image_proc::StereoProcessor::setInterpolation
void setInterpolation(int interp)
Definition: processor.h:222
stereo_image_proc::StereoProcessor::dense_points_
cv::Mat_< cv::Vec3f > dense_points_
Definition: processor.h:213
stereo_image_proc::StereoProcessor::setP2
void setP2(int P2)
stereo_image_proc::StereoProcessor::getDisp12MaxDiff
int getDisp12MaxDiff() const
image_proc::Processor::interpolation_
int interpolation_
stereo_image_proc::StereoImageSet::points
sensor_msgs::PointCloud points
Definition: processor.h:115
stereo_image_proc::StereoProcessor::StereoType
StereoType
Definition: processor.h:103
stereo_image_proc::StereoProcessor::setDisp12MaxDiff
void setDisp12MaxDiff(int disp12MaxDiff)
stereo_image_proc::StereoProcessor::LEFT_RECT_COLOR
@ LEFT_RECT_COLOR
Definition: processor.h:112
stereo_camera_model.h
stereo_image_proc::StereoImageSet::right
image_proc::ImageSet right
Definition: processor.h:113
stereo_image_proc::StereoProcessor::getP1
int getP1() const
stereo_image_proc::StereoProcessor::setStereoType
void setStereoType(StereoType type)
Definition: processor.h:130
stereo_image_proc::StereoProcessor::RIGHT_RECT
@ RIGHT_RECT
Definition: processor.h:114
stereo_image_proc::StereoProcessor::getTextureThreshold
int getTextureThreshold() const
stereo_image_proc::StereoProcessor::getUniquenessRatio
float getUniquenessRatio() const
stereo_image_proc::StereoProcessor::mono_processor_
image_proc::Processor mono_processor_
Definition: processor.h:201
stereo_image_proc::StereoProcessor::BM
@ BM
Definition: processor.h:105
stereo_image_proc::StereoProcessor
Definition: processor.h:87
stereo_image_proc::StereoProcessor::getCorrelationWindowSize
int getCorrelationWindowSize() const
stereo_image_proc::StereoProcessor::getMinDisparity
int getMinDisparity() const
stereo_image_proc::StereoProcessor::DISPARITY
@ DISPARITY
Definition: processor.h:117
stereo_image_proc::StereoProcessor::getInterpolation
int getInterpolation() const
Definition: processor.h:217
image_geometry::StereoCameraModel
stereo_image_proc::StereoProcessor::ALL
@ ALL
Definition: processor.h:124
stereo_image_proc::StereoProcessor::getSpeckleRange
int getSpeckleRange() const
STEREO_IMAGE_PROC_OPENCV2
#define STEREO_IMAGE_PROC_OPENCV2(GET, SET, TYPE, PARAM)
Definition: processor.h:228
stereo_image_proc::StereoProcessor::getStereoType
StereoType getStereoType() const
Definition: processor.h:128
image_proc::Processor
stereo_image_proc::StereoProcessor::setCorrelationWindowSize
void setCorrelationWindowSize(int size)
stereo_image_proc::StereoProcessor::processPoints
void processPoints(const stereo_msgs::DisparityImage &disparity, const cv::Mat &color, const std::string &encoding, const image_geometry::StereoCameraModel &model, sensor_msgs::PointCloud &points) const
Definition: processor.cpp:168
stereo_image_proc::StereoProcessor::processDisparity
void processDisparity(const cv::Mat &left_rect, const cv::Mat &right_rect, const image_geometry::StereoCameraModel &model, stereo_msgs::DisparityImage &disparity) const
Definition: processor.cpp:115
stereo_image_proc::StereoProcessor::setSpeckleSize
void setSpeckleSize(int size)
stereo_image_proc::StereoProcessor::setDisparityRange
void setDisparityRange(int range)
stereo_image_proc::StereoProcessor::getDisparityRange
int getDisparityRange() const
stereo_image_proc::StereoProcessor::block_matcher_
cv::StereoBM block_matcher_
Definition: processor.h:208
stereo_image_proc::StereoProcessor::STEREO_ALL
@ STEREO_ALL
Definition: processor.h:123
stereo_image_proc::StereoProcessor::disparity16_
cv::Mat_< int16_t > disparity16_
Definition: processor.h:203
stereo_image_proc::StereoProcessor::SGBM
@ SGBM
Definition: processor.h:105
stereo_image_proc::StereoProcessor::RIGHT_COLOR
@ RIGHT_COLOR
Definition: processor.h:115
stereo_image_proc
Definition: processor.h:44
stereo_image_proc::StereoProcessor::setMinDisparity
void setMinDisparity(int min_d)
STEREO_IMAGE_PROC_OPENCV3
#define STEREO_IMAGE_PROC_OPENCV3(GET, SET, TYPE, GET_OPENCV, SET_OPENCV)
Definition: processor.h:242
stereo_image_proc::StereoProcessor::setUniquenessRatio
void setUniquenessRatio(float ratio)
stereo_image_proc::StereoProcessor::process
bool process(const sensor_msgs::ImageConstPtr &left_raw, const sensor_msgs::ImageConstPtr &right_raw, const image_geometry::StereoCameraModel &model, StereoImageSet &output, int flags) const
Definition: processor.cpp:74
stereo_image_proc::StereoProcessor::LEFT_MONO
@ LEFT_MONO
Definition: processor.h:109
stereo_image_proc::StereoProcessor::LEFT_RECT
@ LEFT_RECT
Definition: processor.h:110
stereo_image_proc::StereoProcessor::processPoints2
void processPoints2(const stereo_msgs::DisparityImage &disparity, const cv::Mat &color, const std::string &encoding, const image_geometry::StereoCameraModel &model, sensor_msgs::PointCloud2 &points) const
Definition: processor.cpp:267
stereo_image_proc::StereoProcessor::RIGHT_ALL
@ RIGHT_ALL
Definition: processor.h:122
stereo_image_proc::StereoProcessor::RIGHT_MONO
@ RIGHT_MONO
Definition: processor.h:113
stereo_image_proc::StereoProcessor::setTextureThreshold
void setTextureThreshold(int threshold)
stereo_image_proc::StereoProcessor::getSpeckleSize
int getSpeckleSize() const
stereo_image_proc::StereoProcessor::setP1
void setP1(int P1)
stereo_image_proc::StereoImageSet
Definition: processor.h:78
image_proc::ImageSet
stereo_image_proc::StereoProcessor::LEFT_ALL
@ LEFT_ALL
Definition: processor.h:121
stereo_image_proc::StereoProcessor::setSpeckleRange
void setSpeckleRange(int range)
stereo_image_proc::StereoProcessor::current_stereo_algorithm_
StereoType current_stereo_algorithm_
Definition: processor.h:211
stereo_image_proc::StereoProcessor::getPreFilterCap
int getPreFilterCap() const
stereo_image_proc::StereoProcessor::getSgbmMode
int getSgbmMode() const
stereo_image_proc::StereoImageSet::points2
sensor_msgs::PointCloud2 points2
Definition: processor.h:116
stereo_image_proc::StereoProcessor::getPreFilterSize
int getPreFilterSize() const


stereo_image_proc
Author(s): Patrick Mihelich, Kurt Konolige, Jeremy Leibs
autogenerated on Wed Jan 24 2024 03:57:24