SampleConsensus represents the base class. All sample consensus methods must inherit from this class. More...
#include <sac.h>
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. | |
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. | |
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. |
SampleConsensus represents the base class. All sample consensus methods must inherit from this class.
typedef boost::shared_ptr<const SampleConsensus> pcl::SampleConsensus< T >::ConstPtr |
typedef boost::shared_ptr<SampleConsensus> pcl::SampleConsensus< T >::Ptr |
typedef SampleConsensusModel<T>::Ptr pcl::SampleConsensus< T >::SampleConsensusModelPtr [private] |
Reimplemented in pcl::RandomizedMEstimatorSampleConsensus< PointT >, pcl::MaximumLikelihoodSampleConsensus< PointT >, pcl::MEstimatorSampleConsensus< PointT >, pcl::RandomizedRandomSampleConsensus< PointT >, pcl::LeastMedianSquares< PointT >, pcl::ProgressiveSampleConsensus< PointT >, and pcl::RandomSampleConsensus< PointT >.
pcl::SampleConsensus< T >::SampleConsensus | ( | ) | [inline, private] |
pcl::SampleConsensus< T >::SampleConsensus | ( | const SampleConsensusModelPtr & | model, |
bool | random = false |
||
) | [inline] |
pcl::SampleConsensus< T >::SampleConsensus | ( | const SampleConsensusModelPtr & | model, |
double | threshold, | ||
bool | random = false |
||
) | [inline] |
virtual pcl::SampleConsensus< T >::~SampleConsensus | ( | ) | [inline, virtual] |
virtual bool pcl::SampleConsensus< T >::computeModel | ( | int | debug_verbosity_level = 0 | ) | [pure virtual] |
Compute the actual model. Pure virtual.
Implemented in pcl::MaximumLikelihoodSampleConsensus< PointT >, pcl::RandomizedMEstimatorSampleConsensus< PointT >, pcl::ProgressiveSampleConsensus< PointT >, pcl::RandomizedRandomSampleConsensus< PointT >, pcl::MEstimatorSampleConsensus< PointT >, pcl::LeastMedianSquares< PointT >, and pcl::RandomSampleConsensus< PointT >.
double pcl::SampleConsensus< T >::getDistanceThreshold | ( | ) | [inline] |
void pcl::SampleConsensus< T >::getInliers | ( | std::vector< int > & | inliers | ) | [inline] |
int pcl::SampleConsensus< T >::getMaxIterations | ( | ) | [inline] |
void pcl::SampleConsensus< T >::getModel | ( | std::vector< int > & | model | ) | [inline] |
void pcl::SampleConsensus< T >::getModelCoefficients | ( | Eigen::VectorXf & | model_coefficients | ) | [inline] |
double pcl::SampleConsensus< T >::getProbability | ( | ) | [inline] |
void pcl::SampleConsensus< T >::getRandomSamples | ( | const boost::shared_ptr< std::vector< int > > & | indices, |
size_t | nr_samples, | ||
std::set< int > & | indices_subset | ||
) | [inline] |
double pcl::SampleConsensus< T >::rnd | ( | ) | [inline, protected] |
void pcl::SampleConsensus< T >::setDistanceThreshold | ( | double | threshold | ) | [inline] |
void pcl::SampleConsensus< T >::setMaxIterations | ( | int | max_iterations | ) | [inline] |
void pcl::SampleConsensus< T >::setProbability | ( | double | probability | ) | [inline] |
std::vector<int> pcl::SampleConsensus< T >::inliers_ [protected] |
int pcl::SampleConsensus< T >::iterations_ [protected] |
int pcl::SampleConsensus< T >::max_iterations_ [protected] |
std::vector<int> pcl::SampleConsensus< T >::model_ [protected] |
Eigen::VectorXf pcl::SampleConsensus< T >::model_coefficients_ [protected] |
double pcl::SampleConsensus< T >::probability_ [protected] |
boost::shared_ptr<boost::uniform_01<boost::mt19937> > pcl::SampleConsensus< T >::rng_ [protected] |
boost::mt19937 pcl::SampleConsensus< T >::rng_alg_ [protected] |
SampleConsensusModelPtr pcl::SampleConsensus< T >::sac_model_ [protected] |
double pcl::SampleConsensus< T >::threshold_ [protected] |