Public Types | Public Member Functions | Private Attributes
stereo_image_proc::StereoProcessor Class Reference

#include <processor.h>

List of all members.

Public Types

enum  {
  LEFT_MONO = 1 << 0, LEFT_RECT = 1 << 1, LEFT_COLOR = 1 << 2, LEFT_RECT_COLOR = 1 << 3,
  RIGHT_MONO = 1 << 4, RIGHT_RECT = 1 << 5, RIGHT_COLOR = 1 << 6, RIGHT_RECT_COLOR = 1 << 7,
  DISPARITY = 1 << 8, POINT_CLOUD = 1 << 9, POINT_CLOUD2 = 1 << 10, LEFT_ALL = LEFT_MONO | LEFT_RECT | LEFT_COLOR | LEFT_RECT_COLOR,
  RIGHT_ALL = RIGHT_MONO | RIGHT_RECT | RIGHT_COLOR | RIGHT_RECT_COLOR, STEREO_ALL = DISPARITY | POINT_CLOUD | POINT_CLOUD2, ALL = LEFT_ALL | RIGHT_ALL | STEREO_ALL
}

Public Member Functions

int getCorrelationWindowSize () const
int getDisparityRange () const
int getInterpolation () const
int getMinDisparity () const
int getPreFilterCap () const
int getPreFilterSize () const
int getSpeckleRange () const
int getSpeckleSize () const
int getTextureThreshold () const
float getUniquenessRatio () const
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 processDisparity (const cv::Mat &left_rect, const cv::Mat &right_rect, const image_geometry::StereoCameraModel &model, stereo_msgs::DisparityImage &disparity) const
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 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 setCorrelationWindowSize (int size)
void setDisparityRange (int range)
void setInterpolation (int interp)
void setMinDisparity (int min_d)
void setPreFilterCap (int cap)
void setPreFilterSize (int size)
void setSpeckleRange (int range)
void setSpeckleSize (int size)
void setTextureThreshold (int threshold)
void setUniquenessRatio (float ratio)
 StereoProcessor ()

Private Attributes

cv::StereoBM block_matcher_
cv::Mat_< cv::Vec3f > dense_points_
cv::Mat_< int16_t > disparity16_
cv::Mat_< uint32_t > labels_
image_proc::Processor mono_processor_
cv::Mat_< uint8_t > region_types_
cv::Mat_< uint32_t > wavefront_

Detailed Description

Definition at line 54 of file processor.h.


Member Enumeration Documentation

anonymous enum
Enumerator:
LEFT_MONO 
LEFT_RECT 
LEFT_COLOR 
LEFT_RECT_COLOR 
RIGHT_MONO 
RIGHT_RECT 
RIGHT_COLOR 
RIGHT_RECT_COLOR 
DISPARITY 
POINT_CLOUD 
POINT_CLOUD2 
LEFT_ALL 
RIGHT_ALL 
STEREO_ALL 
ALL 

Definition at line 63 of file processor.h.


Constructor & Destructor Documentation

Definition at line 58 of file processor.h.


Member Function Documentation

Definition at line 181 of file processor.h.

Definition at line 201 of file processor.h.

Definition at line 151 of file processor.h.

Definition at line 191 of file processor.h.

Definition at line 171 of file processor.h.

Definition at line 161 of file processor.h.

Definition at line 241 of file processor.h.

Definition at line 231 of file processor.h.

Definition at line 211 of file processor.h.

Definition at line 221 of file processor.h.

bool stereo_image_proc::StereoProcessor::process ( const sensor_msgs::ImageConstPtr &  left_raw,
const sensor_msgs::ImageConstPtr &  right_raw,
const image_geometry::StereoCameraModel model,
StereoImageSet output,
int  flags 
) const

Definition at line 42 of file processor.cpp.

void stereo_image_proc::StereoProcessor::processDisparity ( const cv::Mat &  left_rect,
const cv::Mat &  right_rect,
const image_geometry::StereoCameraModel model,
stereo_msgs::DisparityImage &  disparity 
) const
Todo:
is_bigendian? :)
Todo:
Window of (potentially) valid disparities

Definition at line 83 of file processor.cpp.

void stereo_image_proc::StereoProcessor::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 at line 127 of file processor.cpp.

void stereo_image_proc::StereoProcessor::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 at line 204 of file processor.cpp.

Definition at line 186 of file processor.h.

Definition at line 206 of file processor.h.

Definition at line 156 of file processor.h.

Definition at line 196 of file processor.h.

Definition at line 176 of file processor.h.

Definition at line 166 of file processor.h.

Definition at line 246 of file processor.h.

Definition at line 236 of file processor.h.

Definition at line 216 of file processor.h.

Definition at line 226 of file processor.h.


Member Data Documentation

cv::StereoBM stereo_image_proc::StereoProcessor::block_matcher_ [mutable, private]

Definition at line 141 of file processor.h.

cv::Mat_<cv::Vec3f> stereo_image_proc::StereoProcessor::dense_points_ [mutable, private]

Definition at line 147 of file processor.h.

cv::Mat_<int16_t> stereo_image_proc::StereoProcessor::disparity16_ [mutable, private]

Definition at line 140 of file processor.h.

cv::Mat_<uint32_t> stereo_image_proc::StereoProcessor::labels_ [mutable, private]

Definition at line 143 of file processor.h.

Definition at line 138 of file processor.h.

cv::Mat_<uint8_t> stereo_image_proc::StereoProcessor::region_types_ [mutable, private]

Definition at line 145 of file processor.h.

cv::Mat_<uint32_t> stereo_image_proc::StereoProcessor::wavefront_ [mutable, private]

Definition at line 144 of file processor.h.


The documentation for this class was generated from the following files:


stereo_image_proc
Author(s): Patrick Mihelich, Kurt Konolige, Jeremy Leibs
autogenerated on Mon Oct 6 2014 00:46:19