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

SampleConsensusModelRegistration defines a model for Point-To-Point registration outlier rejection. More...

#include <sac_model_registration.h>

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

List of all members.

Public Types

typedef SampleConsensusModel
< PointT >::PointCloud 
PointCloud
typedef SampleConsensusModel
< PointT >::PointCloudConstPtr 
PointCloudConstPtr
typedef SampleConsensusModel
< PointT >::PointCloudPtr 
PointCloudPtr
typedef boost::shared_ptr
< SampleConsensusModelRegistration
Ptr

Public Member Functions

bool computeModelCoefficients (const std::vector< int > &samples, Eigen::VectorXf &model_coefficients)
 Compute a 4x4 rigid transformation matrix from the samples given.
virtual int countWithinDistance (const Eigen::VectorXf &model_coefficients, const double threshold)
 Count all the points which respect the given model coefficients as inliers.
bool doSamplesVerifyModel (const std::set< int > &, const Eigen::VectorXf &, const double)
 Verify whether a subset of indices verifies a given set of model coefficients. Pure virtual.
void getDistancesToModel (const Eigen::VectorXf &model_coefficients, std::vector< double > &distances)
 Compute all distances from the transformed points to their correspondences.
pcl::SacModel getModelType () const
 Return an unique id for this model (SACMODEL_REGISTRATION).
void optimizeModelCoefficients (const std::vector< int > &inliers, const Eigen::VectorXf &model_coefficients, Eigen::VectorXf &optimized_coefficients)
 Recompute the 4x4 transformation using the given inlier set.
void projectPoints (const std::vector< int > &, const Eigen::VectorXf &, PointCloud &, bool=true)
 Create a new point cloud with inliers projected onto the model. Pure virtual.
 SampleConsensusModelRegistration (const PointCloudConstPtr &cloud, bool random=false)
 Constructor for base SampleConsensusModelRegistration.
 SampleConsensusModelRegistration (const PointCloudConstPtr &cloud, const std::vector< int > &indices, bool random=false)
 Constructor for base SampleConsensusModelRegistration.
void selectWithinDistance (const Eigen::VectorXf &model_coefficients, const double threshold, std::vector< int > &inliers)
 Select all the points which respect the given model coefficients as inliers.
virtual void setInputCloud (const PointCloudConstPtr &cloud)
 Provide a pointer to the input dataset.
void setInputTarget (const PointCloudConstPtr &target)
 Set the input point cloud target.
void setInputTarget (const PointCloudConstPtr &target, const std::vector< int > &indices_tgt)
 Set the input point cloud target.
virtual ~SampleConsensusModelRegistration ()
 Empty destructor.

Protected Member Functions

void computeOriginalIndexMapping ()
 Compute mappings between original indices of the input_/target_ clouds.
void computeSampleDistanceThreshold (const PointCloudConstPtr &cloud)
 Computes an "optimal" sample distance threshold based on the principal directions of the input cloud.
void computeSampleDistanceThreshold (const PointCloudConstPtr &cloud, const std::vector< int > &indices)
 Computes an "optimal" sample distance threshold based on the principal directions of the input cloud.
void estimateRigidTransformationSVD (const pcl::PointCloud< PointT > &cloud_src, const std::vector< int > &indices_src, const pcl::PointCloud< PointT > &cloud_tgt, const std::vector< int > &indices_tgt, Eigen::VectorXf &transform)
 Estimate a rigid transformation between a source and a target point cloud using an SVD closed-form solution of absolute orientation using unit quaternions.
bool isModelValid (const Eigen::VectorXf &model_coefficients)
 Check whether a model is valid given the user constraints.
virtual bool isSampleGood (const std::vector< int > &samples) const
 Check if a sample of indices results in a good sample of points indices.

Protected Attributes

std::map< int, int > correspondences_
 Given the index in the original point cloud, give the matching original index in the target cloud.
boost::shared_ptr< std::vector
< int > > 
indices_tgt_
 A pointer to the vector of target point indices to use.
double sample_dist_thresh_
 Internal distance threshold used for the sample selection step.
PointCloudConstPtr target_
 A boost shared pointer to the target point cloud data array.

Detailed Description

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

SampleConsensusModelRegistration defines a model for Point-To-Point registration outlier rejection.

Author:
Radu Bogdan Rusu

Definition at line 58 of file sac_model_registration.h.


Member Typedef Documentation

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

Constructor & Destructor Documentation

template<typename PointT>
pcl::SampleConsensusModelRegistration< PointT >::SampleConsensusModelRegistration ( const PointCloudConstPtr cloud,
bool  random = false 
) [inline]

Constructor for base SampleConsensusModelRegistration.

Parameters:
[in]cloudthe input point cloud dataset
[in]randomif true set the random seed to the current time, else set to 12345 (default: false)

Definition at line 75 of file sac_model_registration.h.

template<typename PointT>
pcl::SampleConsensusModelRegistration< PointT >::SampleConsensusModelRegistration ( const PointCloudConstPtr cloud,
const std::vector< int > &  indices,
bool  random = false 
) [inline]

Constructor for base SampleConsensusModelRegistration.

Parameters:
[in]cloudthe input point cloud dataset
[in]indicesa vector of point indices to be used from cloud
[in]randomif true set the random seed to the current time, else set to 12345 (default: false)

Definition at line 92 of file sac_model_registration.h.

template<typename PointT>
virtual pcl::SampleConsensusModelRegistration< PointT >::~SampleConsensusModelRegistration ( ) [inline, virtual]

Empty destructor.

Definition at line 106 of file sac_model_registration.h.


Member Function Documentation

template<typename PointT >
bool pcl::SampleConsensusModelRegistration< PointT >::computeModelCoefficients ( const std::vector< int > &  samples,
Eigen::VectorXf &  model_coefficients 
) [virtual]

Compute a 4x4 rigid transformation matrix from the samples given.

Parameters:
[in]samplesthe indices found as good candidates for creating a valid model
[out]model_coefficientsthe resultant model coefficients

Implements pcl::SampleConsensusModel< PointT >.

Definition at line 67 of file sac_model_registration.hpp.

template<typename PointT>
void pcl::SampleConsensusModelRegistration< PointT >::computeOriginalIndexMapping ( ) [inline, protected]

Compute mappings between original indices of the input_/target_ clouds.

Definition at line 310 of file sac_model_registration.h.

template<typename PointT>
void pcl::SampleConsensusModelRegistration< PointT >::computeSampleDistanceThreshold ( const PointCloudConstPtr cloud) [inline, protected]

Computes an "optimal" sample distance threshold based on the principal directions of the input cloud.

Parameters:
[in]cloudthe const boost shared pointer to a PointCloud message

Reimplemented in pcl::SampleConsensusModelRegistration2D< PointT >.

Definition at line 239 of file sac_model_registration.h.

template<typename PointT>
void pcl::SampleConsensusModelRegistration< PointT >::computeSampleDistanceThreshold ( const PointCloudConstPtr cloud,
const std::vector< int > &  indices 
) [inline, protected]

Computes an "optimal" sample distance threshold based on the principal directions of the input cloud.

Parameters:
[in]cloudthe const boost shared pointer to a PointCloud message

Reimplemented in pcl::SampleConsensusModelRegistration2D< PointT >.

Definition at line 267 of file sac_model_registration.h.

template<typename PointT >
int pcl::SampleConsensusModelRegistration< PointT >::countWithinDistance ( const Eigen::VectorXf &  model_coefficients,
const double  threshold 
) [virtual]

Count all the points which respect the given model coefficients as inliers.

Parameters:
[in]model_coefficientsthe coefficients of a model that we need to compute distances to
[in]thresholdmaximum admissible distance threshold for determining the inliers from the outliers
Returns:
the resultant number of inliers

Implements pcl::SampleConsensusModel< PointT >.

Reimplemented in pcl::SampleConsensusModelRegistration2D< PointT >.

Definition at line 193 of file sac_model_registration.hpp.

template<typename PointT>
bool pcl::SampleConsensusModelRegistration< PointT >::doSamplesVerifyModel ( const std::set< int > &  indices,
const Eigen::VectorXf &  model_coefficients,
const double  threshold 
) [inline, virtual]

Verify whether a subset of indices verifies a given set of model coefficients. Pure virtual.

Parameters:
[in]indicesthe data indices that need to be tested against the model
[in]model_coefficientsthe set of model coefficients
[in]thresholda maximum admissible distance threshold for determining the inliers from the outliers

Implements pcl::SampleConsensusModel< PointT >.

Definition at line 202 of file sac_model_registration.h.

template<typename PointT >
void pcl::SampleConsensusModelRegistration< PointT >::estimateRigidTransformationSVD ( const pcl::PointCloud< PointT > &  cloud_src,
const std::vector< int > &  indices_src,
const pcl::PointCloud< PointT > &  cloud_tgt,
const std::vector< int > &  indices_tgt,
Eigen::VectorXf &  transform 
) [protected]

Estimate a rigid transformation between a source and a target point cloud using an SVD closed-form solution of absolute orientation using unit quaternions.

Parameters:
[in]cloud_srcthe source point cloud dataset
[in]indices_srcthe vector of indices describing the points of interest in cloud_src
[in]cloud_tgtthe target point cloud dataset
[in]indices_tgtthe vector of indices describing the correspondences of the interest points from indices_src
[out]transformthe resultant transformation matrix (as model coefficients)

This method is an implementation of: Horn, B. “Closed-Form Solution of Absolute Orientation Using Unit Quaternions,” JOSA A, Vol. 4, No. 4, 1987

Definition at line 268 of file sac_model_registration.hpp.

template<typename PointT >
void pcl::SampleConsensusModelRegistration< PointT >::getDistancesToModel ( const Eigen::VectorXf &  model_coefficients,
std::vector< double > &  distances 
) [virtual]

Compute all distances from the transformed points to their correspondences.

Parameters:
[in]model_coefficientsthe 4x4 transformation matrix
[out]distancesthe resultant estimated distances

Implements pcl::SampleConsensusModel< PointT >.

Reimplemented in pcl::SampleConsensusModelRegistration2D< PointT >.

Definition at line 88 of file sac_model_registration.hpp.

template<typename PointT>
pcl::SacModel pcl::SampleConsensusModelRegistration< PointT >::getModelType ( ) const [inline, virtual]

Return an unique id for this model (SACMODEL_REGISTRATION).

Implements pcl::SampleConsensusModel< PointT >.

Definition at line 211 of file sac_model_registration.h.

template<typename PointT>
bool pcl::SampleConsensusModelRegistration< PointT >::isModelValid ( const Eigen::VectorXf &  model_coefficients) [inline, protected, virtual]

Check whether a model is valid given the user constraints.

Parameters:
[in]model_coefficientsthe set of model coefficients

Implements pcl::SampleConsensusModel< PointT >.

Definition at line 218 of file sac_model_registration.h.

template<typename PointT >
bool pcl::SampleConsensusModelRegistration< PointT >::isSampleGood ( const std::vector< int > &  samples) const [protected, virtual]

Check if a sample of indices results in a good sample of points indices.

Parameters:
[in]samplesthe resultant index samples

Implements pcl::SampleConsensusModel< PointT >.

Reimplemented in pcl::SampleConsensusModelRegistration2D< PointT >.

Definition at line 51 of file sac_model_registration.hpp.

template<typename PointT >
void pcl::SampleConsensusModelRegistration< PointT >::optimizeModelCoefficients ( const std::vector< int > &  inliers,
const Eigen::VectorXf &  model_coefficients,
Eigen::VectorXf &  optimized_coefficients 
) [virtual]

Recompute the 4x4 transformation using the given inlier set.

Parameters:
[in]inliersthe data inliers found as supporting the model
[in]model_coefficientsthe initial guess for the optimization
[out]optimized_coefficientsthe resultant recomputed transformation

Implements pcl::SampleConsensusModel< PointT >.

Definition at line 239 of file sac_model_registration.hpp.

template<typename PointT>
void pcl::SampleConsensusModelRegistration< PointT >::projectPoints ( const std::vector< int > &  inliers,
const Eigen::VectorXf &  model_coefficients,
PointCloud projected_points,
bool  copy_data_fields = true 
) [inline, virtual]

Create a new point cloud with inliers projected onto the model. Pure virtual.

Parameters:
[in]inliersthe data inliers that we want to project on the model
[in]model_coefficientsthe coefficients of a model
[out]projected_pointsthe resultant projected points
[in]copy_data_fieldsset to true (default) if we want the projected_points cloud to be an exact copy of the input dataset minus the point projections on the plane model

Implements pcl::SampleConsensusModel< PointT >.

Definition at line 195 of file sac_model_registration.h.

template<typename PointT >
void pcl::SampleConsensusModelRegistration< PointT >::selectWithinDistance ( const Eigen::VectorXf &  model_coefficients,
const double  threshold,
std::vector< int > &  inliers 
) [virtual]

Select all the points which respect the given model coefficients as inliers.

Parameters:
[in]model_coefficientsthe 4x4 transformation matrix
[in]thresholda maximum admissible distance threshold for determining the inliers from the outliers
[out]inliersthe resultant model inliers

Implements pcl::SampleConsensusModel< PointT >.

Reimplemented in pcl::SampleConsensusModelRegistration2D< PointT >.

Definition at line 134 of file sac_model_registration.hpp.

template<typename PointT>
virtual void pcl::SampleConsensusModelRegistration< PointT >::setInputCloud ( const PointCloudConstPtr cloud) [inline, virtual]

Provide a pointer to the input dataset.

Parameters:
[in]cloudthe const boost shared pointer to a PointCloud message

Reimplemented from pcl::SampleConsensusModel< PointT >.

Definition at line 112 of file sac_model_registration.h.

template<typename PointT>
void pcl::SampleConsensusModelRegistration< PointT >::setInputTarget ( const PointCloudConstPtr target) [inline]

Set the input point cloud target.

Parameters:
[in]targetthe input point cloud target

Definition at line 123 of file sac_model_registration.h.

template<typename PointT>
void pcl::SampleConsensusModelRegistration< PointT >::setInputTarget ( const PointCloudConstPtr target,
const std::vector< int > &  indices_tgt 
) [inline]

Set the input point cloud target.

Parameters:
[in]targetthe input point cloud target
[in]indices_tgta vector of point indices to be used from target

Definition at line 141 of file sac_model_registration.h.


Member Data Documentation

template<typename PointT>
std::map<int, int> pcl::SampleConsensusModelRegistration< PointT >::correspondences_ [protected]

Given the index in the original point cloud, give the matching original index in the target cloud.

Definition at line 325 of file sac_model_registration.h.

template<typename PointT>
boost::shared_ptr<std::vector<int> > pcl::SampleConsensusModelRegistration< PointT >::indices_tgt_ [protected]

A pointer to the vector of target point indices to use.

Definition at line 322 of file sac_model_registration.h.

template<typename PointT>
double pcl::SampleConsensusModelRegistration< PointT >::sample_dist_thresh_ [protected]

Internal distance threshold used for the sample selection step.

Definition at line 328 of file sac_model_registration.h.

template<typename PointT>
PointCloudConstPtr pcl::SampleConsensusModelRegistration< PointT >::target_ [protected]

A boost shared pointer to the target point cloud data array.

Definition at line 319 of file sac_model_registration.h.


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


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