Public Types | Public Member Functions | Private Types | Private Member Functions | Private Attributes
pcl::ihs::InputDataProcessing Class Reference

Bundles methods that are applied to the input data from the sensor. More...

#include <input_data_processing.h>

List of all members.

Public Types

typedef pcl::PointCloud
< PointXYZRGBA
CloudXYZRGBA
typedef CloudXYZRGBA::ConstPtr CloudXYZRGBAConstPtr
typedef CloudXYZRGBA::Ptr CloudXYZRGBAPtr
typedef pcl::PointCloud
< PointXYZRGBNormal
CloudXYZRGBNormal
typedef CloudXYZRGBNormal::ConstPtr CloudXYZRGBNormalConstPtr
typedef CloudXYZRGBNormal::Ptr CloudXYZRGBNormalPtr
typedef pcl::PointXYZRGBA PointXYZRGBA
typedef pcl::PointXYZRGBNormal PointXYZRGBNormal

Public Member Functions

bool calculateNormals (const CloudXYZRGBAConstPtr &cloud_in, CloudXYZRGBNormalPtr &cloud_out) const
 Calculate the normals of the input cloud.
 InputDataProcessing ()
 Constructor.
bool segment (const CloudXYZRGBAConstPtr &cloud_in, CloudXYZRGBNormalPtr &cloud_out, CloudXYZRGBNormalPtr &cloud_discarded) const
 Apply the segmentation on the input cloud (XYZ and HSV).
void setXMin (const float x_min)
 Points outside of X - Y - Z - min / max are discarded. The unit is cm. The min values must be smaller than the max values.
void setXMax (const float x_max)
void setYMin (const float y_min)
void setYMax (const float y_max)
void setZMin (const float z_min)
void setZMax (const float z_max)
float getXMin () const
float getXMax () const
float getYMin () const
float getYMax () const
float getZMin () const
float getZMax () const
void setHMin (const float h_min)
 Simple color segmentation in the HSV color space. Points inside of H - S - V min / max are discarded. H must be in the range 0 and 360, S and V in the range 0 and 1.
void setHMax (const float h_max)
void setSMin (const float s_min)
void setSMax (const float s_max)
void setVMin (const float v_min)
void setVMax (const float v_max)
float getHMin () const
float getHMax () const
float getSMin () const
float getSMax () const
float getVMin () const
float getVMax () const
void setColorSegmentationInverted (const bool hsv_inverted)
 If true the color values inside of H - S - V min / max are accepted instead of discarded.
bool getColorSegmentationInverted () const
void setColorSegmentationEnabled (const bool hsv_enabled)
 Enable / disable the color segmentation.
bool getColorSegmentationEnabled () const
void setXYZErodeSize (const unsigned int size)
 The XYZ mask is eroded with a kernel of this size.
unsigned int getXYZErodeSize () const
void setHSVDilateSize (const unsigned int size)
 The HSV mask is dilated with a kernel of this size.
unsigned int getHSVDilateSize () const

Private Types

typedef pcl::PointCloud< NormalCloudNormals
typedef boost::shared_ptr
< const CloudNormals
CloudNormalsConstPtr
typedef boost::shared_ptr
< CloudNormals
CloudNormalsPtr
typedef Eigen::Matrix< bool,
Eigen::Dynamic, Eigen::Dynamic > 
MatrixXb
typedef Eigen::MatrixXi MatrixXi
typedef pcl::Normal Normal
typedef
pcl::IntegralImageNormalEstimation
< PointXYZRGBA, Normal
NormalEstimation
typedef boost::shared_ptr
< const NormalEstimation
NormalEstimationConstPtr
typedef boost::shared_ptr
< NormalEstimation
NormalEstimationPtr

Private Member Functions

void dilate (MatrixXb &mask, const int k) const
 Dilates the input mask k times with a diamond shaped structuring element.
void erode (MatrixXb &mask, const int k) const
 Erodes the input mask k times with a diamond shaped structuring element.
MatrixXi manhattan (const MatrixXb &mat, const bool comp) const
 Calculates the manhattan distance map for the input matrix.
void RGBToHSV (const unsigned char r, const unsigned char g, const unsigned char b, float &h, float &s, float &v) const
 Conversion from the RGB to HSV color space.

Private Attributes

float h_max_
float h_min_
bool hsv_enabled_
bool hsv_inverted_
NormalEstimationPtr normal_estimation_
float s_max_
float s_min_
unsigned int size_dilate_
unsigned int size_erode_
float v_max_
float v_min_
float x_max_
float x_min_
float y_max_
float y_min_
float z_max_
float z_min_

Detailed Description

Bundles methods that are applied to the input data from the sensor.

Author:
Martin Saelzle

Definition at line 71 of file input_data_processing.h.


Member Typedef Documentation

Definition at line 173 of file input_data_processing.h.

typedef boost::shared_ptr<const CloudNormals> pcl::ihs::InputDataProcessing::CloudNormalsConstPtr [private]

Definition at line 175 of file input_data_processing.h.

typedef boost::shared_ptr<CloudNormals> pcl::ihs::InputDataProcessing::CloudNormalsPtr [private]

Definition at line 174 of file input_data_processing.h.

Definition at line 76 of file input_data_processing.h.

Definition at line 78 of file input_data_processing.h.

Definition at line 77 of file input_data_processing.h.

Definition at line 81 of file input_data_processing.h.

Definition at line 83 of file input_data_processing.h.

Definition at line 82 of file input_data_processing.h.

typedef Eigen::Matrix<bool, Eigen::Dynamic, Eigen::Dynamic> pcl::ihs::InputDataProcessing::MatrixXb [private]

Definition at line 181 of file input_data_processing.h.

typedef Eigen::MatrixXi pcl::ihs::InputDataProcessing::MatrixXi [private]

Definition at line 182 of file input_data_processing.h.

Definition at line 172 of file input_data_processing.h.

Definition at line 177 of file input_data_processing.h.

Definition at line 179 of file input_data_processing.h.

Definition at line 178 of file input_data_processing.h.

Definition at line 75 of file input_data_processing.h.

Definition at line 80 of file input_data_processing.h.


Constructor & Destructor Documentation

Constructor.

Definition at line 49 of file input_data_processing.cpp.


Member Function Documentation

Calculate the normals of the input cloud.

Parameters:
[in]cloud_inThe input cloud.
[out]cloud_outInput cloud with normals appended.
Returns:
true if success.
Note:
Converts from m to cm.

Definition at line 214 of file input_data_processing.cpp.

void pcl::ihs::InputDataProcessing::dilate ( MatrixXb mask,
const int  k 
) const [private]

Dilates the input mask k times with a diamond shaped structuring element.

See also:
http://ostermiller.org/dilate_and_erode.html

Definition at line 277 of file input_data_processing.cpp.

void pcl::ihs::InputDataProcessing::erode ( MatrixXb mask,
const int  k 
) const [private]

Erodes the input mask k times with a diamond shaped structuring element.

See also:
http://ostermiller.org/dilate_and_erode.html

Definition at line 269 of file input_data_processing.cpp.

Definition at line 155 of file input_data_processing.h.

Definition at line 149 of file input_data_processing.h.

float pcl::ihs::InputDataProcessing::getHMax ( ) const [inline]

Definition at line 139 of file input_data_processing.h.

float pcl::ihs::InputDataProcessing::getHMin ( ) const [inline]

Definition at line 138 of file input_data_processing.h.

unsigned int pcl::ihs::InputDataProcessing::getHSVDilateSize ( ) const [inline]

Definition at line 167 of file input_data_processing.h.

float pcl::ihs::InputDataProcessing::getSMax ( ) const [inline]

Definition at line 141 of file input_data_processing.h.

float pcl::ihs::InputDataProcessing::getSMin ( ) const [inline]

Definition at line 140 of file input_data_processing.h.

float pcl::ihs::InputDataProcessing::getVMax ( ) const [inline]

Definition at line 143 of file input_data_processing.h.

float pcl::ihs::InputDataProcessing::getVMin ( ) const [inline]

Definition at line 142 of file input_data_processing.h.

float pcl::ihs::InputDataProcessing::getXMax ( ) const [inline]

Definition at line 120 of file input_data_processing.h.

float pcl::ihs::InputDataProcessing::getXMin ( ) const [inline]

Definition at line 119 of file input_data_processing.h.

unsigned int pcl::ihs::InputDataProcessing::getXYZErodeSize ( ) const [inline]

Definition at line 161 of file input_data_processing.h.

float pcl::ihs::InputDataProcessing::getYMax ( ) const [inline]

Definition at line 122 of file input_data_processing.h.

float pcl::ihs::InputDataProcessing::getYMin ( ) const [inline]

Definition at line 121 of file input_data_processing.h.

float pcl::ihs::InputDataProcessing::getZMax ( ) const [inline]

Definition at line 124 of file input_data_processing.h.

float pcl::ihs::InputDataProcessing::getZMin ( ) const [inline]

Definition at line 123 of file input_data_processing.h.

pcl::ihs::InputDataProcessing::MatrixXi pcl::ihs::InputDataProcessing::manhattan ( const MatrixXb mat,
const bool  comp 
) const [private]

Calculates the manhattan distance map for the input matrix.

Parameters:
[in]matInput matrix.
[in]compCompared value. mat==comp will have zero distance.
Returns:
Matrix containing the distances to mat==comp
See also:
http://ostermiller.org/dilate_and_erode.html

Definition at line 285 of file input_data_processing.cpp.

void pcl::ihs::InputDataProcessing::RGBToHSV ( const unsigned char  r,
const unsigned char  g,
const unsigned char  b,
float &  h,
float &  s,
float &  v 
) const [private]

Conversion from the RGB to HSV color space.

Definition at line 324 of file input_data_processing.cpp.

bool pcl::ihs::InputDataProcessing::segment ( const CloudXYZRGBAConstPtr cloud_in,
CloudXYZRGBNormalPtr cloud_out,
CloudXYZRGBNormalPtr cloud_discarded 
) const

Apply the segmentation on the input cloud (XYZ and HSV).

Parameters:
[in]cloud_inThe input cloud.
[out]cloud_outThe segmented cloud.
[out]cloud_discardedCloud containing all points that were removed during the HSV segmentation. The points in the XYZ segmentation are NOT used!
Returns:
true if success.
Note:
Converts from m to cm.

Definition at line 81 of file input_data_processing.cpp.

void pcl::ihs::InputDataProcessing::setColorSegmentationEnabled ( const bool  hsv_enabled) [inline]

Enable / disable the color segmentation.

Definition at line 154 of file input_data_processing.h.

void pcl::ihs::InputDataProcessing::setColorSegmentationInverted ( const bool  hsv_inverted) [inline]

If true the color values inside of H - S - V min / max are accepted instead of discarded.

Definition at line 148 of file input_data_processing.h.

void pcl::ihs::InputDataProcessing::setHMax ( const float  h_max) [inline]

Definition at line 132 of file input_data_processing.h.

void pcl::ihs::InputDataProcessing::setHMin ( const float  h_min) [inline]

Simple color segmentation in the HSV color space. Points inside of H - S - V min / max are discarded. H must be in the range 0 and 360, S and V in the range 0 and 1.

Note:
If you set values outside of the allowed range the member variables are clamped to the next best value. E.g. H is set to 0 if you pass -1.

Definition at line 131 of file input_data_processing.h.

void pcl::ihs::InputDataProcessing::setHSVDilateSize ( const unsigned int  size) [inline]

The HSV mask is dilated with a kernel of this size.

Definition at line 166 of file input_data_processing.h.

void pcl::ihs::InputDataProcessing::setSMax ( const float  s_max) [inline]

Definition at line 134 of file input_data_processing.h.

void pcl::ihs::InputDataProcessing::setSMin ( const float  s_min) [inline]

Definition at line 133 of file input_data_processing.h.

void pcl::ihs::InputDataProcessing::setVMax ( const float  v_max) [inline]

Definition at line 136 of file input_data_processing.h.

void pcl::ihs::InputDataProcessing::setVMin ( const float  v_min) [inline]

Definition at line 135 of file input_data_processing.h.

void pcl::ihs::InputDataProcessing::setXMax ( const float  x_max) [inline]

Definition at line 113 of file input_data_processing.h.

void pcl::ihs::InputDataProcessing::setXMin ( const float  x_min) [inline]

Points outside of X - Y - Z - min / max are discarded. The unit is cm. The min values must be smaller than the max values.

Definition at line 112 of file input_data_processing.h.

void pcl::ihs::InputDataProcessing::setXYZErodeSize ( const unsigned int  size) [inline]

The XYZ mask is eroded with a kernel of this size.

Definition at line 160 of file input_data_processing.h.

void pcl::ihs::InputDataProcessing::setYMax ( const float  y_max) [inline]

Definition at line 115 of file input_data_processing.h.

void pcl::ihs::InputDataProcessing::setYMin ( const float  y_min) [inline]

Definition at line 114 of file input_data_processing.h.

void pcl::ihs::InputDataProcessing::setZMax ( const float  z_max) [inline]

Definition at line 117 of file input_data_processing.h.

void pcl::ihs::InputDataProcessing::setZMin ( const float  z_min) [inline]

Definition at line 116 of file input_data_processing.h.


Member Data Documentation

Definition at line 228 of file input_data_processing.h.

Definition at line 227 of file input_data_processing.h.

Definition at line 235 of file input_data_processing.h.

Definition at line 234 of file input_data_processing.h.

Definition at line 218 of file input_data_processing.h.

Definition at line 230 of file input_data_processing.h.

Definition at line 229 of file input_data_processing.h.

Definition at line 237 of file input_data_processing.h.

Definition at line 238 of file input_data_processing.h.

Definition at line 232 of file input_data_processing.h.

Definition at line 231 of file input_data_processing.h.

Definition at line 221 of file input_data_processing.h.

Definition at line 220 of file input_data_processing.h.

Definition at line 223 of file input_data_processing.h.

Definition at line 222 of file input_data_processing.h.

Definition at line 225 of file input_data_processing.h.

Definition at line 224 of file input_data_processing.h.


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


pcl
Author(s): Open Perception
autogenerated on Wed Aug 26 2015 15:43:57