CorrespondenceEstimationNormalShooting computes correspondences as points in the target cloud which have minimum distance to normals computed on the input cloud More...
#include <correspondence_estimation_normal_shooting.h>

Public Types | |
| typedef boost::shared_ptr < const CorrespondenceEstimationNormalShooting < PointSource, PointTarget, NormalT, Scalar > > | ConstPtr |
| typedef pcl::search::KdTree < PointTarget > | KdTree |
| typedef pcl::search::KdTree < PointTarget >::Ptr | KdTreePtr |
| typedef PointCloudNormals::ConstPtr | NormalsConstPtr |
| typedef PointCloudNormals::Ptr | NormalsPtr |
| typedef pcl::PointCloud< NormalT > | PointCloudNormals |
| 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 boost::shared_ptr < CorrespondenceEstimationNormalShooting < PointSource, PointTarget, NormalT, Scalar > > | Ptr |
Public Member Functions | |
| CorrespondenceEstimationNormalShooting () | |
| Empty constructor. | |
| void | determineCorrespondences (pcl::Correspondences &correspondences, double max_distance=std::numeric_limits< double >::max()) |
| Determine the correspondences between input and target cloud. | |
| virtual void | determineReciprocalCorrespondences (pcl::Correspondences &correspondences, double max_distance=std::numeric_limits< double >::max()) |
| Determine the reciprocal correspondences between input and target cloud. A correspondence is considered reciprocal if both Src_i has Tgt_i as a correspondence, and Tgt_i has Src_i as one. | |
| void | getKSearch () const |
| Get the number of nearest neighbours considered in the target point cloud for computing correspondences. By default we use k = 10 nearest neighbors. | |
| NormalsConstPtr | getSourceNormals () const |
| Get the normals of the source point cloud. | |
| void | setKSearch (unsigned int k) |
| Set the number of nearest neighbours to be considered in the target point cloud. By default, we use k = 10 nearest neighbors. | |
| void | setSourceNormals (const NormalsConstPtr &normals) |
| Set the normals computed on the source point cloud. | |
| virtual | ~CorrespondenceEstimationNormalShooting () |
| Empty destructor. | |
Protected Member Functions | |
| bool | initCompute () |
| Internal computation initalization. | |
Private Attributes | |
| unsigned int | k_ |
| The number of neighbours to be considered in the target point cloud. | |
| NormalsConstPtr | source_normals_ |
| The normals computed at each point in the source cloud. | |
| NormalsPtr | source_normals_transformed_ |
| The normals computed at each point in the source cloud. | |
CorrespondenceEstimationNormalShooting computes correspondences as points in the target cloud which have minimum distance to normals computed on the input cloud
Code example:
pcl::PointCloud<pcl::PointNormal>::Ptr source, target; // ... read or fill in source and target pcl::CorrespondenceEstimationNormalShooting<pcl::PointNormal, pcl::PointNormal, pcl::PointNormal> est; est.setInputSource (source); est.setSourceNormals (source); est.setInputTarget (target); // Test the first 10 correspondences for each point in source, and return the best est.setKSearch (10); pcl::Correspondences all_correspondences; // Determine all correspondences est.determineCorrespondences (all_correspondences);
Definition at line 78 of file correspondence_estimation_normal_shooting.h.
| typedef boost::shared_ptr<const CorrespondenceEstimationNormalShooting<PointSource, PointTarget, NormalT, Scalar> > pcl::registration::CorrespondenceEstimationNormalShooting< PointSource, PointTarget, NormalT, Scalar >::ConstPtr |
Reimplemented from pcl::registration::CorrespondenceEstimationBase< PointSource, PointTarget, Scalar >.
Definition at line 82 of file correspondence_estimation_normal_shooting.h.
| typedef pcl::search::KdTree<PointTarget> pcl::registration::CorrespondenceEstimationNormalShooting< PointSource, PointTarget, NormalT, Scalar >::KdTree |
Reimplemented from pcl::registration::CorrespondenceEstimationBase< PointSource, PointTarget, Scalar >.
Definition at line 94 of file correspondence_estimation_normal_shooting.h.
| typedef pcl::search::KdTree<PointTarget>::Ptr pcl::registration::CorrespondenceEstimationNormalShooting< PointSource, PointTarget, NormalT, Scalar >::KdTreePtr |
Reimplemented from pcl::registration::CorrespondenceEstimationBase< PointSource, PointTarget, Scalar >.
Definition at line 95 of file correspondence_estimation_normal_shooting.h.
| typedef PointCloudNormals::ConstPtr pcl::registration::CorrespondenceEstimationNormalShooting< PointSource, PointTarget, NormalT, Scalar >::NormalsConstPtr |
Definition at line 107 of file correspondence_estimation_normal_shooting.h.
| typedef PointCloudNormals::Ptr pcl::registration::CorrespondenceEstimationNormalShooting< PointSource, PointTarget, NormalT, Scalar >::NormalsPtr |
Definition at line 106 of file correspondence_estimation_normal_shooting.h.
| typedef pcl::PointCloud<NormalT> pcl::registration::CorrespondenceEstimationNormalShooting< PointSource, PointTarget, NormalT, Scalar >::PointCloudNormals |
Definition at line 105 of file correspondence_estimation_normal_shooting.h.
| typedef pcl::PointCloud<PointSource> pcl::registration::CorrespondenceEstimationNormalShooting< PointSource, PointTarget, NormalT, Scalar >::PointCloudSource |
Reimplemented from pcl::registration::CorrespondenceEstimationBase< PointSource, PointTarget, Scalar >.
Definition at line 97 of file correspondence_estimation_normal_shooting.h.
| typedef PointCloudSource::ConstPtr pcl::registration::CorrespondenceEstimationNormalShooting< PointSource, PointTarget, NormalT, Scalar >::PointCloudSourceConstPtr |
Reimplemented from pcl::registration::CorrespondenceEstimationBase< PointSource, PointTarget, Scalar >.
Definition at line 99 of file correspondence_estimation_normal_shooting.h.
| typedef PointCloudSource::Ptr pcl::registration::CorrespondenceEstimationNormalShooting< PointSource, PointTarget, NormalT, Scalar >::PointCloudSourcePtr |
Reimplemented from pcl::registration::CorrespondenceEstimationBase< PointSource, PointTarget, Scalar >.
Definition at line 98 of file correspondence_estimation_normal_shooting.h.
| typedef pcl::PointCloud<PointTarget> pcl::registration::CorrespondenceEstimationNormalShooting< PointSource, PointTarget, NormalT, Scalar >::PointCloudTarget |
Reimplemented from pcl::registration::CorrespondenceEstimationBase< PointSource, PointTarget, Scalar >.
Definition at line 101 of file correspondence_estimation_normal_shooting.h.
| typedef PointCloudTarget::ConstPtr pcl::registration::CorrespondenceEstimationNormalShooting< PointSource, PointTarget, NormalT, Scalar >::PointCloudTargetConstPtr |
Reimplemented from pcl::registration::CorrespondenceEstimationBase< PointSource, PointTarget, Scalar >.
Definition at line 103 of file correspondence_estimation_normal_shooting.h.
| typedef PointCloudTarget::Ptr pcl::registration::CorrespondenceEstimationNormalShooting< PointSource, PointTarget, NormalT, Scalar >::PointCloudTargetPtr |
Reimplemented from pcl::registration::CorrespondenceEstimationBase< PointSource, PointTarget, Scalar >.
Definition at line 102 of file correspondence_estimation_normal_shooting.h.
| typedef boost::shared_ptr<CorrespondenceEstimationNormalShooting<PointSource, PointTarget, NormalT, Scalar> > pcl::registration::CorrespondenceEstimationNormalShooting< PointSource, PointTarget, NormalT, Scalar >::Ptr |
Reimplemented from pcl::registration::CorrespondenceEstimationBase< PointSource, PointTarget, Scalar >.
Definition at line 81 of file correspondence_estimation_normal_shooting.h.
| pcl::registration::CorrespondenceEstimationNormalShooting< PointSource, PointTarget, NormalT, Scalar >::CorrespondenceEstimationNormalShooting | ( | ) | [inline] |
Empty constructor.
Definition at line 114 of file correspondence_estimation_normal_shooting.h.
| virtual pcl::registration::CorrespondenceEstimationNormalShooting< PointSource, PointTarget, NormalT, Scalar >::~CorrespondenceEstimationNormalShooting | ( | ) | [inline, virtual] |
Empty destructor.
Definition at line 123 of file correspondence_estimation_normal_shooting.h.
| void pcl::registration::CorrespondenceEstimationNormalShooting< PointSource, PointTarget, NormalT, Scalar >::determineCorrespondences | ( | pcl::Correspondences & | correspondences, |
| double | max_distance = std::numeric_limits<double>::max () |
||
| ) | [virtual] |
Determine the correspondences between input and target cloud.
| [out] | correspondences | the found correspondences (index of query point, index of target point, distance) |
| [in] | max_distance | maximum distance between the normal on the source point cloud and the corresponding point in the target point cloud |
Implements pcl::registration::CorrespondenceEstimationBase< PointSource, PointTarget, Scalar >.
Definition at line 58 of file correspondence_estimation_normal_shooting.hpp.
| void pcl::registration::CorrespondenceEstimationNormalShooting< PointSource, PointTarget, NormalT, Scalar >::determineReciprocalCorrespondences | ( | pcl::Correspondences & | correspondences, |
| double | max_distance = std::numeric_limits<double>::max () |
||
| ) | [virtual] |
Determine the reciprocal correspondences between input and target cloud. A correspondence is considered reciprocal if both Src_i has Tgt_i as a correspondence, and Tgt_i has Src_i as one.
| [out] | correspondences | the found correspondences (index of query and target point, distance) |
| [in] | max_distance | maximum allowed distance between correspondences |
Implements pcl::registration::CorrespondenceEstimationBase< PointSource, PointTarget, Scalar >.
Definition at line 175 of file correspondence_estimation_normal_shooting.hpp.
| void pcl::registration::CorrespondenceEstimationNormalShooting< PointSource, PointTarget, NormalT, Scalar >::getKSearch | ( | ) | const [inline] |
Get the number of nearest neighbours considered in the target point cloud for computing correspondences. By default we use k = 10 nearest neighbors.
Definition at line 169 of file correspondence_estimation_normal_shooting.h.
| NormalsConstPtr pcl::registration::CorrespondenceEstimationNormalShooting< PointSource, PointTarget, NormalT, Scalar >::getSourceNormals | ( | ) | const [inline] |
Get the normals of the source point cloud.
Definition at line 134 of file correspondence_estimation_normal_shooting.h.
| bool pcl::registration::CorrespondenceEstimationNormalShooting< PointSource, PointTarget, NormalT, Scalar >::initCompute | ( | ) | [protected] |
Internal computation initalization.
Reimplemented from pcl::registration::CorrespondenceEstimationBase< PointSource, PointTarget, Scalar >.
Definition at line 45 of file correspondence_estimation_normal_shooting.hpp.
| void pcl::registration::CorrespondenceEstimationNormalShooting< PointSource, PointTarget, NormalT, Scalar >::setKSearch | ( | unsigned int | k | ) | [inline] |
Set the number of nearest neighbours to be considered in the target point cloud. By default, we use k = 10 nearest neighbors.
| [in] | k | the number of nearest neighbours to be considered |
Definition at line 162 of file correspondence_estimation_normal_shooting.h.
| void pcl::registration::CorrespondenceEstimationNormalShooting< PointSource, PointTarget, NormalT, Scalar >::setSourceNormals | ( | const NormalsConstPtr & | normals | ) | [inline] |
Set the normals computed on the source point cloud.
| [in] | normals | the normals computed for the source cloud |
Definition at line 129 of file correspondence_estimation_normal_shooting.h.
unsigned int pcl::registration::CorrespondenceEstimationNormalShooting< PointSource, PointTarget, NormalT, Scalar >::k_ [private] |
The number of neighbours to be considered in the target point cloud.
Definition at line 191 of file correspondence_estimation_normal_shooting.h.
NormalsConstPtr pcl::registration::CorrespondenceEstimationNormalShooting< PointSource, PointTarget, NormalT, Scalar >::source_normals_ [private] |
The normals computed at each point in the source cloud.
Definition at line 185 of file correspondence_estimation_normal_shooting.h.
NormalsPtr pcl::registration::CorrespondenceEstimationNormalShooting< PointSource, PointTarget, NormalT, Scalar >::source_normals_transformed_ [private] |
The normals computed at each point in the source cloud.
Definition at line 188 of file correspondence_estimation_normal_shooting.h.