Public Types | Public Member Functions | Protected Member Functions | Protected Attributes
pcl::SACSegmentation< PointT > Class Template Reference

SACSegmentation represents the Nodelet segmentation class for Sample Consensus methods and models, in the sense that it just creates a Nodelet wrapper for generic-purpose SAC-based segmentation. More...

#include <sac_segmentation.h>

Inheritance diagram for pcl::SACSegmentation< PointT >:
Inheritance graph
[legend]

List of all members.

Public Types

typedef pcl::PointCloud< PointTPointCloud
typedef PointCloud::ConstPtr PointCloudConstPtr
typedef PointCloud::Ptr PointCloudPtr
typedef SampleConsensusModel
< PointT >::Ptr 
SampleConsensusModelPtr
typedef SampleConsensus
< PointT >::Ptr 
SampleConsensusPtr
typedef pcl::search::Search
< PointT >::Ptr 
SearchPtr

Public Member Functions

Eigen::Vector3f getAxis () const
 Get the axis along which we need to search for a model perpendicular to.
double getDistanceThreshold () const
 Get the distance to the model threshold.
double getEpsAngle () const
 Get the epsilon (delta) model angle threshold in radians.
int getMaxIterations () const
 Get maximum number of iterations before giving up.
SampleConsensusPtr getMethod () const
 Get a pointer to the SAC method used.
int getMethodType () const
 Get the type of sample consensus method used.
SampleConsensusModelPtr getModel () const
 Get a pointer to the SAC model used.
int getModelType () const
 Get the type of SAC model used.
bool getOptimizeCoefficients () const
 Get the coefficient refinement internal flag.
double getProbability () const
 Get the probability of choosing at least one sample free from outliers.
void getRadiusLimits (double &min_radius, double &max_radius)
 Get the minimum and maximum allowable radius limits for the model as set by the user.
void getSamplesMaxDist (double &radius)
 Get maximum distance allowed when drawing random samples.
 SACSegmentation ()
 Empty constructor.
virtual void segment (PointIndices &inliers, ModelCoefficients &model_coefficients)
 Base method for segmentation of a model in a PointCloud given by <setInputCloud (), setIndices ()>
void setAxis (const Eigen::Vector3f &ax)
 Set the axis along which we need to search for a model perpendicular to.
void setDistanceThreshold (double threshold)
 Distance to the model threshold (user given parameter).
void setEpsAngle (double ea)
 Set the angle epsilon (delta) threshold.
void setMaxIterations (int max_iterations)
 Set the maximum number of iterations before giving up.
void setMethodType (int method)
 The type of sample consensus method to use (user given parameter).
void setModelType (int model)
 The type of model to use (user given parameter).
void setOptimizeCoefficients (bool optimize)
 Set to true if a coefficient refinement is required.
void setProbability (double probability)
 Set the probability of choosing at least one sample free from outliers.
void setRadiusLimits (const double &min_radius, const double &max_radius)
 Set the minimum and maximum allowable radius limits for the model (applicable to models that estimate a radius)
void setSamplesMaxDist (const double &radius, SearchPtr search)
 Set the maximum distance allowed when drawing random samples.
virtual ~SACSegmentation ()
 Empty destructor.

Protected Member Functions

virtual std::string getClassName () const
 Class get name method.
virtual void initSAC (const int method_type)
 Initialize the Sample Consensus method and set its parameters.
virtual bool initSACModel (const int model_type)
 Initialize the Sample Consensus model and set its parameters.

Protected Attributes

Eigen::Vector3f axis_
 The axis along which we need to search for a model perpendicular to.
double eps_angle_
 The maximum allowed difference between the model normal and the given axis.
int max_iterations_
 Maximum number of iterations before giving up (user given parameter).
int method_type_
 The type of sample consensus method to use (user given parameter).
SampleConsensusModelPtr model_
 The model that needs to be segmented.
int model_type_
 The type of model to use (user given parameter).
bool optimize_coefficients_
 Set to true if a coefficient refinement is required.
double probability_
 Desired probability of choosing at least one sample free from outliers (user given parameter).
double radius_max_
double radius_min_
 The minimum and maximum radius limits for the model. Applicable to all models that estimate a radius.
SampleConsensusPtr sac_
 The sample consensus segmentation method.
double samples_radius_
 The maximum distance of subsequent samples from the first (radius search)
SearchPtr samples_radius_search_
 The search object for picking subsequent samples using radius search.
double threshold_
 Distance to the model threshold (user given parameter).

Detailed Description

template<typename PointT>
class pcl::SACSegmentation< PointT >

SACSegmentation represents the Nodelet segmentation class for Sample Consensus methods and models, in the sense that it just creates a Nodelet wrapper for generic-purpose SAC-based segmentation.

Author:
Radu Bogdan Rusu

Definition at line 65 of file sac_segmentation.h.


Member Typedef Documentation

template<typename PointT>
typedef pcl::PointCloud<PointT> pcl::SACSegmentation< PointT >::PointCloud
template<typename PointT>
typedef PointCloud::ConstPtr pcl::SACSegmentation< PointT >::PointCloudConstPtr
template<typename PointT>
typedef PointCloud::Ptr pcl::SACSegmentation< PointT >::PointCloudPtr
template<typename PointT>
typedef SampleConsensusModel<PointT>::Ptr pcl::SACSegmentation< PointT >::SampleConsensusModelPtr
template<typename PointT>
typedef SampleConsensus<PointT>::Ptr pcl::SACSegmentation< PointT >::SampleConsensusPtr
template<typename PointT>
typedef pcl::search::Search<PointT>::Ptr pcl::SACSegmentation< PointT >::SearchPtr

Definition at line 77 of file sac_segmentation.h.


Constructor & Destructor Documentation

template<typename PointT>
pcl::SACSegmentation< PointT >::SACSegmentation ( ) [inline]

Empty constructor.

Definition at line 83 of file sac_segmentation.h.

template<typename PointT>
virtual pcl::SACSegmentation< PointT >::~SACSegmentation ( ) [inline, virtual]

Empty destructor.

Definition at line 92 of file sac_segmentation.h.


Member Function Documentation

template<typename PointT>
Eigen::Vector3f pcl::SACSegmentation< PointT >::getAxis ( ) const [inline]

Get the axis along which we need to search for a model perpendicular to.

Definition at line 213 of file sac_segmentation.h.

template<typename PointT>
virtual std::string pcl::SACSegmentation< PointT >::getClassName ( ) const [inline, protected, virtual]
template<typename PointT>
double pcl::SACSegmentation< PointT >::getDistanceThreshold ( ) const [inline]

Get the distance to the model threshold.

Definition at line 130 of file sac_segmentation.h.

template<typename PointT>
double pcl::SACSegmentation< PointT >::getEpsAngle ( ) const [inline]

Get the epsilon (delta) model angle threshold in radians.

Definition at line 223 of file sac_segmentation.h.

template<typename PointT>
int pcl::SACSegmentation< PointT >::getMaxIterations ( ) const [inline]

Get maximum number of iterations before giving up.

Definition at line 140 of file sac_segmentation.h.

template<typename PointT>
SampleConsensusPtr pcl::SACSegmentation< PointT >::getMethod ( ) const [inline]

Get a pointer to the SAC method used.

Definition at line 106 of file sac_segmentation.h.

template<typename PointT>
int pcl::SACSegmentation< PointT >::getMethodType ( ) const [inline]

Get the type of sample consensus method used.

Definition at line 120 of file sac_segmentation.h.

template<typename PointT>
SampleConsensusModelPtr pcl::SACSegmentation< PointT >::getModel ( ) const [inline]

Get a pointer to the SAC model used.

Definition at line 110 of file sac_segmentation.h.

template<typename PointT>
int pcl::SACSegmentation< PointT >::getModelType ( ) const [inline]

Get the type of SAC model used.

Definition at line 102 of file sac_segmentation.h.

template<typename PointT>
bool pcl::SACSegmentation< PointT >::getOptimizeCoefficients ( ) const [inline]

Get the coefficient refinement internal flag.

Definition at line 160 of file sac_segmentation.h.

template<typename PointT>
double pcl::SACSegmentation< PointT >::getProbability ( ) const [inline]

Get the probability of choosing at least one sample free from outliers.

Definition at line 150 of file sac_segmentation.h.

template<typename PointT>
void pcl::SACSegmentation< PointT >::getRadiusLimits ( double &  min_radius,
double &  max_radius 
) [inline]

Get the minimum and maximum allowable radius limits for the model as set by the user.

Parameters:
[out]min_radiusthe resultant minimum radius model
[out]max_radiusthe resultant maximum radius model

Definition at line 179 of file sac_segmentation.h.

template<typename PointT>
void pcl::SACSegmentation< PointT >::getSamplesMaxDist ( double &  radius) [inline]

Get maximum distance allowed when drawing random samples.

Parameters:
[out]radiusthe maximum distance (L2 norm)

Definition at line 200 of file sac_segmentation.h.

template<typename PointT >
void pcl::SACSegmentation< PointT >::initSAC ( const int  method_type) [protected, virtual]

Initialize the Sample Consensus method and set its parameters.

Parameters:
[in]method_typethe type of SAC method to be used

Definition at line 260 of file sac_segmentation.hpp.

template<typename PointT >
bool pcl::SACSegmentation< PointT >::initSACModel ( const int  model_type) [protected, virtual]

Initialize the Sample Consensus model and set its parameters.

Parameters:
[in]model_typethe type of SAC model that is to be used

Reimplemented in pcl::SACSegmentationFromNormals< PointT, PointNT >, and pcl::SACSegmentationFromNormals< PointType, pcl::Normal >.

Definition at line 129 of file sac_segmentation.hpp.

template<typename PointT >
void pcl::SACSegmentation< PointT >::segment ( PointIndices &  inliers,
ModelCoefficients &  model_coefficients 
) [virtual]

Base method for segmentation of a model in a PointCloud given by <setInputCloud (), setIndices ()>

Parameters:
[in]inliersthe resultant point indices that support the model found (inliers)
[out]model_coefficientsthe resultant model coefficients

Definition at line 71 of file sac_segmentation.hpp.

template<typename PointT>
void pcl::SACSegmentation< PointT >::setAxis ( const Eigen::Vector3f &  ax) [inline]

Set the axis along which we need to search for a model perpendicular to.

Parameters:
[in]axthe axis along which we need to search for a model perpendicular to

Definition at line 209 of file sac_segmentation.h.

template<typename PointT>
void pcl::SACSegmentation< PointT >::setDistanceThreshold ( double  threshold) [inline]

Distance to the model threshold (user given parameter).

Parameters:
[in]thresholdthe distance threshold to use

Definition at line 126 of file sac_segmentation.h.

template<typename PointT>
void pcl::SACSegmentation< PointT >::setEpsAngle ( double  ea) [inline]

Set the angle epsilon (delta) threshold.

Parameters:
[in]eathe maximum allowed difference between the model normal and the given axis in radians.

Definition at line 219 of file sac_segmentation.h.

template<typename PointT>
void pcl::SACSegmentation< PointT >::setMaxIterations ( int  max_iterations) [inline]

Set the maximum number of iterations before giving up.

Parameters:
[in]max_iterationsthe maximum number of iterations the sample consensus method will run

Definition at line 136 of file sac_segmentation.h.

template<typename PointT>
void pcl::SACSegmentation< PointT >::setMethodType ( int  method) [inline]

The type of sample consensus method to use (user given parameter).

Parameters:
[in]methodthe method type (check method_types.h)

Definition at line 116 of file sac_segmentation.h.

template<typename PointT>
void pcl::SACSegmentation< PointT >::setModelType ( int  model) [inline]

The type of model to use (user given parameter).

Parameters:
[in]modelthe model type (check model_types.h)

Definition at line 98 of file sac_segmentation.h.

template<typename PointT>
void pcl::SACSegmentation< PointT >::setOptimizeCoefficients ( bool  optimize) [inline]

Set to true if a coefficient refinement is required.

Parameters:
[in]optimizetrue for enabling model coefficient refinement, false otherwise

Definition at line 156 of file sac_segmentation.h.

template<typename PointT>
void pcl::SACSegmentation< PointT >::setProbability ( double  probability) [inline]

Set the probability of choosing at least one sample free from outliers.

Parameters:
[in]probabilitythe model fitting probability

Definition at line 146 of file sac_segmentation.h.

template<typename PointT>
void pcl::SACSegmentation< PointT >::setRadiusLimits ( const double &  min_radius,
const double &  max_radius 
) [inline]

Set the minimum and maximum allowable radius limits for the model (applicable to models that estimate a radius)

Parameters:
[in]min_radiusthe minimum radius model
[in]max_radiusthe maximum radius model

Definition at line 168 of file sac_segmentation.h.

template<typename PointT>
void pcl::SACSegmentation< PointT >::setSamplesMaxDist ( const double &  radius,
SearchPtr  search 
) [inline]

Set the maximum distance allowed when drawing random samples.

Parameters:
[in]radiusthe maximum distance (L2 norm)

Definition at line 189 of file sac_segmentation.h.


Member Data Documentation

template<typename PointT>
Eigen::Vector3f pcl::SACSegmentation< PointT >::axis_ [protected]

The axis along which we need to search for a model perpendicular to.

Definition at line 276 of file sac_segmentation.h.

template<typename PointT>
double pcl::SACSegmentation< PointT >::eps_angle_ [protected]

The maximum allowed difference between the model normal and the given axis.

Definition at line 273 of file sac_segmentation.h.

template<typename PointT>
int pcl::SACSegmentation< PointT >::max_iterations_ [protected]

Maximum number of iterations before giving up (user given parameter).

Definition at line 279 of file sac_segmentation.h.

template<typename PointT>
int pcl::SACSegmentation< PointT >::method_type_ [protected]

The type of sample consensus method to use (user given parameter).

Definition at line 255 of file sac_segmentation.h.

template<typename PointT>
SampleConsensusModelPtr pcl::SACSegmentation< PointT >::model_ [protected]

The model that needs to be segmented.

Definition at line 246 of file sac_segmentation.h.

template<typename PointT>
int pcl::SACSegmentation< PointT >::model_type_ [protected]

The type of model to use (user given parameter).

Definition at line 252 of file sac_segmentation.h.

template<typename PointT>
bool pcl::SACSegmentation< PointT >::optimize_coefficients_ [protected]

Set to true if a coefficient refinement is required.

Definition at line 261 of file sac_segmentation.h.

template<typename PointT>
double pcl::SACSegmentation< PointT >::probability_ [protected]

Desired probability of choosing at least one sample free from outliers (user given parameter).

Definition at line 282 of file sac_segmentation.h.

template<typename PointT>
double pcl::SACSegmentation< PointT >::radius_max_ [protected]

Definition at line 264 of file sac_segmentation.h.

template<typename PointT>
double pcl::SACSegmentation< PointT >::radius_min_ [protected]

The minimum and maximum radius limits for the model. Applicable to all models that estimate a radius.

Definition at line 264 of file sac_segmentation.h.

template<typename PointT>
SampleConsensusPtr pcl::SACSegmentation< PointT >::sac_ [protected]

The sample consensus segmentation method.

Definition at line 249 of file sac_segmentation.h.

template<typename PointT>
double pcl::SACSegmentation< PointT >::samples_radius_ [protected]

The maximum distance of subsequent samples from the first (radius search)

Definition at line 267 of file sac_segmentation.h.

template<typename PointT>
SearchPtr pcl::SACSegmentation< PointT >::samples_radius_search_ [protected]

The search object for picking subsequent samples using radius search.

Definition at line 270 of file sac_segmentation.h.

template<typename PointT>
double pcl::SACSegmentation< PointT >::threshold_ [protected]

Distance to the model threshold (user given parameter).

Definition at line 258 of file sac_segmentation.h.


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


pcl
Author(s): Open Perception
autogenerated on Mon Oct 6 2014 03:20:03