Go to the documentation of this file.
34 #ifndef STEREO_IMAGE_PROC_PROCESSOR_H
35 #define STEREO_IMAGE_PROC_PROCESSOR_H
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>
51 sensor_msgs::PointCloud
points;
52 sensor_msgs::PointCloud2
points2;
60 #if CV_MAJOR_VERSION >= 3
150 bool process(
const sensor_msgs::ImageConstPtr& left_raw,
151 const sensor_msgs::ImageConstPtr& right_raw,
157 stereo_msgs::DisparityImage& disparity)
const;
159 void processPoints(
const stereo_msgs::DisparityImage& disparity,
160 const cv::Mat& color,
const std::string& encoding,
162 sensor_msgs::PointCloud& points)
const;
164 const cv::Mat& color,
const std::string& encoding,
166 sensor_msgs::PointCloud2& points)
const;
172 #if CV_MAJOR_VERSION >= 3
196 #define STEREO_IMAGE_PROC_OPENCV2(GET, SET, TYPE, PARAM) \
197 inline TYPE StereoProcessor::GET() const \
199 if (current_stereo_algorithm_ == BM) \
200 return block_matcher_.state->PARAM; \
201 return sg_block_matcher_.PARAM; \
204 inline void StereoProcessor::SET(TYPE param) \
206 block_matcher_.state->PARAM = param; \
207 sg_block_matcher_.PARAM = param; \
210 #define STEREO_IMAGE_PROC_OPENCV3(GET, SET, TYPE, GET_OPENCV, SET_OPENCV) \
211 inline TYPE StereoProcessor::GET() const \
213 if (current_stereo_algorithm_ == BM) \
214 return block_matcher_->GET_OPENCV(); \
215 return sg_block_matcher_->GET_OPENCV(); \
218 inline void StereoProcessor::SET(TYPE param) \
220 block_matcher_->SET_OPENCV(param); \
221 sg_block_matcher_->SET_OPENCV(param); \
224 #if CV_MAJOR_VERSION >= 3
242 #define STEREO_IMAGE_PROC_BM_ONLY_OPENCV2(GET, SET, TYPE, PARAM) \
243 inline TYPE StereoProcessor::GET() const \
245 return block_matcher_.state->PARAM; \
248 inline void StereoProcessor::SET(TYPE param) \
250 block_matcher_.state->PARAM = param; \
253 #define STEREO_IMAGE_PROC_SGBM_ONLY_OPENCV2(GET, SET, TYPE, PARAM) \
254 inline TYPE StereoProcessor::GET() const \
256 return sg_block_matcher_.PARAM; \
259 inline void StereoProcessor::SET(TYPE param) \
261 sg_block_matcher_.PARAM = param; \
264 #define STEREO_IMAGE_PROC_ONLY_OPENCV3(MEMBER, GET, SET, TYPE, GET_OPENCV, SET_OPENCV) \
265 inline TYPE StereoProcessor::GET() const \
267 return MEMBER->GET_OPENCV(); \
270 inline void StereoProcessor::SET(TYPE param) \
272 MEMBER->SET_OPENCV(param); \
276 #if CV_MAJOR_VERSION >= 3
285 #if CV_MAJOR_VERSION >= 3
void setSgbmMode(int fullDP)
void setPreFilterCap(int cap)
stereo_msgs::DisparityImage disparity
#define STEREO_IMAGE_PROC_SGBM_ONLY_OPENCV2(GET, SET, TYPE, PARAM)
image_proc::ImageSet left
void setPreFilterSize(int size)
#define STEREO_IMAGE_PROC_ONLY_OPENCV3(MEMBER, GET, SET, TYPE, GET_OPENCV, SET_OPENCV)
#define STEREO_IMAGE_PROC_BM_ONLY_OPENCV2(GET, SET, TYPE, PARAM)
cv::StereoSGBM sg_block_matcher_
void setInterpolation(int interp)
cv::Mat_< cv::Vec3f > dense_points_
int getDisp12MaxDiff() const
sensor_msgs::PointCloud points
void setDisp12MaxDiff(int disp12MaxDiff)
image_proc::ImageSet right
void setStereoType(StereoType type)
int getTextureThreshold() const
float getUniquenessRatio() const
image_proc::Processor mono_processor_
int getCorrelationWindowSize() const
int getMinDisparity() const
int getInterpolation() const
int getSpeckleRange() const
#define STEREO_IMAGE_PROC_OPENCV2(GET, SET, TYPE, PARAM)
StereoType getStereoType() const
void setCorrelationWindowSize(int size)
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
void processDisparity(const cv::Mat &left_rect, const cv::Mat &right_rect, const image_geometry::StereoCameraModel &model, stereo_msgs::DisparityImage &disparity) const
void setSpeckleSize(int size)
void setDisparityRange(int range)
int getDisparityRange() const
cv::StereoBM block_matcher_
cv::Mat_< int16_t > disparity16_
void setMinDisparity(int min_d)
#define STEREO_IMAGE_PROC_OPENCV3(GET, SET, TYPE, GET_OPENCV, SET_OPENCV)
void setUniquenessRatio(float ratio)
bool process(const sensor_msgs::ImageConstPtr &left_raw, const sensor_msgs::ImageConstPtr &right_raw, const image_geometry::StereoCameraModel &model, StereoImageSet &output, int flags) const
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
void setTextureThreshold(int threshold)
int getSpeckleSize() const
void setSpeckleRange(int range)
StereoType current_stereo_algorithm_
int getPreFilterCap() const
sensor_msgs::PointCloud2 points2
int getPreFilterSize() const
stereo_image_proc
Author(s): Patrick Mihelich, Kurt Konolige, Jeremy Leibs
autogenerated on Wed Jan 24 2024 03:57:24