Public Member Functions | Static Public Member Functions | Public Attributes | Private Member Functions
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 87 of file filtering.h.


Constructor & Destructor Documentation

A class providing an interface to depth image segmenter

Parameters:
normalsNormals 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.

Destructor - obviously, it destructs this class

Definition at line 63 of file filtering.cpp.


Member Function Documentation

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

Parameters:
thresholdNot 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:
planePlane equation
depthDepth image
maskRegion mask
pointsVector of seed points
i_tileRow tile offset
j_tileColumn tile offset
tileSizeSize of tile
indexIndex of filled region
min_planeDistanceMaximal distance from plane to be filled

Definition at line 639 of file filtering.cpp.

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:
tileTile subimage of depth data
tileMaskMask subimage
pointMaskPoint mask subimage
pointsVector of tile points
indexIndex of filling region
planeEquation of filled plane
ioffsetRow offset of tile
joffsetColumn offset of tile
min_planeDistanceMinimal distance from plane to fill

Definition at line 539 of file filtering.cpp.

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:
planeExtracted plane
tileTile subimage of depth data
tileMaskMask subimage
ioffsetRow offset of tile
joffsetColumn offset of tile
indexIndex of filling region

Definition at line 612 of file filtering.cpp.

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:
srcInput CV_16UC depth matrix (raw input from kinect)
dstFinal gradient image
sizeSize of neigborhood (number of maximal pixel distance)
differenceThresholdDifference from center depth to mark a pixel as anomal

Definition at line 288 of file filtering.cpp.

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:
srcInput CV_16UC depth matrix (raw input from kinect)
dstFinal gradient image
sizeSize of neigborhood (number of maximal pixel distance)
differenceThresholdDifference from center normal to mark a pixel as anomal

Definition at line 319 of file filtering.cpp.

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:
srcInput CV_16UC depth matrix (raw input from kinect)
dstFinal gradient image
differenceThresholdDifference from expected plane threshold to mark a pixel as anomal
sizeSize of neigborhood (number of maximal pixel distance)
sobelSizeSize of sobel kernel used for gradient image computation

Definition at line 362 of file filtering.cpp.

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:
srcInput CV_16UC depth matrix (raw input from kinect)
cam_infoCamera info message (ROS)
minimumPlaneDistanceMinimal distance threshold from triangle plane in whole tile (in meters)
minimumTriDistanceMinimal distance threshold from triangle plane in triangle flood fill (in meters)
minimumFloodDistanceMinimal distance threshold from triangle plane in whole image (in meters)
tileSizeTile size
smallestTriangleAreaSmalest randomly found triangle to be considered for plane computation (in pixels^2)
minRegionSizeMinimal region size to be considered
minCandidatesMinimal number of pixels in tile to start a RANSAC

Definition at line 760 of file filtering.cpp.

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:
srcInput CV_16UC depth matrix (raw input from kinect)
cam_infoCamera info message (ROS)
typeType of watershed input - one of WatershedType constants
See also:
WatershedType
Parameters:
seedThresholdThreshold which specifies number of anomal neighbors for selecting this pixel as seed for watershed
alphaIt is always size of neigborhood which is considered for searching the image in watershed preprocessing. If 0.0, default is selected.
betaWhen 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.
gammaIt is used only in combined and predictor. In combined, it specifiesd normal difference threshold, in predictor a sobel size.
See also:
Normals()

Definition at line 164 of file filtering.cpp.


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 190 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 176 of file filtering.h.

Region matrix (filled after "Regions" methods call)

See also:
watershedRegions()
independentTileRegions()

Definition at line 169 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 183 of file filtering.h.


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


srs_env_model_percp
Author(s): Rostislav Hulik (ihulik@fit.vutbr.cz), Tomas Hodan, Michal Spanel (spanel@fit.vutbr.cz)
autogenerated on Mon Oct 6 2014 08:07:23