$search

but_plane_detector::Regions Class Reference

#include <filtering.h>

List of all members.

Public Member Functions

bool computeStatistics (float threshold)
void independentTileRegions (cv::Mat &src, const sensor_msgs::CameraInfoConstPtr &cam_info, float minimumPlaneDistance=0.01, float minimumTriDistance=0.02, float minimumFloodDistance=0.05, int tileSize=30, int smallestTriangleArea=100, int minRegionSize=10, int minCandidates=10)
 Regions (Normals *normals=NULL)
void watershedRegions (cv::Mat &src, const sensor_msgs::CameraInfoConstPtr &cam_info, int type=WatershedType::Combined, int seedThreshold=1, float alpha=0.0, float beta=0.0, float gamma=0.0)
 ~Regions ()

Static Public Member Functions

static void gradientDepthDifference (cv::Mat &src, cv::Mat &dst, int size, float differenceThreshold)
static void gradientNormalDifference (cv::Mat &src, cv::Mat &dst, int size, float differenceThreshold)
static void gradientPlanePredictor (cv::Mat &src, cv::Mat &dst, float differenceThreshold=0.02, int size=2, int sobelSize=5)

Public Attributes

Normalsm_normals
cv::Mat m_planes
cv::Mat m_regionMatrix
cv::Mat m_stddeviation

Private Member Functions

void fillEverything (Plane< float > &plane, cv::Mat &depth, cv::Mat &mask, cv::Mat &points, int i_tile, int j_tile, int tileSize, int index, float min_planeDistance=0.05)
int floodFillTile (cv::Mat &tile, cv::Mat &tileMask, cv::Mat &pointMask, cv::Vec3f *points, int index, Plane< float > &plane, int ioffset, int joffset, float min_planeDistance=0.02)
void getLeastSquaresAndBorder (Plane< float > &plane, cv::Mat &tile, cv::Mat &tileMask, int ioffset, int joffset, int index)

Detailed Description

Class providing an interface to depth image segmentation

Definition at line 85 of file filtering.h.


Constructor & Destructor Documentation

but_plane_detector::Regions::Regions ( Normals normals = NULL  ) 

A class providing an interface to depth image segmenter

Parameters:
normals Normals object with precomputed real points and normals - not necessary - only if you do not want to compute it in this module (for speed reasons)
See also:
Normals()

Definition at line 55 of file filtering.cpp.

but_plane_detector::Regions::~Regions (  ) 

Destructor - obviously, it destructs this class

Definition at line 63 of file filtering.cpp.


Member Function Documentation

bool but_plane_detector::Regions::computeStatistics ( float  threshold  ) 

Method computes from m_regionMatrix statistical information (fills m_planes and m_stddeviation matrices)

Parameters:
threshold Not used now (TODO)

Definition at line 73 of file filtering.cpp.

void but_plane_detector::Regions::fillEverything ( Plane< float > &  plane,
cv::Mat &  depth,
cv::Mat &  mask,
cv::Mat &  points,
int  i_tile,
int  j_tile,
int  tileSize,
int  index,
float  min_planeDistance = 0.05 
) [private]

Auxiliary function for filling entire image from mask seed (until threshold from plane is met)

Parameters:
plane Plane equation
depth Depth image
mask Region mask
points Vector of seed points
i_tile Row tile offset
j_tile Column tile offset
tileSize Size of tile
index Index of filled region
min_planeDistance Maximal distance from plane to be filled
int but_plane_detector::Regions::floodFillTile ( cv::Mat &  tile,
cv::Mat &  tileMask,
cv::Mat &  pointMask,
cv::Vec3f *  points,
int  index,
Plane< float > &  plane,
int  ioffset,
int  joffset,
float  min_planeDistance = 0.02 
) [private]

Auxiliary method which flood fills a tile untill min_planeDistance threshold difference is met

Parameters:
tile Tile subimage of depth data
tileMask Mask subimage
pointMask Point mask subimage
points Vector of tile points
index Index of filling region
plane Equation of filled plane
ioffset Row offset of tile
joffset Column offset of tile
min_planeDistance Minimal distance from plane to fill
void but_plane_detector::Regions::getLeastSquaresAndBorder ( Plane< float > &  plane,
cv::Mat &  tile,
cv::Mat &  tileMask,
int  ioffset,
int  joffset,
int  index 
) [private]

Auxiliary function extracts current region's plane using LSQ

Parameters:
plane Extracted plane
tile Tile subimage of depth data
tileMask Mask subimage
ioffset Row offset of tile
joffset Column offset of tile
index Index of filling region
static void but_plane_detector::Regions::gradientDepthDifference ( cv::Mat &  src,
cv::Mat &  dst,
int  size,
float  differenceThreshold 
) [static]

Method converts an input image into gradient image using comparison of depth data

Parameters:
src Input CV_16UC depth matrix (raw input from kinect)
dst Final gradient image
size Size of neigborhood (number of maximal pixel distance)
differenceThreshold Difference from center depth to mark a pixel as anomal
static void but_plane_detector::Regions::gradientNormalDifference ( cv::Mat &  src,
cv::Mat &  dst,
int  size,
float  differenceThreshold 
) [static]

Method converts an input image into gradient image using comparison of normals

Parameters:
src Input CV_16UC depth matrix (raw input from kinect)
dst Final gradient image
size Size of neigborhood (number of maximal pixel distance)
differenceThreshold Difference from center normal to mark a pixel as anomal
static void but_plane_detector::Regions::gradientPlanePredictor ( cv::Mat &  src,
cv::Mat &  dst,
float  differenceThreshold = 0.02,
int  size = 2,
int  sobelSize = 5 
) [static]

Method converts an input image into gradient image using expected plane prediction. Pixel value is number of pixels around which are not in difference threshold from expected plane.

Parameters:
src Input CV_16UC depth matrix (raw input from kinect)
dst Final gradient image
differenceThreshold Difference from expected plane threshold to mark a pixel as anomal
size Size of neigborhood (number of maximal pixel distance)
sobelSize Size of sobel kernel used for gradient image computation
void but_plane_detector::Regions::independentTileRegions ( cv::Mat &  src,
const sensor_msgs::CameraInfoConstPtr cam_info,
float  minimumPlaneDistance = 0.01,
float  minimumTriDistance = 0.02,
float  minimumFloodDistance = 0.05,
int  tileSize = 30,
int  smallestTriangleArea = 100,
int  minRegionSize = 10,
int  minCandidates = 10 
)

Method segments a depth image using own tile plane searching RANSAC method.

Parameters:
src Input CV_16UC depth matrix (raw input from kinect)
cam_info Camera info message (ROS)
minimumPlaneDistance Minimal distance threshold from triangle plane in whole tile (in meters)
minimumTriDistance Minimal distance threshold from triangle plane in triangle flood fill (in meters)
minimumFloodDistance Minimal distance threshold from triangle plane in whole image (in meters)
tileSize Tile size
smallestTriangleArea Smalest randomly found triangle to be considered for plane computation (in pixels^2)
minRegionSize Minimal region size to be considered
minCandidates Minimal number of pixels in tile to start a RANSAC
void but_plane_detector::Regions::watershedRegions ( cv::Mat &  src,
const sensor_msgs::CameraInfoConstPtr cam_info,
int  type = WatershedType::Combined,
int  seedThreshold = 1,
float  alpha = 0.0,
float  beta = 0.0,
float  gamma = 0.0 
)

Method which segments a depth image with watershed algorithm. There is several approaches, so please be aware of input parameters

Parameters:
src Input CV_16UC depth matrix (raw input from kinect)
cam_info Camera info message (ROS)
type Type of watershed input - one of WatershedType constants
See also:
WatershedType
Parameters:
seedThreshold Threshold which specifies number of anomal neighbors for selecting this pixel as seed for watershed
alpha It is always size of neigborhood which is considered for searching the image in watershed preprocessing. If 0.0, default is selected.
beta When simple preprocessing is selected (depth, normal, predictor), it is always a threshold for selecting anomal neighbors (in depth is in milimeters, normal is in radians ). If combined type is selected, it represents a depth difference.
gamma It is used only in combined and predictor. In combined, it specifiesd normal difference threshold, in predictor a sobel size.
See also:
Normals()

Member Data Documentation

Instance of Normals object - precomputed real point positions and normals. Standard is null if not specified otherwise in constructor or in Region method Freed in destructor!

Definition at line 188 of file filtering.h.

Computed planes matrix (Vec4f type, each component represents component of computed region normal) Filled after computeStatistics method

See also:
computeStatistics()

Definition at line 174 of file filtering.h.

Region matrix (filled after "Regions" methods call)

See also:
watershedRegions()
independentTileRegions()

Definition at line 167 of file filtering.h.

Computed standard deviation of region pixels normals from region mean normal Filled after computeStatistics method

See also:
computeStatistics()

Definition at line 181 of file filtering.h.


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


srs_env_model_percp
Author(s): Rostislav Hulik (ihulik@fit.vutbr.cz), Tomas Hodan, Michal Spanel (spanel@fit.vutbr.cz)
autogenerated on Tue Mar 5 14:55:20 2013