Classes | Public Types | Public Member Functions | Private Member Functions | Static Private Member Functions | Private Attributes
pcl::PPFRegistration< PointSource, PointTarget > Class Template Reference

Class that registers two point clouds based on their sets of PPFSignatures. Please refer to the following publication for more details: B. Drost, M. Ulrich, N. Navab, S. Ilic Model Globally, Match Locally: Efficient and Robust 3D Object Recognition 2010 IEEE Conference on Computer Vision and Pattern Recognition (CVPR) 13-18 June 2010, San Francisco, CA. More...

#include <ppf_registration.h>

Inheritance diagram for pcl::PPFRegistration< PointSource, PointTarget >:
Inheritance graph
[legend]

List of all members.

Classes

struct  PoseWithVotes
 Structure for storing a pose (represented as an Eigen::Affine3f) and an integer for counting votes. More...

Public Types

typedef pcl::PointCloud
< PointSource > 
PointCloudSource
typedef PointCloudSource::ConstPtr PointCloudSourceConstPtr
typedef PointCloudSource::Ptr PointCloudSourcePtr
typedef pcl::PointCloud
< PointTarget > 
PointCloudTarget
typedef PointCloudTarget::ConstPtr PointCloudTargetConstPtr
typedef PointCloudTarget::Ptr PointCloudTargetPtr
typedef std::vector
< PoseWithVotes,
Eigen::aligned_allocator
< PoseWithVotes > > 
PoseWithVotesList

Public Member Functions

float getPositionClusteringThreshold ()
 Returns the parameter defining the position difference clustering parameter - distance threshold below which two poses are considered close enough to be in the same cluster (for the clustering phase of the algorithm)
float getRotationClusteringThreshold ()
 Returns the parameter defining the rotation clustering threshold.
unsigned int getSceneReferencePointSamplingRate ()
 Returns the parameter for the scene reference point sampling rate of the algorithm.
PPFHashMapSearch::Ptr getSearchMethod ()
 Getter function for the search method of the class.
 PPFRegistration ()
 Empty constructor that initializes all the parameters of the algorithm with default values.
void setInputTarget (const PointCloudTargetConstPtr &cloud)
 Provide a pointer to the input target (e.g., the point cloud that we want to align the input source to)
void setPositionClusteringThreshold (float clustering_position_diff_threshold)
 Method for setting the position difference clustering parameter.
void setRotationClusteringThreshold (float clustering_rotation_diff_threshold)
 Method for setting the rotation clustering parameter.
void setSceneReferencePointSamplingRate (unsigned int scene_reference_point_sampling_rate)
 Method for setting the scene reference point sampling rate.
void setSearchMethod (PPFHashMapSearch::Ptr search_method)
 Function that sets the search method for the algorithm.

Private Member Functions

void clusterPoses (PoseWithVotesList &poses, PoseWithVotesList &result)
 Method that clusters a set of given poses by using the clustering thresholds and their corresponding number of votes (see publication for more details)
void computeTransformation (PointCloudSource &output, const Eigen::Matrix4f &guess)
 Method that calculates the transformation between the input_ and target_ point clouds, based on the PPF features.
bool posesWithinErrorBounds (Eigen::Affine3f &pose1, Eigen::Affine3f &pose2)
 Method that checks whether two poses are close together - based on the clustering threshold parameters of the class.

Static Private Member Functions

static bool clusterVotesCompareFunction (const std::pair< size_t, unsigned int > &a, const std::pair< size_t, unsigned int > &b)
 static method used for the std::sort function to order two pairs <index, votes> by the number of votes (unsigned integer value)
static bool poseWithVotesCompareFunction (const PoseWithVotes &a, const PoseWithVotes &b)
 static method used for the std::sort function to order two PoseWithVotes instances by their number of votes

Private Attributes

float clustering_position_diff_threshold_
 position and rotation difference thresholds below which two poses are considered to be in the same cluster (for the clustering phase of the algorithm)
float clustering_rotation_diff_threshold_
unsigned int scene_reference_point_sampling_rate_
 parameter for the sampling rate of the scene reference points
pcl::KdTreeFLANN< PointTarget >
::Ptr 
scene_search_tree_
 use a kd-tree with range searches of range max_dist to skip an O(N) pass through the point cloud
PPFHashMapSearch::Ptr search_method_
 the search method that is going to be used to find matching feature pairs

Detailed Description

template<typename PointSource, typename PointTarget>
class pcl::PPFRegistration< PointSource, PointTarget >

Class that registers two point clouds based on their sets of PPFSignatures. Please refer to the following publication for more details: B. Drost, M. Ulrich, N. Navab, S. Ilic Model Globally, Match Locally: Efficient and Robust 3D Object Recognition 2010 IEEE Conference on Computer Vision and Pattern Recognition (CVPR) 13-18 June 2010, San Francisco, CA.

Note:
This class works in tandem with the PPFEstimation class
Author:
Alexandru-Eugen Ichim

Definition at line 141 of file ppf_registration.h.


Member Typedef Documentation

template<typename PointSource, typename PointTarget>
typedef pcl::PointCloud<PointSource> pcl::PPFRegistration< PointSource, PointTarget >::PointCloudSource

Reimplemented from pcl::Registration< PointSource, PointTarget >.

Definition at line 168 of file ppf_registration.h.

template<typename PointSource, typename PointTarget>
typedef PointCloudSource::ConstPtr pcl::PPFRegistration< PointSource, PointTarget >::PointCloudSourceConstPtr

Reimplemented from pcl::Registration< PointSource, PointTarget >.

Definition at line 170 of file ppf_registration.h.

template<typename PointSource, typename PointTarget>
typedef PointCloudSource::Ptr pcl::PPFRegistration< PointSource, PointTarget >::PointCloudSourcePtr

Reimplemented from pcl::Registration< PointSource, PointTarget >.

Definition at line 169 of file ppf_registration.h.

template<typename PointSource, typename PointTarget>
typedef pcl::PointCloud<PointTarget> pcl::PPFRegistration< PointSource, PointTarget >::PointCloudTarget

Reimplemented from pcl::Registration< PointSource, PointTarget >.

Definition at line 172 of file ppf_registration.h.

template<typename PointSource, typename PointTarget>
typedef PointCloudTarget::ConstPtr pcl::PPFRegistration< PointSource, PointTarget >::PointCloudTargetConstPtr

Reimplemented from pcl::Registration< PointSource, PointTarget >.

Definition at line 174 of file ppf_registration.h.

template<typename PointSource, typename PointTarget>
typedef PointCloudTarget::Ptr pcl::PPFRegistration< PointSource, PointTarget >::PointCloudTargetPtr

Reimplemented from pcl::Registration< PointSource, PointTarget >.

Definition at line 173 of file ppf_registration.h.

template<typename PointSource, typename PointTarget>
typedef std::vector<PoseWithVotes, Eigen::aligned_allocator<PoseWithVotes> > pcl::PPFRegistration< PointSource, PointTarget >::PoseWithVotesList

Definition at line 158 of file ppf_registration.h.


Constructor & Destructor Documentation

template<typename PointSource, typename PointTarget>
pcl::PPFRegistration< PointSource, PointTarget >::PPFRegistration ( ) [inline]

Empty constructor that initializes all the parameters of the algorithm with default values.

Definition at line 178 of file ppf_registration.h.


Member Function Documentation

template<typename PointSource, typename PointTarget>
void pcl::PPFRegistration< PointSource, PointTarget >::clusterPoses ( PoseWithVotesList poses,
PoseWithVotesList result 
) [private]

Method that clusters a set of given poses by using the clustering thresholds and their corresponding number of votes (see publication for more details)

Todo:
some kind of threshold for determining whether a cluster has enough votes or not... now just taking the first three clusters

averaging rotations by just averaging the quaternions in 4D space - reference "On Averaging Rotations" by CLAUS GRAMKOW

Definition at line 249 of file ppf_registration.hpp.

template<typename PointSource , typename PointTarget >
bool pcl::PPFRegistration< PointSource, PointTarget >::clusterVotesCompareFunction ( const std::pair< size_t, unsigned int > &  a,
const std::pair< size_t, unsigned int > &  b 
) [static, private]

static method used for the std::sort function to order two pairs <index, votes> by the number of votes (unsigned integer value)

Definition at line 340 of file ppf_registration.hpp.

template<typename PointSource , typename PointTarget >
void pcl::PPFRegistration< PointSource, PointTarget >::computeTransformation ( PointCloudSource output,
const Eigen::Matrix4f &  guess 
) [private, virtual]

Method that calculates the transformation between the input_ and target_ point clouds, based on the PPF features.

Implements pcl::Registration< PointSource, PointTarget >.

Definition at line 117 of file ppf_registration.hpp.

template<typename PointSource, typename PointTarget>
float pcl::PPFRegistration< PointSource, PointTarget >::getPositionClusteringThreshold ( ) [inline]

Returns the parameter defining the position difference clustering parameter - distance threshold below which two poses are considered close enough to be in the same cluster (for the clustering phase of the algorithm)

Definition at line 198 of file ppf_registration.h.

template<typename PointSource, typename PointTarget>
float pcl::PPFRegistration< PointSource, PointTarget >::getRotationClusteringThreshold ( ) [inline]

Returns the parameter defining the rotation clustering threshold.

Definition at line 210 of file ppf_registration.h.

template<typename PointSource, typename PointTarget>
unsigned int pcl::PPFRegistration< PointSource, PointTarget >::getSceneReferencePointSamplingRate ( ) [inline]

Returns the parameter for the scene reference point sampling rate of the algorithm.

Definition at line 220 of file ppf_registration.h.

template<typename PointSource, typename PointTarget>
PPFHashMapSearch::Ptr pcl::PPFRegistration< PointSource, PointTarget >::getSearchMethod ( ) [inline]

Getter function for the search method of the class.

Definition at line 232 of file ppf_registration.h.

template<typename PointSource , typename PointTarget >
bool pcl::PPFRegistration< PointSource, PointTarget >::posesWithinErrorBounds ( Eigen::Affine3f &  pose1,
Eigen::Affine3f &  pose2 
) [private]

Method that checks whether two poses are close together - based on the clustering threshold parameters of the class.

Definition at line 315 of file ppf_registration.hpp.

template<typename PointSource, typename PointTarget>
bool pcl::PPFRegistration< PointSource, PointTarget >::poseWithVotesCompareFunction ( const PoseWithVotes a,
const PoseWithVotes b 
) [static, private]

static method used for the std::sort function to order two PoseWithVotes instances by their number of votes

Definition at line 331 of file ppf_registration.hpp.

template<typename PointSource , typename PointTarget >
void pcl::PPFRegistration< PointSource, PointTarget >::setInputTarget ( const PointCloudTargetConstPtr cloud)

Provide a pointer to the input target (e.g., the point cloud that we want to align the input source to)

Parameters:
cloudthe input point cloud target

Definition at line 106 of file ppf_registration.hpp.

template<typename PointSource, typename PointTarget>
void pcl::PPFRegistration< PointSource, PointTarget >::setPositionClusteringThreshold ( float  clustering_position_diff_threshold) [inline]

Method for setting the position difference clustering parameter.

Parameters:
clustering_position_diff_thresholddistance threshold below which two poses are considered close enough to be in the same cluster (for the clustering phase of the algorithm)

Definition at line 191 of file ppf_registration.h.

template<typename PointSource, typename PointTarget>
void pcl::PPFRegistration< PointSource, PointTarget >::setRotationClusteringThreshold ( float  clustering_rotation_diff_threshold) [inline]

Method for setting the rotation clustering parameter.

Parameters:
clustering_rotation_diff_thresholdrotation difference threshold below which two poses are considered to be in the same cluster (for the clustering phase of the algorithm)

Definition at line 205 of file ppf_registration.h.

template<typename PointSource, typename PointTarget>
void pcl::PPFRegistration< PointSource, PointTarget >::setSceneReferencePointSamplingRate ( unsigned int  scene_reference_point_sampling_rate) [inline]

Method for setting the scene reference point sampling rate.

Parameters:
scene_reference_point_sampling_ratesampling rate for the scene reference point

Definition at line 216 of file ppf_registration.h.

template<typename PointSource, typename PointTarget>
void pcl::PPFRegistration< PointSource, PointTarget >::setSearchMethod ( PPFHashMapSearch::Ptr  search_method) [inline]

Function that sets the search method for the algorithm.

Note:
Right now, the only available method is the one initially proposed by the authors - by using a hash map with discretized feature vectors
Parameters:
search_methodsmart pointer to the search method to be set

Definition at line 228 of file ppf_registration.h.


Member Data Documentation

template<typename PointSource, typename PointTarget>
float pcl::PPFRegistration< PointSource, PointTarget >::clustering_position_diff_threshold_ [private]

position and rotation difference thresholds below which two poses are considered to be in the same cluster (for the clustering phase of the algorithm)

Definition at line 255 of file ppf_registration.h.

template<typename PointSource, typename PointTarget>
float pcl::PPFRegistration< PointSource, PointTarget >::clustering_rotation_diff_threshold_ [private]

Definition at line 255 of file ppf_registration.h.

template<typename PointSource, typename PointTarget>
unsigned int pcl::PPFRegistration< PointSource, PointTarget >::scene_reference_point_sampling_rate_ [private]

parameter for the sampling rate of the scene reference points

Definition at line 251 of file ppf_registration.h.

template<typename PointSource, typename PointTarget>
pcl::KdTreeFLANN<PointTarget>::Ptr pcl::PPFRegistration< PointSource, PointTarget >::scene_search_tree_ [private]

use a kd-tree with range searches of range max_dist to skip an O(N) pass through the point cloud

Definition at line 258 of file ppf_registration.h.

template<typename PointSource, typename PointTarget>
PPFHashMapSearch::Ptr pcl::PPFRegistration< PointSource, PointTarget >::search_method_ [private]

the search method that is going to be used to find matching feature pairs

Definition at line 248 of file ppf_registration.h.


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


pcl
Author(s): Open Perception
autogenerated on Mon Oct 6 2014 03:19:52