#include <icp_correspondences_check.h>

Public Member Functions | |
| void | estimateRigidTransformationSVD (const PointCloudSource &cloud_src, const PointCloudTarget &cloud_tgt, Eigen::Matrix4f &transformation_matrix) |
| Estimate a rigid rotation transformation between a source and a target point cloud using SVD. | |
| IterativeClosestPointCorrespondencesCheck () | |
| Empty constructor. | |
| IterativeClosestPointCorrespondencesCheck (double radius, int max_nn, double epsilon_z, double epsilon_curvature, bool curvature_check) | |
| Parameterized constructor. | |
| void | setParameters (double radius, int max_nn, double epsilon_z, double epsilon_curvature, bool curvature_check, std::string field) |
| A simple method to set the parameters. | |
| virtual | ~IterativeClosestPointCorrespondencesCheck () |
| Empty destructor. | |
Protected Member Functions | |
| virtual void | computeTransformation (PointCloudSource &output) |
| Rigid transformation computation method. | |
Private Types | |
| typedef RegistrationCorrespondencesCheck < PointSource, PointTarget > ::PointCloudSource | PointCloudSource |
| typedef PointCloudSource::ConstPtr | PointCloudSourceConstPtr |
| typedef PointCloudSource::Ptr | PointCloudSourcePtr |
| typedef RegistrationCorrespondencesCheck < PointSource, PointTarget > ::PointCloudTarget | PointCloudTarget |
| typedef PointIndices::ConstPtr | PointIndicesConstPtr |
| typedef PointIndices::Ptr | PointIndicesPtr |
Private Attributes | |
| bool | curvature_check_ |
| time_t | end |
| double | epsilon_curvature_ |
| double | epsilon_z_ |
| std::string | field_ |
| int | max_nn_ |
| double | radius_ |
| time_t | start |
Definition at line 46 of file icp_correspondences_check.h.
typedef RegistrationCorrespondencesCheck<PointSource, PointTarget>::PointCloudSource pcl::IterativeClosestPointCorrespondencesCheck< PointSource, PointTarget >::PointCloudSource [private] |
Reimplemented from pcl::RegistrationCorrespondencesCheck< PointSource, PointTarget >.
Definition at line 61 of file icp_correspondences_check.h.
typedef PointCloudSource::ConstPtr pcl::IterativeClosestPointCorrespondencesCheck< PointSource, PointTarget >::PointCloudSourceConstPtr [private] |
Reimplemented from pcl::RegistrationCorrespondencesCheck< PointSource, PointTarget >.
Definition at line 63 of file icp_correspondences_check.h.
typedef PointCloudSource::Ptr pcl::IterativeClosestPointCorrespondencesCheck< PointSource, PointTarget >::PointCloudSourcePtr [private] |
Reimplemented from pcl::RegistrationCorrespondencesCheck< PointSource, PointTarget >.
Definition at line 62 of file icp_correspondences_check.h.
typedef RegistrationCorrespondencesCheck<PointSource, PointTarget>::PointCloudTarget pcl::IterativeClosestPointCorrespondencesCheck< PointSource, PointTarget >::PointCloudTarget [private] |
Reimplemented from pcl::RegistrationCorrespondencesCheck< PointSource, PointTarget >.
Definition at line 65 of file icp_correspondences_check.h.
typedef PointIndices::ConstPtr pcl::IterativeClosestPointCorrespondencesCheck< PointSource, PointTarget >::PointIndicesConstPtr [private] |
Reimplemented from pcl::PCLBase< PointSource >.
Definition at line 68 of file icp_correspondences_check.h.
typedef PointIndices::Ptr pcl::IterativeClosestPointCorrespondencesCheck< PointSource, PointTarget >::PointIndicesPtr [private] |
Reimplemented from pcl::PCLBase< PointSource >.
Definition at line 67 of file icp_correspondences_check.h.
| pcl::IterativeClosestPointCorrespondencesCheck< PointSource, PointTarget >::IterativeClosestPointCorrespondencesCheck | ( | ) | [inline] |
Empty constructor.
Definition at line 79 of file icp_correspondences_check.h.
| pcl::IterativeClosestPointCorrespondencesCheck< PointSource, PointTarget >::IterativeClosestPointCorrespondencesCheck | ( | double | radius, |
| int | max_nn, | ||
| double | epsilon_z, | ||
| double | epsilon_curvature, | ||
| bool | curvature_check | ||
| ) | [inline] |
Parameterized constructor.
Definition at line 81 of file icp_correspondences_check.h.
| virtual pcl::IterativeClosestPointCorrespondencesCheck< PointSource, PointTarget >::~IterativeClosestPointCorrespondencesCheck | ( | ) | [inline, virtual] |
Empty destructor.
Definition at line 90 of file icp_correspondences_check.h.
| virtual void pcl::IterativeClosestPointCorrespondencesCheck< PointSource, PointTarget >::computeTransformation | ( | PointCloudSource & | output | ) | [inline, protected, virtual] |
Rigid transformation computation method.
| output | the transformed input point cloud dataset using the rigid transformation found |
Implements pcl::RegistrationCorrespondencesCheck< PointSource, PointTarget >.
Definition at line 98 of file icp_correspondences_check.h.
| void pcl::IterativeClosestPointCorrespondencesCheck< PointSource, PointTarget >::estimateRigidTransformationSVD | ( | const PointCloudSource & | cloud_src, |
| const PointCloudTarget & | cloud_tgt, | ||
| Eigen::Matrix4f & | transformation_matrix | ||
| ) | [inline] |
Estimate a rigid rotation transformation between a source and a target point cloud using SVD.
| cloud_src | the source point cloud dataset |
| cloud_tgt | the target point cloud dataset |
| transformation_matrix | the resultant transformation matrix |
Definition at line 264 of file icp_correspondences_check.h.
| void pcl::IterativeClosestPointCorrespondencesCheck< PointSource, PointTarget >::setParameters | ( | double | radius, |
| int | max_nn, | ||
| double | epsilon_z, | ||
| double | epsilon_curvature, | ||
| bool | curvature_check, | ||
| std::string | field | ||
| ) | [inline] |
A simple method to set the parameters.
Definition at line 331 of file icp_correspondences_check.h.
bool pcl::IterativeClosestPointCorrespondencesCheck< PointSource, PointTarget >::curvature_check_ [private] |
Definition at line 72 of file icp_correspondences_check.h.
time_t pcl::IterativeClosestPointCorrespondencesCheck< PointSource, PointTarget >::end [private] |
Definition at line 73 of file icp_correspondences_check.h.
double pcl::IterativeClosestPointCorrespondencesCheck< PointSource, PointTarget >::epsilon_curvature_ [private] |
Definition at line 70 of file icp_correspondences_check.h.
double pcl::IterativeClosestPointCorrespondencesCheck< PointSource, PointTarget >::epsilon_z_ [private] |
Definition at line 70 of file icp_correspondences_check.h.
std::string pcl::IterativeClosestPointCorrespondencesCheck< PointSource, PointTarget >::field_ [private] |
Definition at line 74 of file icp_correspondences_check.h.
int pcl::IterativeClosestPointCorrespondencesCheck< PointSource, PointTarget >::max_nn_ [private] |
Definition at line 71 of file icp_correspondences_check.h.
double pcl::IterativeClosestPointCorrespondencesCheck< PointSource, PointTarget >::radius_ [private] |
Definition at line 70 of file icp_correspondences_check.h.
time_t pcl::IterativeClosestPointCorrespondencesCheck< PointSource, PointTarget >::start [private] |
Definition at line 73 of file icp_correspondences_check.h.