PrincipalCurvaturesEstimation estimates the directions (eigenvectors) and magnitudes (eigenvalues) of principal surface curvatures for a given point cloud dataset containing points and normals. More...
#include <principal_curvatures.h>
Public Types | |
typedef pcl::PointCloud< PointInT > | PointCloudIn |
typedef Feature< PointInT, PointOutT >::PointCloudOut | PointCloudOut |
Public Member Functions | |
void | computePointPrincipalCurvatures (const pcl::PointCloud< PointNT > &normals, int p_idx, const std::vector< int > &indices, float &pcx, float &pcy, float &pcz, float &pc1, float &pc2) |
Perform Principal Components Analysis (PCA) on the point normals of a surface patch in the tangent plane of the given point normal, and return the principal curvature (eigenvector of the max eigenvalue), along with both the max (pc1) and min (pc2) eigenvalues. | |
PrincipalCurvaturesEstimation () | |
Empty constructor. | |
Protected Member Functions | |
void | computeFeature (PointCloudOut &output) |
Estimate the principal curvature (eigenvector of the max eigenvalue), along with both the max (pc1) and min (pc2) eigenvalues for all points given in <setInputCloud (), setIndices ()> using the surface in setSearchSurface () and the spatial locator in setSearchMethod () | |
Private Member Functions | |
void | computeFeatureEigen (pcl::PointCloud< Eigen::MatrixXf > &) |
Make the computeFeature (&Eigen::MatrixXf); inaccessible from outside the class. | |
Private Attributes | |
EIGEN_ALIGN16 Eigen::Matrix3f | covariance_matrix_ |
Placeholder for the 3x3 covariance matrix at each surface patch. | |
Eigen::Vector3f | demean_ |
Temporary point placeholder. | |
Eigen::Vector3f | eigenvalues_ |
eigenvalues placeholder for a covariance matrix. | |
Eigen::Vector3f | eigenvector_ |
SSE aligned eigenvectors placeholder for a covariance matrix. | |
std::vector< Eigen::Vector3f > | projected_normals_ |
A pointer to the input dataset that contains the point normals of the XYZ dataset. | |
Eigen::Vector3f | xyz_centroid_ |
SSE aligned placeholder for the XYZ centroid of a surface patch. |
PrincipalCurvaturesEstimation estimates the directions (eigenvectors) and magnitudes (eigenvalues) of principal surface curvatures for a given point cloud dataset containing points and normals.
The recommended PointOutT is pcl::PrincipalCurvatures.
Definition at line 61 of file principal_curvatures.h.
typedef pcl::PointCloud<PointInT> pcl::PrincipalCurvaturesEstimation< PointInT, PointNT, PointOutT >::PointCloudIn |
Reimplemented from pcl::FeatureFromNormals< PointInT, PointNT, PointOutT >.
Definition at line 74 of file principal_curvatures.h.
typedef Feature<PointInT, PointOutT>::PointCloudOut pcl::PrincipalCurvaturesEstimation< PointInT, PointNT, PointOutT >::PointCloudOut |
Reimplemented from pcl::FeatureFromNormals< PointInT, PointNT, PointOutT >.
Definition at line 73 of file principal_curvatures.h.
pcl::PrincipalCurvaturesEstimation< PointInT, PointNT, PointOutT >::PrincipalCurvaturesEstimation | ( | ) | [inline] |
Empty constructor.
Definition at line 77 of file principal_curvatures.h.
void pcl::PrincipalCurvaturesEstimation< PointInT, PointNT, PointOutT >::computeFeature | ( | PointCloudOut & | output | ) | [protected, virtual] |
Estimate the principal curvature (eigenvector of the max eigenvalue), along with both the max (pc1) and min (pc2) eigenvalues for all points given in <setInputCloud (), setIndices ()> using the surface in setSearchSurface () and the spatial locator in setSearchMethod ()
[out] | output | the resultant point cloud model dataset that contains the principal curvature estimates |
Implements pcl::Feature< PointInT, PointOutT >.
Definition at line 113 of file principal_curvatures.hpp.
void pcl::PrincipalCurvaturesEstimation< PointInT, PointNT, PointOutT >::computeFeatureEigen | ( | pcl::PointCloud< Eigen::MatrixXf > & | ) | [inline, private, virtual] |
Make the computeFeature (&Eigen::MatrixXf); inaccessible from outside the class.
[out] | output | the output point cloud |
Implements pcl::Feature< PointInT, PointOutT >.
Reimplemented in pcl::PrincipalCurvaturesEstimation< PointInT, PointNT, Eigen::MatrixXf >.
Definition at line 137 of file principal_curvatures.h.
void pcl::PrincipalCurvaturesEstimation< PointInT, PointNT, PointOutT >::computePointPrincipalCurvatures | ( | const pcl::PointCloud< PointNT > & | normals, |
int | p_idx, | ||
const std::vector< int > & | indices, | ||
float & | pcx, | ||
float & | pcy, | ||
float & | pcz, | ||
float & | pc1, | ||
float & | pc2 | ||
) |
Perform Principal Components Analysis (PCA) on the point normals of a surface patch in the tangent plane of the given point normal, and return the principal curvature (eigenvector of the max eigenvalue), along with both the max (pc1) and min (pc2) eigenvalues.
[in] | normals | the point cloud normals |
[in] | p_idx | the query point at which the least-squares plane was estimated |
[in] | indices | the point cloud indices that need to be used |
[out] | pcx | the principal curvature X direction |
[out] | pcy | the principal curvature Y direction |
[out] | pcz | the principal curvature Z direction |
[out] | pc1 | the max eigenvalue of curvature |
[out] | pc2 | the min eigenvalue of curvature |
Definition at line 47 of file principal_curvatures.hpp.
EIGEN_ALIGN16 Eigen::Matrix3f pcl::PrincipalCurvaturesEstimation< PointInT, PointNT, PointOutT >::covariance_matrix_ [private] |
Placeholder for the 3x3 covariance matrix at each surface patch.
Definition at line 126 of file principal_curvatures.h.
Eigen::Vector3f pcl::PrincipalCurvaturesEstimation< PointInT, PointNT, PointOutT >::demean_ [private] |
Temporary point placeholder.
Definition at line 123 of file principal_curvatures.h.
Eigen::Vector3f pcl::PrincipalCurvaturesEstimation< PointInT, PointNT, PointOutT >::eigenvalues_ [private] |
eigenvalues placeholder for a covariance matrix.
Definition at line 131 of file principal_curvatures.h.
Eigen::Vector3f pcl::PrincipalCurvaturesEstimation< PointInT, PointNT, PointOutT >::eigenvector_ [private] |
SSE aligned eigenvectors placeholder for a covariance matrix.
Definition at line 129 of file principal_curvatures.h.
std::vector<Eigen::Vector3f> pcl::PrincipalCurvaturesEstimation< PointInT, PointNT, PointOutT >::projected_normals_ [private] |
A pointer to the input dataset that contains the point normals of the XYZ dataset.
Definition at line 117 of file principal_curvatures.h.
Eigen::Vector3f pcl::PrincipalCurvaturesEstimation< PointInT, PointNT, PointOutT >::xyz_centroid_ [private] |
SSE aligned placeholder for the XYZ centroid of a surface patch.
Definition at line 120 of file principal_curvatures.h.