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

MaximumLikelihoodSampleConsensus represents an implementation of the MLESAC (Maximum Likelihood Estimator SAmple Consensus) algorithm, as described in: "MLESAC: A new robust estimator with application to estimating image geometry", P.H.S. Torr and A. Zisserman, Computer Vision and Image Understanding, vol 78, 2000. More...

#include <mlesac.h>

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

List of all members.

Public Types

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

Public Member Functions

bool computeModel (int debug_verbosity_level=0)
 Compute the actual model and find the inliers.
int getEMIterations () const
 Get the number of EM iterations.
 MaximumLikelihoodSampleConsensus (const SampleConsensusModelPtr &model)
 MLESAC (Maximum Likelihood Estimator SAmple Consensus) main constructor.
 MaximumLikelihoodSampleConsensus (const SampleConsensusModelPtr &model, double threshold)
 MLESAC (Maximum Likelihood Estimator SAmple Consensus) main constructor.
void setEMIterations (int iterations)
 Set the number of EM iterations.

Protected Member Functions

void computeMedian (const PointCloudConstPtr &cloud, const boost::shared_ptr< std::vector< int > > &indices, Eigen::Vector4f &median)
 Compute the median value of a 3D point cloud using a given set point indices and return it as a Point32.
double computeMedianAbsoluteDeviation (const PointCloudConstPtr &cloud, const boost::shared_ptr< std::vector< int > > &indices, double sigma)
 Compute the median absolute deviation:

\[ MAD = \sigma * median_i (| Xi - median_j(Xj) |) \]

.

void getMinMax (const PointCloudConstPtr &cloud, const boost::shared_ptr< std::vector< int > > &indices, Eigen::Vector4f &min_p, Eigen::Vector4f &max_p)
 Determine the minimum and maximum 3D bounding box coordinates for a given set of points.

Private Types

typedef SampleConsensusModel
< PointT >::PointCloudConstPtr 
PointCloudConstPtr
typedef SampleConsensusModel
< PointT >::Ptr 
SampleConsensusModelPtr

Private Attributes

int iterations_EM_
 Maximum number of EM (Expectation Maximization) iterations.
double sigma_
 The MLESAC sigma parameter.

Detailed Description

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

MaximumLikelihoodSampleConsensus represents an implementation of the MLESAC (Maximum Likelihood Estimator SAmple Consensus) algorithm, as described in: "MLESAC: A new robust estimator with application to estimating image geometry", P.H.S. Torr and A. Zisserman, Computer Vision and Image Understanding, vol 78, 2000.

Note:
MLESAC is useful in situations where most of the data samples belong to the model, and a fast outlier rejection algorithm is needed.
Author:
Radu B. Rusu

Definition at line 57 of file mlesac.h.


Member Typedef Documentation

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

Reimplemented from pcl::SampleConsensus< PointT >.

Definition at line 64 of file mlesac.h.

Definition at line 60 of file mlesac.h.

template<typename PointT>
typedef boost::shared_ptr<MaximumLikelihoodSampleConsensus> pcl::MaximumLikelihoodSampleConsensus< PointT >::Ptr

Reimplemented from pcl::SampleConsensus< PointT >.

Definition at line 63 of file mlesac.h.

Reimplemented from pcl::SampleConsensus< PointT >.

Definition at line 59 of file mlesac.h.


Constructor & Destructor Documentation

MLESAC (Maximum Likelihood Estimator SAmple Consensus) main constructor.

Parameters:
[in]modela Sample Consensus model

Definition at line 78 of file mlesac.h.

template<typename PointT>
pcl::MaximumLikelihoodSampleConsensus< PointT >::MaximumLikelihoodSampleConsensus ( const SampleConsensusModelPtr model,
double  threshold 
) [inline]

MLESAC (Maximum Likelihood Estimator SAmple Consensus) main constructor.

Parameters:
[in]modela Sample Consensus model
[in]thresholddistance to model threshold

Definition at line 90 of file mlesac.h.


Member Function Documentation

template<typename PointT >
void pcl::MaximumLikelihoodSampleConsensus< PointT >::computeMedian ( const PointCloudConstPtr cloud,
const boost::shared_ptr< std::vector< int > > &  indices,
Eigen::Vector4f &  median 
) [protected]

Compute the median value of a 3D point cloud using a given set point indices and return it as a Point32.

Parameters:
[in]cloudthe point cloud data message
[in]indicesthe point indices
[out]medianthe resultant median value

Definition at line 264 of file mlesac.hpp.

template<typename PointT >
double pcl::MaximumLikelihoodSampleConsensus< PointT >::computeMedianAbsoluteDeviation ( const PointCloudConstPtr cloud,
const boost::shared_ptr< std::vector< int > > &  indices,
double  sigma 
) [protected]

Compute the median absolute deviation:

\[ MAD = \sigma * median_i (| Xi - median_j(Xj) |) \]

.

Note:
Sigma needs to be chosen carefully (a good starting sigma value is 1.4826)
Parameters:
[in]cloudthe point cloud data message
[in]indicesthe set of point indices to use
[in]sigmathe sigma value

Definition at line 207 of file mlesac.hpp.

template<typename PointT >
bool pcl::MaximumLikelihoodSampleConsensus< PointT >::computeModel ( int  debug_verbosity_level = 0) [virtual]

Compute the actual model and find the inliers.

Parameters:
[in]debug_verbosity_levelenable/disable on-screen debug information and set the verbosity level

Implements pcl::SampleConsensus< PointT >.

Definition at line 49 of file mlesac.hpp.

template<typename PointT>
int pcl::MaximumLikelihoodSampleConsensus< PointT >::getEMIterations ( ) const [inline]

Get the number of EM iterations.

Definition at line 112 of file mlesac.h.

template<typename PointT >
void pcl::MaximumLikelihoodSampleConsensus< PointT >::getMinMax ( const PointCloudConstPtr cloud,
const boost::shared_ptr< std::vector< int > > &  indices,
Eigen::Vector4f &  min_p,
Eigen::Vector4f &  max_p 
) [protected]

Determine the minimum and maximum 3D bounding box coordinates for a given set of points.

Parameters:
[in]cloudthe point cloud message
[in]indicesthe set of point indices to use
[out]min_pthe resultant minimum bounding box coordinates
[out]max_pthe resultant maximum bounding box coordinates

Definition at line 240 of file mlesac.hpp.

template<typename PointT>
void pcl::MaximumLikelihoodSampleConsensus< PointT >::setEMIterations ( int  iterations) [inline]

Set the number of EM iterations.

Parameters:
[in]iterationsthe number of EM iterations

Definition at line 108 of file mlesac.h.


Member Data Documentation

template<typename PointT>
int pcl::MaximumLikelihoodSampleConsensus< PointT >::iterations_EM_ [private]

Maximum number of EM (Expectation Maximization) iterations.

Definition at line 154 of file mlesac.h.

template<typename PointT>
double pcl::MaximumLikelihoodSampleConsensus< PointT >::sigma_ [private]

The MLESAC sigma parameter.

Definition at line 156 of file mlesac.h.


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


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