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 20 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 29 of file processor.h.


Constructor & Destructor Documentation

stereo_image_proc::StereoProcessor::StereoProcessor (  )  [inline]

Definition at line 24 of file processor.h.


Member Function Documentation

int stereo_image_proc::StereoProcessor::getCorrelationWindowSize (  )  const [inline]

Definition at line 147 of file processor.h.

int stereo_image_proc::StereoProcessor::getDisparityRange (  )  const [inline]

Definition at line 167 of file processor.h.

int stereo_image_proc::StereoProcessor::getInterpolation (  )  const [inline]

Definition at line 117 of file processor.h.

int stereo_image_proc::StereoProcessor::getMinDisparity (  )  const [inline]

Definition at line 157 of file processor.h.

int stereo_image_proc::StereoProcessor::getPreFilterCap (  )  const [inline]

Definition at line 137 of file processor.h.

int stereo_image_proc::StereoProcessor::getPreFilterSize (  )  const [inline]

Definition at line 127 of file processor.h.

int stereo_image_proc::StereoProcessor::getSpeckleRange (  )  const [inline]

Definition at line 207 of file processor.h.

int stereo_image_proc::StereoProcessor::getSpeckleSize (  )  const [inline]

Definition at line 197 of file processor.h.

int stereo_image_proc::StereoProcessor::getTextureThreshold (  )  const [inline]

Definition at line 177 of file processor.h.

float stereo_image_proc::StereoProcessor::getUniquenessRatio (  )  const [inline]

Definition at line 187 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 5 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 46 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 90 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 167 of file processor.cpp.

void stereo_image_proc::StereoProcessor::setCorrelationWindowSize ( int  size  )  [inline]

Definition at line 152 of file processor.h.

void stereo_image_proc::StereoProcessor::setDisparityRange ( int  range  )  [inline]

Definition at line 172 of file processor.h.

void stereo_image_proc::StereoProcessor::setInterpolation ( int  interp  )  [inline]

Definition at line 122 of file processor.h.

void stereo_image_proc::StereoProcessor::setMinDisparity ( int  min_d  )  [inline]

Definition at line 162 of file processor.h.

void stereo_image_proc::StereoProcessor::setPreFilterCap ( int  cap  )  [inline]

Definition at line 142 of file processor.h.

void stereo_image_proc::StereoProcessor::setPreFilterSize ( int  size  )  [inline]

Definition at line 132 of file processor.h.

void stereo_image_proc::StereoProcessor::setSpeckleRange ( int  range  )  [inline]

Definition at line 212 of file processor.h.

void stereo_image_proc::StereoProcessor::setSpeckleSize ( int  size  )  [inline]

Definition at line 202 of file processor.h.

void stereo_image_proc::StereoProcessor::setTextureThreshold ( int  threshold  )  [inline]

Definition at line 182 of file processor.h.

void stereo_image_proc::StereoProcessor::setUniquenessRatio ( float  ratio  )  [inline]

Definition at line 192 of file processor.h.


Member Data Documentation

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

Definition at line 107 of file processor.h.

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

Definition at line 113 of file processor.h.

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

Definition at line 106 of file processor.h.

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

Definition at line 109 of file processor.h.

image_proc::Processor stereo_image_proc::StereoProcessor::mono_processor_ [private]

Definition at line 104 of file processor.h.

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

Definition at line 111 of file processor.h.

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

Definition at line 110 of file processor.h.


The documentation for this class was generated from the following files:
 All Classes Namespaces Files Functions Variables Typedefs Enumerator Friends


stereo_image_proc
Author(s): Patrick Mihelich, Kurt Konolige, Jeremy Leibs
autogenerated on Fri Jan 11 12:01:40 2013