pcl::SampleConsensusModel< PointT > Class Template Reference

SampleConsensusModel represents the base model class. All sample consensus models must inherit from this class. More...

#include <sac_model.h>

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

List of all members.

Public Types

typedef boost::shared_ptr
< const SampleConsensusModel
ConstPtr
typedef pcl::PointCloud< PointT > PointCloud
typedef pcl::PointCloud
< PointT >::ConstPtr 
PointCloudConstPtr
typedef pcl::PointCloud
< PointT >::Ptr 
PointCloudPtr
typedef boost::shared_ptr
< SampleConsensusModel
Ptr

Public Member Functions

virtual bool computeModelCoefficients (const std::vector< int > &samples, Eigen::VectorXf &model_coefficients)=0
 Check whether the given index samples can form a valid model, compute the model coefficients from these samples and store them internally in model_coefficients_. Pure virtual.
virtual bool doSamplesVerifyModel (const std::set< int > &indices, const Eigen::VectorXf &model_coefficients, double threshold)=0
 Verify whether a subset of indices verifies a given set of model coefficients. Pure virtual.
virtual void getDistancesToModel (const Eigen::VectorXf &model_coefficients, std::vector< double > &distances)=0
 Compute all distances from the cloud data to a given model. Pure virtual.
IndicesPtr getIndices () const
 Get a pointer to the vector of indices used.
PointCloudConstPtr getInputCloud () const
 Get a pointer to the input point cloud dataset.
virtual SacModel getModelType () const =0
 Return an unique id for each type of model employed.
void getRadiusLimits (double &min_radius, double &max_radius)
 Get the minimum and maximum allowable radius limits for the model as set by the user.
virtual void getSamples (int &iterations, std::vector< int > &samples)=0
 Get a set of random data samples and return them as point indices. Pure virtual.
unsigned int getSampleSize () const
 Return the size of a sample from which a model is computed.
virtual void optimizeModelCoefficients (const std::vector< int > &inliers, const Eigen::VectorXf &model_coefficients, Eigen::VectorXf &optimized_coefficients)=0
 Recompute the model coefficients using the given inlier set and return them to the user. Pure virtual.
virtual void projectPoints (const std::vector< int > &inliers, const Eigen::VectorXf &model_coefficients, PointCloud &projected_points, bool copy_data_fields=true)=0
 Create a new point cloud with inliers projected onto the model. Pure virtual.
 SampleConsensusModel (const PointCloudConstPtr &cloud, const std::vector< int > &indices)
 Constructor for base SampleConsensusModel.
 SampleConsensusModel (const PointCloudConstPtr &cloud)
 Constructor for base SampleConsensusModel.
virtual void selectWithinDistance (const Eigen::VectorXf &model_coefficients, double threshold, std::vector< int > &inliers)=0
 Select all the points which respect the given model coefficients as inliers. Pure virtual.
void setIndices (std::vector< int > &indices)
 Provide the vector of indices that represents the input data.
void setIndices (const IndicesPtr &indices)
 Provide a pointer to the vector of indices that represents the input data.
virtual void setInputCloud (const PointCloudConstPtr &cloud)
 Provide a pointer to the input dataset.
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).
virtual ~SampleConsensusModel ()
 Destructor for base SampleConsensusModel.

Protected Member Functions

virtual bool isModelValid (const Eigen::VectorXf &model_coefficients)=0
 Check whether a model is valid given the user constraints.

Protected Attributes

IndicesPtr indices_
 A pointer to the vector of point indices to use.
PointCloudConstPtr input_
 A boost shared pointer to the point cloud data array.
double radius_max_
double radius_min_
 The minimum and maximum radius limits for the model. Applicable to all models that estimate a radius.

Private Member Functions

 SampleConsensusModel ()
 Empty constructor for base SampleConsensusModel.

Friends

class ProgressiveSampleConsensus< PointT >

Detailed Description

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

SampleConsensusModel represents the base model class. All sample consensus models must inherit from this class.

Author:
Radu Bogdan Rusu

Definition at line 61 of file sac_model.h.


Member Typedef Documentation

template<typename PointT>
typedef boost::shared_ptr<const SampleConsensusModel> pcl::SampleConsensusModel< PointT >::ConstPtr

Definition at line 69 of file sac_model.h.

template<typename PointT>
typedef pcl::PointCloud<PointT> pcl::SampleConsensusModel< PointT >::PointCloud
template<typename PointT>
typedef pcl::PointCloud<PointT>::ConstPtr pcl::SampleConsensusModel< PointT >::PointCloudConstPtr
template<typename PointT>
typedef pcl::PointCloud<PointT>::Ptr pcl::SampleConsensusModel< PointT >::PointCloudPtr
template<typename PointT>
typedef boost::shared_ptr<SampleConsensusModel> pcl::SampleConsensusModel< PointT >::Ptr

Constructor & Destructor Documentation

template<typename PointT>
pcl::SampleConsensusModel< PointT >::SampleConsensusModel (  )  [inline, private]

Empty constructor for base SampleConsensusModel.

Definition at line 73 of file sac_model.h.

template<typename PointT>
pcl::SampleConsensusModel< PointT >::SampleConsensusModel ( const PointCloudConstPtr cloud  )  [inline]

Constructor for base SampleConsensusModel.

Parameters:
cloud the input point cloud dataset

Definition at line 79 of file sac_model.h.

template<typename PointT>
pcl::SampleConsensusModel< PointT >::SampleConsensusModel ( const PointCloudConstPtr cloud,
const std::vector< int > &  indices 
) [inline]

Constructor for base SampleConsensusModel.

Parameters:
cloud the input point cloud dataset
indices a vector of point indices to be used from cloud

Definition at line 90 of file sac_model.h.

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

Destructor for base SampleConsensusModel.

Definition at line 104 of file sac_model.h.


Member Function Documentation

template<typename PointT>
virtual bool pcl::SampleConsensusModel< PointT >::computeModelCoefficients ( const std::vector< int > &  samples,
Eigen::VectorXf &  model_coefficients 
) [pure virtual]

Check whether the given index samples can form a valid model, compute the model coefficients from these samples and store them internally in model_coefficients_. Pure virtual.

Parameters:
samples the point indices found as possible good candidates for creating a valid model
model_coefficients the computed model coefficients

Implemented in pcl::SampleConsensusModelCircle2D< PointT >, pcl::SampleConsensusModelCylinder< PointT, PointNT >, pcl::SampleConsensusModelLine< PointT >, pcl::SampleConsensusModelPlane< PointT >, pcl::SampleConsensusModelRegistration< PointT >, and pcl::SampleConsensusModelSphere< PointT >.

template<typename PointT>
virtual bool pcl::SampleConsensusModel< PointT >::doSamplesVerifyModel ( const std::set< int > &  indices,
const Eigen::VectorXf &  model_coefficients,
double  threshold 
) [pure virtual]

Verify whether a subset of indices verifies a given set of model coefficients. Pure virtual.

Parameters:
indices the data indices that need to be tested against the model
model_coefficients the set of model coefficients
threshold a maximum admissible distance threshold for determining the inliers from the outliers

Implemented in pcl::SampleConsensusModelCircle2D< PointT >, pcl::SampleConsensusModelCylinder< PointT, PointNT >, pcl::SampleConsensusModelLine< PointT >, pcl::SampleConsensusModelPlane< PointT >, pcl::SampleConsensusModelRegistration< PointT >, and pcl::SampleConsensusModelSphere< PointT >.

template<typename PointT>
virtual void pcl::SampleConsensusModel< PointT >::getDistancesToModel ( const Eigen::VectorXf &  model_coefficients,
std::vector< double > &  distances 
) [pure virtual]
template<typename PointT>
IndicesPtr pcl::SampleConsensusModel< PointT >::getIndices (  )  const [inline]

Get a pointer to the vector of indices used.

Definition at line 231 of file sac_model.h.

template<typename PointT>
PointCloudConstPtr pcl::SampleConsensusModel< PointT >::getInputCloud (  )  const [inline]

Get a pointer to the input point cloud dataset.

Definition at line 212 of file sac_model.h.

template<typename PointT>
virtual SacModel pcl::SampleConsensusModel< PointT >::getModelType (  )  const [pure virtual]
template<typename PointT>
void pcl::SampleConsensusModel< 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:
min_radius the resultant minimum radius model
max_radius the resultant maximum radius model

Definition at line 261 of file sac_model.h.

template<typename PointT>
virtual void pcl::SampleConsensusModel< PointT >::getSamples ( int &  iterations,
std::vector< int > &  samples 
) [pure virtual]

Get a set of random data samples and return them as point indices. Pure virtual.

Parameters:
iterations the internal number of iterations used by SAC methods
samples the resultant model samples

Implemented in pcl::SampleConsensusModelCircle2D< PointT >, pcl::SampleConsensusModelCylinder< PointT, PointNT >, pcl::SampleConsensusModelLine< PointT >, pcl::SampleConsensusModelPlane< PointT >, pcl::SampleConsensusModelRegistration< PointT >, and pcl::SampleConsensusModelSphere< PointT >.

template<typename PointT>
unsigned int pcl::SampleConsensusModel< PointT >::getSampleSize (  )  const [inline]

Return the size of a sample from which a model is computed.

Definition at line 239 of file sac_model.h.

template<typename PointT>
virtual bool pcl::SampleConsensusModel< PointT >::isModelValid ( const Eigen::VectorXf &  model_coefficients  )  [inline, protected, pure virtual]
template<typename PointT>
virtual void pcl::SampleConsensusModel< PointT >::optimizeModelCoefficients ( const std::vector< int > &  inliers,
const Eigen::VectorXf &  model_coefficients,
Eigen::VectorXf &  optimized_coefficients 
) [pure virtual]

Recompute the model coefficients using the given inlier set and return them to the user. Pure virtual.

Note:
: these are the coefficients of the model after refinement (e.g., after a least-squares optimization)
Parameters:
inliers the data inliers supporting the model
model_coefficients the initial guess for the model coefficients
optimized_coefficients the resultant recomputed coefficients after non-linear optimization

Implemented in pcl::SampleConsensusModelCircle2D< PointT >, pcl::SampleConsensusModelCylinder< PointT, PointNT >, pcl::SampleConsensusModelLine< PointT >, pcl::SampleConsensusModelPlane< PointT >, pcl::SampleConsensusModelRegistration< PointT >, and pcl::SampleConsensusModelSphere< PointT >.

template<typename PointT>
virtual void pcl::SampleConsensusModel< PointT >::projectPoints ( const std::vector< int > &  inliers,
const Eigen::VectorXf &  model_coefficients,
PointCloud projected_points,
bool  copy_data_fields = true 
) [pure virtual]

Create a new point cloud with inliers projected onto the model. Pure virtual.

Parameters:
inliers the data inliers that we want to project on the model
model_coefficients the coefficients of a model
projected_points the resultant projected points
copy_data_fields set to true (default) if we want the projected_points cloud to be an exact copy of the input dataset minus the point projections on the plane model

Implemented in pcl::SampleConsensusModelCircle2D< PointT >, pcl::SampleConsensusModelCylinder< PointT, PointNT >, pcl::SampleConsensusModelLine< PointT >, pcl::SampleConsensusModelPlane< PointT >, pcl::SampleConsensusModelRegistration< PointT >, and pcl::SampleConsensusModelSphere< PointT >.

template<typename PointT>
virtual void pcl::SampleConsensusModel< PointT >::selectWithinDistance ( const Eigen::VectorXf &  model_coefficients,
double  threshold,
std::vector< int > &  inliers 
) [pure virtual]

Select all the points which respect the given model coefficients as inliers. Pure virtual.

Parameters:
model_coefficients the coefficients of a model that we need to compute distances to
threshold a maximum admissible distance threshold for determining the inliers from the outliers
inliers the resultant model inliers

Implemented in pcl::SampleConsensusModelCircle2D< PointT >, pcl::SampleConsensusModelCylinder< PointT, PointNT >, pcl::SampleConsensusModelLine< PointT >, pcl::SampleConsensusModelNormalParallelPlane< PointT, PointNT >, pcl::SampleConsensusModelNormalPlane< PointT, PointNT >, pcl::SampleConsensusModelParallelLine< PointT >, pcl::SampleConsensusModelParallelPlane< PointT >, pcl::SampleConsensusModelPerpendicularPlane< PointT >, pcl::SampleConsensusModelPlane< PointT >, pcl::SampleConsensusModelRegistration< PointT >, and pcl::SampleConsensusModelSphere< PointT >.

template<typename PointT>
void pcl::SampleConsensusModel< PointT >::setIndices ( std::vector< int > &  indices  )  [inline]

Provide the vector of indices that represents the input data.

Parameters:
indices the vector of indices that represents the input data.

Definition at line 224 of file sac_model.h.

template<typename PointT>
void pcl::SampleConsensusModel< PointT >::setIndices ( const IndicesPtr indices  )  [inline]

Provide a pointer to the vector of indices that represents the input data.

Parameters:
indices a pointer to the vector of indices that represents the input data.

Definition at line 218 of file sac_model.h.

template<typename PointT>
virtual void pcl::SampleConsensusModel< PointT >::setInputCloud ( const PointCloudConstPtr cloud  )  [inline, virtual]

Provide a pointer to the input dataset.

Parameters:
cloud the const boost shared pointer to a PointCloud message

Reimplemented in pcl::SampleConsensusModelRegistration< PointT >.

Definition at line 196 of file sac_model.h.

template<typename PointT>
void pcl::SampleConsensusModel< 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:
min_radius the minimum radius model
max_radius the maximum radius model
Todo:
change this to set limits on the entire model

Definition at line 248 of file sac_model.h.


Friends And Related Function Documentation

template<typename PointT>
friend class ProgressiveSampleConsensus< PointT > [friend]

Definition at line 267 of file sac_model.h.


Member Data Documentation

template<typename PointT>
IndicesPtr pcl::SampleConsensusModel< PointT >::indices_ [protected]

A pointer to the vector of point indices to use.

Definition at line 280 of file sac_model.h.

template<typename PointT>
PointCloudConstPtr pcl::SampleConsensusModel< PointT >::input_ [protected]

A boost shared pointer to the point cloud data array.

Definition at line 277 of file sac_model.h.

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

Definition at line 285 of file sac_model.h.

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

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

Definition at line 285 of file sac_model.h.


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


pcl
Author(s): See http://pcl.ros.org/authors for the complete list of authors.
autogenerated on Fri Jan 11 09:57:22 2013