#include <image_proc/processor.h>
#include <image_geometry/stereo_camera_model.h>
#include <stereo_msgs/DisparityImage.h>
#include <sensor_msgs/PointCloud.h>
#include <sensor_msgs/PointCloud2.h>
Go to the source code of this file.
Classes | |
struct | stereo_image_proc::StereoImageSet |
class | stereo_image_proc::StereoProcessor |
Namespaces | |
namespace | stereo_image_proc |
Defines | |
#define | STEREO_IMAGE_PROC_BM_ONLY_OPENCV2(GET, SET, TYPE, PARAM) |
#define | STEREO_IMAGE_PROC_ONLY_OPENCV3(MEMBER, GET, SET, TYPE, GET_OPENCV, SET_OPENCV) |
#define | STEREO_IMAGE_PROC_OPENCV2(GET, SET, TYPE, PARAM) |
#define | STEREO_IMAGE_PROC_OPENCV3(GET, SET, TYPE, GET_OPENCV, SET_OPENCV) |
#define | STEREO_IMAGE_PROC_SGBM_ONLY_OPENCV2(GET, SET, TYPE, PARAM) |
#define STEREO_IMAGE_PROC_BM_ONLY_OPENCV2 | ( | GET, | |
SET, | |||
TYPE, | |||
PARAM | |||
) |
inline TYPE StereoProcessor::GET() const \ { \ return block_matcher_.state->PARAM; \ } \ \ inline void StereoProcessor::SET(TYPE param) \ { \ block_matcher_.state->PARAM = param; \ }
Definition at line 241 of file processor.h.
#define STEREO_IMAGE_PROC_ONLY_OPENCV3 | ( | MEMBER, | |
GET, | |||
SET, | |||
TYPE, | |||
GET_OPENCV, | |||
SET_OPENCV | |||
) |
inline TYPE StereoProcessor::GET() const \ { \ return MEMBER->GET_OPENCV(); \ } \ \ inline void StereoProcessor::SET(TYPE param) \ { \ MEMBER->SET_OPENCV(param); \ }
Definition at line 263 of file processor.h.
#define STEREO_IMAGE_PROC_OPENCV2 | ( | GET, | |
SET, | |||
TYPE, | |||
PARAM | |||
) |
inline TYPE StereoProcessor::GET() const \ { \ if (current_stereo_algorithm_ == BM) \ return block_matcher_.state->PARAM; \ return sg_block_matcher_.PARAM; \ } \ \ inline void StereoProcessor::SET(TYPE param) \ { \ block_matcher_.state->PARAM = param; \ sg_block_matcher_.PARAM = param; \ }
Definition at line 195 of file processor.h.
#define STEREO_IMAGE_PROC_OPENCV3 | ( | GET, | |
SET, | |||
TYPE, | |||
GET_OPENCV, | |||
SET_OPENCV | |||
) |
inline TYPE StereoProcessor::GET() const \ { \ if (current_stereo_algorithm_ == BM) \ return block_matcher_->GET_OPENCV(); \ return sg_block_matcher_->GET_OPENCV(); \ } \ \ inline void StereoProcessor::SET(TYPE param) \ { \ block_matcher_->SET_OPENCV(param); \ sg_block_matcher_->SET_OPENCV(param); \ }
Definition at line 209 of file processor.h.
#define STEREO_IMAGE_PROC_SGBM_ONLY_OPENCV2 | ( | GET, | |
SET, | |||
TYPE, | |||
PARAM | |||
) |
inline TYPE StereoProcessor::GET() const \ { \ return sg_block_matcher_.PARAM; \ } \ \ inline void StereoProcessor::SET(TYPE param) \ { \ sg_block_matcher_.PARAM = param; \ }
Definition at line 252 of file processor.h.