Public Member Functions | Protected Types | Protected Member Functions | Protected Attributes
pcl::registration::CorrespondenceRejectorSurfaceNormal Class Reference

#include <correspondence_rejection_surface_normal.h>

Inheritance diagram for pcl::registration::CorrespondenceRejectorSurfaceNormal:
Inheritance graph
[legend]

List of all members.

Public Member Functions

 CorrespondenceRejectorSurfaceNormal ()
 Empty constructor.
template<typename NormalT >
pcl::PointCloud< NormalT >::Ptr getInputNormals () const
 Get the normals computed on the input point cloud.
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.
template<typename NormalT >
pcl::PointCloud< NormalT >::Ptr getTargetNormals () const
 Get the normals computed on the target point cloud.
double getThreshold () const
 Get the thresholding angle between the normals for correspondence rejection.
template<typename PointT , typename NormalT >
void initializeDataContainer ()
 Initialize the data container object for the point type and the normal type.
template<typename PointT >
void setInputCloud (const typename pcl::PointCloud< PointT >::ConstPtr &input)
 Provide a source point cloud dataset (must contain XYZ data!), used to compute the correspondence distance.
template<typename PointT , typename NormalT >
void setInputNormals (const typename pcl::PointCloud< NormalT >::ConstPtr &normals)
 Set the normals computed on the input point cloud.
template<typename PointT >
void setInputTarget (const typename pcl::PointCloud< PointT >::ConstPtr &target)
 Provide a target point cloud dataset (must contain XYZ data!), used to compute the correspondence distance.
template<typename PointT , typename NormalT >
void setTargetNormals (const typename pcl::PointCloud< NormalT >::ConstPtr &normals)
 Set the normals computed on the target point cloud.
void setThreshold (double threshold)
 Set the thresholding angle between the normals for correspondence rejection.

Protected Types

typedef boost::shared_ptr
< DataContainerInterface
DataContainerPtr

Protected Member Functions

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

Protected Attributes

DataContainerPtr data_container_
 A pointer to the DataContainer object containing the input and target point clouds.
double threshold_
 The median distance threshold between two correspondent points in source <-> target.

Detailed Description

CorrespondenceRejectorSurfaceNormal implements a simple correspondence rejection method based on the angle between the normals at correspondent points.

Note:
If setInputCloud and setInputTarget are given, then the distances between correspondences will be estimated using the given XYZ data, and not read from the set of input correspondences.
Author:
Aravindhan K Krishnan. This code is ported from libpointmatcher (https://github.com/ethz-asl/libpointmatcher)

Definition at line 59 of file correspondence_rejection_surface_normal.h.


Member Typedef Documentation

Definition at line 164 of file correspondence_rejection_surface_normal.h.


Constructor & Destructor Documentation

Empty constructor.

Definition at line 68 of file correspondence_rejection_surface_normal.h.


Member Function Documentation

void pcl::registration::CorrespondenceRejectorSurfaceNormal::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 155 of file correspondence_rejection_surface_normal.h.

Get the normals computed on the input point cloud.

Definition at line 143 of file correspondence_rejection_surface_normal.h.

void pcl::registration::CorrespondenceRejectorSurfaceNormal::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 43 of file correspondence_rejection_surface_normal.hpp.

Get the normals computed on the target point cloud.

Definition at line 147 of file correspondence_rejection_surface_normal.h.

Get the thresholding angle between the normals for correspondence rejection.

Definition at line 90 of file correspondence_rejection_surface_normal.h.

template<typename PointT , typename NormalT >
void pcl::registration::CorrespondenceRejectorSurfaceNormal::initializeDataContainer ( ) [inline]

Initialize the data container object for the point type and the normal type.

Definition at line 95 of file correspondence_rejection_surface_normal.h.

template<typename PointT >
void pcl::registration::CorrespondenceRejectorSurfaceNormal::setInputCloud ( const typename pcl::PointCloud< PointT >::ConstPtr &  input) [inline]

Provide a source point cloud dataset (must contain XYZ data!), used to compute the correspondence distance.

Parameters:
[in]clouda cloud containing XYZ data

Definition at line 104 of file correspondence_rejection_surface_normal.h.

template<typename PointT , typename NormalT >
void pcl::registration::CorrespondenceRejectorSurfaceNormal::setInputNormals ( const typename pcl::PointCloud< NormalT >::ConstPtr &  normals) [inline]

Set the normals computed on the input point cloud.

Parameters:
[in]normalsthe normals computed for the input cloud

Definition at line 125 of file correspondence_rejection_surface_normal.h.

template<typename PointT >
void pcl::registration::CorrespondenceRejectorSurfaceNormal::setInputTarget ( const typename pcl::PointCloud< PointT >::ConstPtr &  target) [inline]

Provide a target point cloud dataset (must contain XYZ data!), used to compute the correspondence distance.

Parameters:
[in]targeta cloud containing XYZ data

Definition at line 115 of file correspondence_rejection_surface_normal.h.

template<typename PointT , typename NormalT >
void pcl::registration::CorrespondenceRejectorSurfaceNormal::setTargetNormals ( const typename pcl::PointCloud< NormalT >::ConstPtr &  normals) [inline]

Set the normals computed on the target point cloud.

Parameters:
[in]normalsthe normals computed for the input cloud

Definition at line 135 of file correspondence_rejection_surface_normal.h.

Set the thresholding angle between the normals for correspondence rejection.

Parameters:
[in]thresholdcosine of the thresholding angle between the normals for rejection

Definition at line 86 of file correspondence_rejection_surface_normal.h.


Member Data Documentation

A pointer to the DataContainer object containing the input and target point clouds.

Definition at line 167 of file correspondence_rejection_surface_normal.h.

The median distance threshold between two correspondent points in source <-> target.

Definition at line 162 of file correspondence_rejection_surface_normal.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