Public Types | Public Member Functions | Protected Member Functions | Protected Attributes | Private Types | Private Member Functions
pcl::SampleConsensus< T > Class Template Reference

SampleConsensus represents the base class. All sample consensus methods must inherit from this class. More...

#include <sac.h>

List of all members.

Public Types

typedef boost::shared_ptr
< const SampleConsensus
ConstPtr
typedef boost::shared_ptr
< SampleConsensus
Ptr

Public Member Functions

virtual bool computeModel (int debug_verbosity_level=0)=0
 Compute the actual model. Pure virtual.
double getDistanceThreshold ()
 Get the distance to model threshold, as set by the user.
void getInliers (std::vector< int > &inliers)
 Return the best set of inliers found so far for this model.
int getMaxIterations ()
 Get the maximum number of iterations, as set by the user.
void getModel (std::vector< int > &model)
 Return the best model found so far.
void getModelCoefficients (Eigen::VectorXf &model_coefficients)
 Return the model coefficients of the best model found so far.
double getProbability ()
 Obtain the probability of choosing at least one sample free from outliers, as set by the user.
void getRandomSamples (const boost::shared_ptr< std::vector< int > > &indices, size_t nr_samples, std::set< int > &indices_subset)
 Get a set of randomly selected indices.
SampleConsensusModelPtr getSampleConsensusModel () const
 Get the Sample Consensus model used.
virtual bool refineModel (const double sigma=3.0, const unsigned int max_iterations=1000)
 Refine the model found. This loops over the model coefficients and optimizes them together with the set of inliers, until the change in the set of inliers is minimal.
 SampleConsensus (const SampleConsensusModelPtr &model, bool random=false)
 Constructor for base SAC.
 SampleConsensus (const SampleConsensusModelPtr &model, double threshold, bool random=false)
 Constructor for base SAC.
void setDistanceThreshold (double threshold)
 Set the distance to model threshold.
void setMaxIterations (int max_iterations)
 Set the maximum number of iterations.
void setProbability (double probability)
 Set the desired probability of choosing at least one sample free from outliers.
void setSampleConsensusModel (const SampleConsensusModelPtr &model)
 Set the Sample Consensus model to use.
virtual ~SampleConsensus ()
 Destructor for base SAC.

Protected Member Functions

double rnd ()
 Boost-based random number generator.

Protected Attributes

std::vector< int > inliers_
 The indices of the points that were chosen as inliers after the last computeModel () call.
int iterations_
 Total number of internal loop iterations that we've done so far.
int max_iterations_
 Maximum number of iterations before giving up.
std::vector< int > model_
 The model found after the last computeModel () as point cloud indices.
Eigen::VectorXf model_coefficients_
 The coefficients of our model computed directly from the model found.
double probability_
 Desired probability of choosing at least one sample free from outliers.
boost::shared_ptr
< boost::uniform_01
< boost::mt19937 > > 
rng_
 Boost-based random number generator distribution.
boost::mt19937 rng_alg_
 Boost-based random number generator algorithm.
SampleConsensusModelPtr sac_model_
 The underlying data model used (i.e. what is it that we attempt to search for).
double threshold_
 Distance to model threshold.

Private Types

typedef SampleConsensusModel
< T >::Ptr 
SampleConsensusModelPtr

Private Member Functions

 SampleConsensus ()
 Constructor for base SAC.

Detailed Description

template<typename T>
class pcl::SampleConsensus< T >

SampleConsensus represents the base class. All sample consensus methods must inherit from this class.

Author:
Radu Bogdan Rusu

Definition at line 56 of file sac.h.


Member Typedef Documentation

template<typename T>
typedef boost::shared_ptr<const SampleConsensus> pcl::SampleConsensus< T >::ConstPtr
template<typename T>
typedef boost::shared_ptr<SampleConsensus> pcl::SampleConsensus< T >::Ptr
template<typename T>
typedef SampleConsensusModel<T>::Ptr pcl::SampleConsensus< T >::SampleConsensusModelPtr [private]

Constructor & Destructor Documentation

template<typename T>
pcl::SampleConsensus< T >::SampleConsensus ( ) [inline, private]

Constructor for base SAC.

Definition at line 62 of file sac.h.

template<typename T>
pcl::SampleConsensus< T >::SampleConsensus ( const SampleConsensusModelPtr model,
bool  random = false 
) [inline]

Constructor for base SAC.

Parameters:
[in]modela Sample Consensus model
[in]randomif true set the random seed to the current time, else set to 12345 (default: false)

Definition at line 72 of file sac.h.

template<typename T>
pcl::SampleConsensus< T >::SampleConsensus ( const SampleConsensusModelPtr model,
double  threshold,
bool  random = false 
) [inline]

Constructor for base SAC.

Parameters:
[in]modela Sample Consensus model
[in]thresholddistance to model threshol
[in]randomif true set the random seed to the current time, else set to 12345 (default: false)

Definition at line 96 of file sac.h.

template<typename T>
virtual pcl::SampleConsensus< T >::~SampleConsensus ( ) [inline, virtual]

Destructor for base SAC.

Definition at line 134 of file sac.h.


Member Function Documentation

template<typename T>
virtual bool pcl::SampleConsensus< T >::computeModel ( int  debug_verbosity_level = 0) [pure virtual]
template<typename T>
double pcl::SampleConsensus< T >::getDistanceThreshold ( ) [inline]

Get the distance to model threshold, as set by the user.

Definition at line 144 of file sac.h.

template<typename T>
void pcl::SampleConsensus< T >::getInliers ( std::vector< int > &  inliers) [inline]

Return the best set of inliers found so far for this model.

Parameters:
[out]inliersthe resultant set of inliers

Definition at line 300 of file sac.h.

template<typename T>
int pcl::SampleConsensus< T >::getMaxIterations ( ) [inline]

Get the maximum number of iterations, as set by the user.

Definition at line 154 of file sac.h.

template<typename T>
void pcl::SampleConsensus< T >::getModel ( std::vector< int > &  model) [inline]

Return the best model found so far.

Parameters:
[out]modelthe resultant model

Definition at line 294 of file sac.h.

template<typename T>
void pcl::SampleConsensus< T >::getModelCoefficients ( Eigen::VectorXf &  model_coefficients) [inline]

Return the model coefficients of the best model found so far.

Parameters:
[out]model_coefficientsthe resultant model coefficients

Definition at line 306 of file sac.h.

template<typename T>
double pcl::SampleConsensus< T >::getProbability ( ) [inline]

Obtain the probability of choosing at least one sample free from outliers, as set by the user.

Definition at line 165 of file sac.h.

template<typename T>
void pcl::SampleConsensus< T >::getRandomSamples ( const boost::shared_ptr< std::vector< int > > &  indices,
size_t  nr_samples,
std::set< int > &  indices_subset 
) [inline]

Get a set of randomly selected indices.

Parameters:
[in]indicesthe input indices vector
[in]nr_samplesthe desired number of point indices to randomly select
[out]indices_subsetthe resultant output set of randomly selected indices

Definition at line 280 of file sac.h.

template<typename T>
SampleConsensusModelPtr pcl::SampleConsensus< T >::getSampleConsensusModel ( ) const [inline]

Get the Sample Consensus model used.

Definition at line 128 of file sac.h.

template<typename T>
virtual bool pcl::SampleConsensus< T >::refineModel ( const double  sigma = 3.0,
const unsigned int  max_iterations = 1000 
) [inline, virtual]

Refine the model found. This loops over the model coefficients and optimizes them together with the set of inliers, until the change in the set of inliers is minimal.

Parameters:
[in]sigmastandard deviation multiplier for considering a sample as inlier (Mahalanobis distance)
[in]max_iterationsthe maxim number of iterations to try to refine in case the inliers keep on changing

Definition at line 179 of file sac.h.

template<typename T>
double pcl::SampleConsensus< T >::rnd ( ) [inline, protected]

Boost-based random number generator.

Definition at line 341 of file sac.h.

template<typename T>
void pcl::SampleConsensus< T >::setDistanceThreshold ( double  threshold) [inline]

Set the distance to model threshold.

Parameters:
[in]thresholddistance to model threshold

Definition at line 140 of file sac.h.

template<typename T>
void pcl::SampleConsensus< T >::setMaxIterations ( int  max_iterations) [inline]

Set the maximum number of iterations.

Parameters:
[in]max_iterationsmaximum number of iterations

Definition at line 150 of file sac.h.

template<typename T>
void pcl::SampleConsensus< T >::setProbability ( double  probability) [inline]

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

Parameters:
[in]probabilitythe desired probability of choosing at least one sample free from outliers
Note:
internally, the probability is set to 99% (0.99) by default.

Definition at line 161 of file sac.h.

template<typename T>
void pcl::SampleConsensus< T >::setSampleConsensusModel ( const SampleConsensusModelPtr model) [inline]

Set the Sample Consensus model to use.

Parameters:
[in]modela Sample Consensus model

Definition at line 121 of file sac.h.


Member Data Documentation

template<typename T>
std::vector<int> pcl::SampleConsensus< T >::inliers_ [protected]

The indices of the points that were chosen as inliers after the last computeModel () call.

Definition at line 316 of file sac.h.

template<typename T>
int pcl::SampleConsensus< T >::iterations_ [protected]

Total number of internal loop iterations that we've done so far.

Definition at line 325 of file sac.h.

template<typename T>
int pcl::SampleConsensus< T >::max_iterations_ [protected]

Maximum number of iterations before giving up.

Definition at line 331 of file sac.h.

template<typename T>
std::vector<int> pcl::SampleConsensus< T >::model_ [protected]

The model found after the last computeModel () as point cloud indices.

Definition at line 313 of file sac.h.

template<typename T>
Eigen::VectorXf pcl::SampleConsensus< T >::model_coefficients_ [protected]

The coefficients of our model computed directly from the model found.

Definition at line 319 of file sac.h.

template<typename T>
double pcl::SampleConsensus< T >::probability_ [protected]

Desired probability of choosing at least one sample free from outliers.

Definition at line 322 of file sac.h.

template<typename T>
boost::shared_ptr<boost::uniform_01<boost::mt19937> > pcl::SampleConsensus< T >::rng_ [protected]

Boost-based random number generator distribution.

Definition at line 337 of file sac.h.

template<typename T>
boost::mt19937 pcl::SampleConsensus< T >::rng_alg_ [protected]

Boost-based random number generator algorithm.

Definition at line 334 of file sac.h.

template<typename T>
SampleConsensusModelPtr pcl::SampleConsensus< T >::sac_model_ [protected]

The underlying data model used (i.e. what is it that we attempt to search for).

Definition at line 310 of file sac.h.

template<typename T>
double pcl::SampleConsensus< T >::threshold_ [protected]

Distance to model threshold.

Definition at line 328 of file sac.h.


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


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