34 #ifndef STEREO_IMAGE_PROC_PROCESSOR_H 35 #define STEREO_IMAGE_PROC_PROCESSOR_H 37 #include <image_proc/processor.h> 39 #include <stereo_msgs/DisparityImage.h> 40 #include <sensor_msgs/PointCloud.h> 41 #include <sensor_msgs/PointCloud2.h> 59 #if CV_MAJOR_VERSION >= 3 61 block_matcher_ = cv::StereoBM::create();
62 sg_block_matcher_ = cv::StereoSGBM::create(1, 1, 10);
64 : block_matcher_(cv::StereoBM::BASIC_PRESET),
79 LEFT_RECT_COLOR = 1 << 3,
83 RIGHT_RECT_COLOR = 1 << 7,
86 POINT_CLOUD2 = 1 << 10,
88 LEFT_ALL = LEFT_MONO | LEFT_RECT | LEFT_COLOR | LEFT_RECT_COLOR,
89 RIGHT_ALL = RIGHT_MONO | RIGHT_RECT | RIGHT_COLOR | RIGHT_RECT_COLOR,
90 STEREO_ALL = DISPARITY | POINT_CLOUD | POINT_CLOUD2,
91 ALL = LEFT_ALL | RIGHT_ALL | STEREO_ALL
99 int getInterpolation()
const;
100 void setInterpolation(
int interp);
104 int getPreFilterSize()
const;
105 void setPreFilterSize(
int size);
107 int getPreFilterCap()
const;
108 void setPreFilterCap(
int cap);
112 int getCorrelationWindowSize()
const;
113 void setCorrelationWindowSize(
int size);
115 int getMinDisparity()
const;
116 void setMinDisparity(
int min_d);
118 int getDisparityRange()
const;
119 void setDisparityRange(
int range);
123 int getTextureThreshold()
const;
124 void setTextureThreshold(
int threshold);
126 float getUniquenessRatio()
const;
127 void setUniquenessRatio(
float ratio);
129 int getSpeckleSize()
const;
130 void setSpeckleSize(
int size);
132 int getSpeckleRange()
const;
133 void setSpeckleRange(
int range);
136 int getSgbmMode()
const;
137 void setSgbmMode(
int fullDP);
145 int getDisp12MaxDiff()
const;
146 void setDisp12MaxDiff(
int disp12MaxDiff);
149 bool process(
const sensor_msgs::ImageConstPtr& left_raw,
150 const sensor_msgs::ImageConstPtr& right_raw,
154 void processDisparity(
const cv::Mat& left_rect,
const cv::Mat& right_rect,
156 stereo_msgs::DisparityImage&
disparity)
const;
158 void processPoints(
const stereo_msgs::DisparityImage& disparity,
159 const cv::Mat& color,
const std::string& encoding,
161 sensor_msgs::PointCloud&
points)
const;
162 void processPoints2(
const stereo_msgs::DisparityImage& disparity,
163 const cv::Mat& color,
const std::string& encoding,
165 sensor_msgs::PointCloud2& points)
const;
171 #if CV_MAJOR_VERSION >= 3 172 mutable cv::Ptr<cv::StereoBM> block_matcher_;
173 mutable cv::Ptr<cv::StereoSGBM> sg_block_matcher_;
186 return mono_processor_.interpolation_;
191 mono_processor_.interpolation_ = interp;
195 #define STEREO_IMAGE_PROC_OPENCV2(GET, SET, TYPE, PARAM) \ 196 inline TYPE StereoProcessor::GET() const \ 198 if (current_stereo_algorithm_ == BM) \ 199 return block_matcher_.state->PARAM; \ 200 return sg_block_matcher_.PARAM; \ 203 inline void StereoProcessor::SET(TYPE param) \ 205 block_matcher_.state->PARAM = param; \ 206 sg_block_matcher_.PARAM = param; \ 209 #define STEREO_IMAGE_PROC_OPENCV3(GET, SET, TYPE, GET_OPENCV, SET_OPENCV) \ 210 inline TYPE StereoProcessor::GET() const \ 212 if (current_stereo_algorithm_ == BM) \ 213 return block_matcher_->GET_OPENCV(); \ 214 return sg_block_matcher_->GET_OPENCV(); \ 217 inline void StereoProcessor::SET(TYPE param) \ 219 block_matcher_->SET_OPENCV(param); \ 220 sg_block_matcher_->SET_OPENCV(param); \ 223 #if CV_MAJOR_VERSION >= 3 241 #define STEREO_IMAGE_PROC_BM_ONLY_OPENCV2(GET, SET, TYPE, PARAM) \ 242 inline TYPE StereoProcessor::GET() const \ 244 return block_matcher_.state->PARAM; \ 247 inline void StereoProcessor::SET(TYPE param) \ 249 block_matcher_.state->PARAM = param; \ 252 #define STEREO_IMAGE_PROC_SGBM_ONLY_OPENCV2(GET, SET, TYPE, PARAM) \ 253 inline TYPE StereoProcessor::GET() const \ 255 return sg_block_matcher_.PARAM; \ 258 inline void StereoProcessor::SET(TYPE param) \ 260 sg_block_matcher_.PARAM = param; \ 263 #define STEREO_IMAGE_PROC_ONLY_OPENCV3(MEMBER, GET, SET, TYPE, GET_OPENCV, SET_OPENCV) \ 264 inline TYPE StereoProcessor::GET() const \ 266 return MEMBER->GET_OPENCV(); \ 269 inline void StereoProcessor::SET(TYPE param) \ 271 MEMBER->SET_OPENCV(param); \ 275 #if CV_MAJOR_VERSION >= 3 284 #if CV_MAJOR_VERSION >= 3 #define STEREO_IMAGE_PROC_ONLY_OPENCV3(MEMBER, GET, SET, TYPE, GET_OPENCV, SET_OPENCV)
void setStereoType(StereoType type)
int getInterpolation() const
#define STEREO_IMAGE_PROC_SGBM_ONLY_OPENCV2(GET, SET, TYPE, PARAM)
image_proc::Processor mono_processor_
cv::Mat_< int16_t > disparity16_
#define STEREO_IMAGE_PROC_BM_ONLY_OPENCV2(GET, SET, TYPE, PARAM)
image_proc::ImageSet left
cv::Mat_< cv::Vec3f > dense_points_
#define STEREO_IMAGE_PROC_OPENCV2(GET, SET, TYPE, PARAM)
sensor_msgs::PointCloud points
#define STEREO_IMAGE_PROC_OPENCV3(GET, SET, TYPE, GET_OPENCV, SET_OPENCV)
stereo_msgs::DisparityImage disparity
StereoType getStereoType() const
cv::StereoBM block_matcher_
StereoType current_stereo_algorithm_
cv::StereoSGBM sg_block_matcher_
image_proc::ImageSet right
sensor_msgs::PointCloud2 points2
void setInterpolation(int interp)