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 Member Functions

bool computeModel (int debug_verbosity_level=0)
 Compute the actual model and find the inliers.
int getEMIterations ()
 Get the number of EM iterations.
 MaximumLikelihoodSampleConsensus (const SampleConsensusModelPtr &model, double threshold)
 MLESAC (Maximum Likelihood Estimator SAmple Consensus) main constructor.
 MaximumLikelihoodSampleConsensus (const SampleConsensusModelPtr &model)
 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 IndicesPtr &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 IndicesPtr &indices, double sigma)
 Compute the median absolute deviation:

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

.

void getMinMax (const PointCloudConstPtr &cloud, const IndicesPtr &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 Bogdan Rusu

Definition at line 54 of file mlesac.h.


Member Typedef Documentation

template<typename PointT>
typedef SampleConsensusModel<PointT>::PointCloudConstPtr pcl::MaximumLikelihoodSampleConsensus< PointT >::PointCloudConstPtr [private]

Definition at line 66 of file mlesac.h.

template<typename PointT>
typedef SampleConsensusModel<PointT>::Ptr pcl::MaximumLikelihoodSampleConsensus< PointT >::SampleConsensusModelPtr [private]

Reimplemented from pcl::SampleConsensus< PointT >.

Definition at line 65 of file mlesac.h.


Constructor & Destructor Documentation

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

MLESAC (Maximum Likelihood Estimator SAmple Consensus) main constructor.

Parameters:
model a Sample Consensus model

Definition at line 72 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:
model a Sample Consensus model
threshold distance to model threshold

Definition at line 83 of file mlesac.h.


Member Function Documentation

template<typename PointT >
void pcl::MaximumLikelihoodSampleConsensus< PointT >::computeMedian ( const PointCloudConstPtr cloud,
const IndicesPtr indices,
Eigen::Vector4f &  median 
) [inline, protected]

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

Parameters:
cloud the point cloud data message
indices the point indices
median the resultant median value

Definition at line 243 of file mlesac.hpp.

template<typename PointT >
double pcl::MaximumLikelihoodSampleConsensus< PointT >::computeMedianAbsoluteDeviation ( const PointCloudConstPtr cloud,
const IndicesPtr indices,
double  sigma 
) [inline, 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:
cloud the point cloud data message
indices the set of point indices to use
sigma the sigma value

Definition at line 191 of file mlesac.hpp.

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

Compute the actual model and find the inliers.

Parameters:
debug_verbosity_level enable/disable on-screen debug information and set the verbosity level

Implements pcl::SampleConsensus< PointT >.

Definition at line 45 of file mlesac.hpp.

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

Get the number of EM iterations.

Definition at line 101 of file mlesac.h.

template<typename PointT >
void pcl::MaximumLikelihoodSampleConsensus< PointT >::getMinMax ( const PointCloudConstPtr cloud,
const IndicesPtr indices,
Eigen::Vector4f &  min_p,
Eigen::Vector4f &  max_p 
) [inline, protected]

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

Parameters:
cloud the point cloud message
indices the set of point indices to use
min_p the resultant minimum bounding box coordinates
max_p the resultant maximum bounding box coordinates

Definition at line 222 of file mlesac.hpp.

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

Set the number of EM iterations.

Parameters:
iterations the number of EM iterations

Definition at line 98 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 133 of file mlesac.h.

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

The MLESAC sigma parameter.

Definition at line 135 of file mlesac.h.


The documentation for this class was generated from the following files:
 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:19 2013