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

CorrespondenceRejectorSampleConsensus implements a correspondence rejection using Random Sample Consensus to identify inliers (and reject outliers) More...

#include <correspondence_rejection_sample_consensus.h>

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

List of all members.

Public Member Functions

 CorrespondenceRejectorSampleConsensus ()
 Empty constructor.
Eigen::Matrix4f getBestTransformation ()
 Get the best transformation after RANSAC rejection.
double getInlierThreshold ()
 Get the maximum distance between corresponding points.
int getMaxIterations ()
 Get the maximum number of iterations.
void getRemainingCorrespondences (const pcl::Correspondences &original_correspondences, pcl::Correspondences &remaining_correspondences)
 Get a list of valid correspondences after rejection from the original set of correspondences.
void setInlierThreshold (double threshold)
 Set the maximum distance between corresponding points. Correspondences with distances below the threshold are considered as inliers.
virtual void setInputCloud (const PointCloudConstPtr &cloud)
 Provide a source point cloud dataset (must contain XYZ data!)
void setMaxIterations (int max_iterations)
 Set the maximum number of iterations.
virtual void setTargetCloud (const PointCloudConstPtr &cloud)
 Provide a target point cloud dataset (must contain XYZ data!)
virtual ~CorrespondenceRejectorSampleConsensus ()
 Empty destructor.

Protected Member Functions

void applyRejection (pcl::Correspondences &correspondences)
 Apply the rejection algorithm.

Protected Attributes

Eigen::Matrix4f best_transformation_
double inlier_threshold_
PointCloudConstPtr input_
int max_iterations_
PointCloudConstPtr target_

Private Types

typedef pcl::PointCloud< PointTPointCloud
typedef PointCloud::ConstPtr PointCloudConstPtr
typedef PointCloud::Ptr PointCloudPtr

Detailed Description

template<typename PointT>
class pcl::registration::CorrespondenceRejectorSampleConsensus< PointT >

CorrespondenceRejectorSampleConsensus implements a correspondence rejection using Random Sample Consensus to identify inliers (and reject outliers)

Author:
Dirk Holz

Definition at line 56 of file correspondence_rejection_sample_consensus.h.


Member Typedef Documentation

Definition at line 62 of file correspondence_rejection_sample_consensus.h.

Definition at line 64 of file correspondence_rejection_sample_consensus.h.

Definition at line 63 of file correspondence_rejection_sample_consensus.h.


Constructor & Destructor Documentation

Empty constructor.

Definition at line 69 of file correspondence_rejection_sample_consensus.h.

Empty destructor.

Definition at line 80 of file correspondence_rejection_sample_consensus.h.


Member Function Documentation

template<typename PointT>
void pcl::registration::CorrespondenceRejectorSampleConsensus< PointT >::applyRejection ( pcl::Correspondences correspondences) [inline, protected, virtual]

Apply the rejection algorithm.

Parameters:
[out]correspondencesthe set of resultant correspondences.

Implements pcl::registration::CorrespondenceRejector.

Definition at line 139 of file correspondence_rejection_sample_consensus.h.

template<typename PointT>
Eigen::Matrix4f pcl::registration::CorrespondenceRejectorSampleConsensus< PointT >::getBestTransformation ( ) [inline]

Get the best transformation after RANSAC rejection.

Returns:
The homogeneous 4x4 transformation yielding the largest number of inliers.

Definition at line 131 of file correspondence_rejection_sample_consensus.h.

template<typename PointT>
double pcl::registration::CorrespondenceRejectorSampleConsensus< PointT >::getInlierThreshold ( ) [inline]

Get the maximum distance between corresponding points.

Returns:
Distance threshold in the same dimension as source and target data sets.

Definition at line 113 of file correspondence_rejection_sample_consensus.h.

Get the maximum number of iterations.

Returns:
max_iterations Maximum number if iterations to run

Definition at line 125 of file correspondence_rejection_sample_consensus.h.

template<typename PointT >
void pcl::registration::CorrespondenceRejectorSampleConsensus< PointT >::getRemainingCorrespondences ( const pcl::Correspondences original_correspondences,
pcl::Correspondences remaining_correspondences 
) [inline, virtual]

Get a list of valid correspondences after rejection from the original set of correspondences.

Parameters:
[in]original_correspondencesthe set of initial correspondences given
[out]remaining_correspondencesthe resultant filtered set of remaining correspondences

Implements pcl::registration::CorrespondenceRejector.

Definition at line 45 of file correspondence_rejection_sample_consensus.hpp.

template<typename PointT>
void pcl::registration::CorrespondenceRejectorSampleConsensus< PointT >::setInlierThreshold ( double  threshold) [inline]

Set the maximum distance between corresponding points. Correspondences with distances below the threshold are considered as inliers.

Parameters:
[in]thresholdDistance threshold in the same dimension as source and target data sets.

Definition at line 107 of file correspondence_rejection_sample_consensus.h.

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

Provide a source point cloud dataset (must contain XYZ data!)

Parameters:
[in]clouda cloud containing XYZ data

Definition at line 94 of file correspondence_rejection_sample_consensus.h.

template<typename PointT>
void pcl::registration::CorrespondenceRejectorSampleConsensus< PointT >::setMaxIterations ( int  max_iterations) [inline]

Set the maximum number of iterations.

Parameters:
[in]max_iterationsMaximum number if iterations to run

Definition at line 119 of file correspondence_rejection_sample_consensus.h.

template<typename PointT>
virtual void pcl::registration::CorrespondenceRejectorSampleConsensus< PointT >::setTargetCloud ( const PointCloudConstPtr cloud) [inline, virtual]

Provide a target point cloud dataset (must contain XYZ data!)

Parameters:
[in]clouda cloud containing XYZ data

Definition at line 100 of file correspondence_rejection_sample_consensus.h.


Member Data Documentation

template<typename PointT>
Eigen::Matrix4f pcl::registration::CorrespondenceRejectorSampleConsensus< PointT >::best_transformation_ [protected]

Definition at line 151 of file correspondence_rejection_sample_consensus.h.

template<typename PointT>
double pcl::registration::CorrespondenceRejectorSampleConsensus< PointT >::inlier_threshold_ [protected]

Definition at line 144 of file correspondence_rejection_sample_consensus.h.

Definition at line 148 of file correspondence_rejection_sample_consensus.h.

Definition at line 146 of file correspondence_rejection_sample_consensus.h.

Definition at line 149 of file correspondence_rejection_sample_consensus.h.


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


pcl
Author(s): Open Perception
autogenerated on Mon Oct 6 2014 03:20:21