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>
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:
| |
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. |
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.
Definition at line 54 of file mlesac.h.
typedef SampleConsensusModel<PointT>::PointCloudConstPtr pcl::MaximumLikelihoodSampleConsensus< PointT >::PointCloudConstPtr [private] |
typedef SampleConsensusModel<PointT>::Ptr pcl::MaximumLikelihoodSampleConsensus< PointT >::SampleConsensusModelPtr [private] |
Reimplemented from pcl::SampleConsensus< PointT >.
pcl::MaximumLikelihoodSampleConsensus< PointT >::MaximumLikelihoodSampleConsensus | ( | const SampleConsensusModelPtr & | model | ) | [inline] |
pcl::MaximumLikelihoodSampleConsensus< PointT >::MaximumLikelihoodSampleConsensus | ( | const SampleConsensusModelPtr & | model, | |
double | threshold | |||
) | [inline] |
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.
cloud | the point cloud data message | |
indices | the point indices | |
median | the resultant median value |
Definition at line 243 of file mlesac.hpp.
double pcl::MaximumLikelihoodSampleConsensus< PointT >::computeMedianAbsoluteDeviation | ( | const PointCloudConstPtr & | cloud, | |
const IndicesPtr & | indices, | |||
double | sigma | |||
) | [inline, protected] |
Compute the median absolute deviation:
.
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.
bool pcl::MaximumLikelihoodSampleConsensus< PointT >::computeModel | ( | int | debug_verbosity_level = 0 |
) | [inline, virtual] |
Compute the actual model and find the inliers.
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.
int pcl::MaximumLikelihoodSampleConsensus< PointT >::getEMIterations | ( | ) | [inline] |
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.
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.
void pcl::MaximumLikelihoodSampleConsensus< PointT >::setEMIterations | ( | int | iterations | ) | [inline] |
int pcl::MaximumLikelihoodSampleConsensus< PointT >::iterations_EM_ [private] |
double pcl::MaximumLikelihoodSampleConsensus< PointT >::sigma_ [private] |