#include <correspondence_rejection_surface_normal.h>
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. |
CorrespondenceRejectorSurfaceNormal implements a simple correspondence rejection method based on the angle between the normals at correspondent points.
Definition at line 59 of file correspondence_rejection_surface_normal.h.
typedef boost::shared_ptr<DataContainerInterface> pcl::registration::CorrespondenceRejectorSurfaceNormal::DataContainerPtr [protected] |
Definition at line 164 of file correspondence_rejection_surface_normal.h.
pcl::registration::CorrespondenceRejectorSurfaceNormal::CorrespondenceRejectorSurfaceNormal | ( | ) | [inline] |
Empty constructor.
Definition at line 68 of file correspondence_rejection_surface_normal.h.
void pcl::registration::CorrespondenceRejectorSurfaceNormal::applyRejection | ( | pcl::Correspondences & | correspondences | ) | [inline, protected, virtual] |
Apply the rejection algorithm.
[out] | correspondences | the set of resultant correspondences. |
Implements pcl::registration::CorrespondenceRejector.
Definition at line 155 of file correspondence_rejection_surface_normal.h.
pcl::PointCloud<NormalT>::Ptr pcl::registration::CorrespondenceRejectorSurfaceNormal::getInputNormals | ( | ) | const [inline] |
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.
[in] | original_correspondences | the set of initial correspondences given |
[out] | remaining_correspondences | the resultant filtered set of remaining correspondences |
Implements pcl::registration::CorrespondenceRejector.
Definition at line 43 of file correspondence_rejection_surface_normal.hpp.
pcl::PointCloud<NormalT>::Ptr pcl::registration::CorrespondenceRejectorSurfaceNormal::getTargetNormals | ( | ) | const [inline] |
Get the normals computed on the target point cloud.
Definition at line 147 of file correspondence_rejection_surface_normal.h.
double pcl::registration::CorrespondenceRejectorSurfaceNormal::getThreshold | ( | ) | const [inline] |
Get the thresholding angle between the normals for correspondence rejection.
Definition at line 90 of file correspondence_rejection_surface_normal.h.
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.
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.
[in] | cloud | a cloud containing XYZ data |
Definition at line 104 of file correspondence_rejection_surface_normal.h.
void pcl::registration::CorrespondenceRejectorSurfaceNormal::setInputNormals | ( | const typename pcl::PointCloud< NormalT >::ConstPtr & | normals | ) | [inline] |
Set the normals computed on the input point cloud.
[in] | normals | the normals computed for the input cloud |
Definition at line 125 of file correspondence_rejection_surface_normal.h.
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.
[in] | target | a cloud containing XYZ data |
Definition at line 115 of file correspondence_rejection_surface_normal.h.
void pcl::registration::CorrespondenceRejectorSurfaceNormal::setTargetNormals | ( | const typename pcl::PointCloud< NormalT >::ConstPtr & | normals | ) | [inline] |
Set the normals computed on the target point cloud.
[in] | normals | the normals computed for the input cloud |
Definition at line 135 of file correspondence_rejection_surface_normal.h.
void pcl::registration::CorrespondenceRejectorSurfaceNormal::setThreshold | ( | double | threshold | ) | [inline] |
Set the thresholding angle between the normals for correspondence rejection.
[in] | threshold | cosine of the thresholding angle between the normals for rejection |
Definition at line 86 of file correspondence_rejection_surface_normal.h.
DataContainerPtr pcl::registration::CorrespondenceRejectorSurfaceNormal::data_container_ [protected] |
A pointer to the DataContainer object containing the input and target point clouds.
Definition at line 167 of file correspondence_rejection_surface_normal.h.
double pcl::registration::CorrespondenceRejectorSurfaceNormal::threshold_ [protected] |
The median distance threshold between two correspondent points in source <-> target.
Definition at line 162 of file correspondence_rejection_surface_normal.h.