NormalEstimation estimates local surface properties at each 3D point, such as surface normals and curvatures. More...
#include <normal_3d.h>
Public Types | |
typedef Feature< PointInT, PointOutT >::PointCloudOut | PointCloudOut |
Public Member Functions | |
void | computePointNormal (const pcl::PointCloud< PointInT > &cloud, const std::vector< int > &indices, float &nx, float &ny, float &nz, float &curvature) |
Compute the Least-Squares plane fit for a given set of points, using their indices, and return the estimated plane parameters together with the surface curvature. | |
void | computePointNormal (const pcl::PointCloud< PointInT > &cloud, const std::vector< int > &indices, Eigen::Vector4f &plane_parameters, float &curvature) |
Compute the Least-Squares plane fit for a given set of points, using their indices, and return the estimated plane parameters together with the surface curvature. | |
void | getViewPoint (float &vpx, float &vpy, float &vpz) |
Get the viewpoint. | |
NormalEstimation () | |
Empty constructor. | |
void | setViewPoint (float vpx, float vpy, float vpz) |
Set the viewpoint. | |
Protected Member Functions | |
void | computeFeature (PointCloudOut &output) |
Estimate normals for all points given in <setInputCloud (), setIndices ()> using the surface in setSearchSurface () and the spatial locator in setSearchMethod (). | |
Private Attributes | |
EIGEN_ALIGN16 Eigen::Matrix3f | covariance_matrix_ |
Placeholder for the 3x3 covariance matrix at each surface patch. | |
float | vpx_ |
Values describing the viewpoint ("pinhole" camera model assumed). For per point viewpoints, inherit from NormalEstimation and provide your own computeFeature (). By default, the viewpoint is set to 0,0,0. | |
float | vpy_ |
float | vpz_ |
Eigen::Vector4f | xyz_centroid_ |
16-bytes aligned placeholder for the XYZ centroid of a surface patch. |
NormalEstimation estimates local surface properties at each 3D point, such as surface normals and curvatures.
Definition at line 180 of file normal_3d.h.
typedef Feature<PointInT, PointOutT>::PointCloudOut pcl::NormalEstimation< PointInT, PointOutT >::PointCloudOut |
Reimplemented from pcl::Feature< PointInT, PointOutT >.
Reimplemented in pcl::NormalEstimationOMP< PointInT, PointOutT >, and pcl::NormalEstimationTBB< PointInT, PointOutT >.
Definition at line 191 of file normal_3d.h.
pcl::NormalEstimation< PointInT, PointOutT >::NormalEstimation | ( | ) | [inline] |
Empty constructor.
Definition at line 194 of file normal_3d.h.
void pcl::NormalEstimation< PointInT, PointOutT >::computeFeature | ( | PointCloudOut & | output | ) | [inline, protected, virtual] |
Estimate normals for all points given in <setInputCloud (), setIndices ()> using the surface in setSearchSurface () and the spatial locator in setSearchMethod ().
output | the resultant point cloud model dataset that contains surface normals and curvatures |
Implements pcl::Feature< PointInT, PointOutT >.
Reimplemented in pcl::NormalEstimationOMP< PointInT, PointOutT >, and pcl::NormalEstimationTBB< PointInT, PointOutT >.
Definition at line 45 of file normal_3d.hpp.
void pcl::NormalEstimation< PointInT, PointOutT >::computePointNormal | ( | const pcl::PointCloud< PointInT > & | cloud, | |
const std::vector< int > & | indices, | |||
float & | nx, | |||
float & | ny, | |||
float & | nz, | |||
float & | curvature | |||
) | [inline] |
Compute the Least-Squares plane fit for a given set of points, using their indices, and return the estimated plane parameters together with the surface curvature.
cloud | the input point cloud | |
indices | the point cloud indices that need to be used | |
nx | the resultant X component of the plane normal | |
ny | the resultant Y component of the plane normal | |
nz | the resultant Z component of the plane normal | |
curvature | the estimated surface curvature as a measure of
|
Definition at line 241 of file normal_3d.h.
void pcl::NormalEstimation< PointInT, PointOutT >::computePointNormal | ( | const pcl::PointCloud< PointInT > & | cloud, | |
const std::vector< int > & | indices, | |||
Eigen::Vector4f & | plane_parameters, | |||
float & | curvature | |||
) | [inline] |
Compute the Least-Squares plane fit for a given set of points, using their indices, and return the estimated plane parameters together with the surface curvature.
cloud | the input point cloud | |
indices | the point cloud indices that need to be used | |
plane_parameters | the plane parameters as: a, b, c, d (ax + by + cz + d = 0) | |
curvature | the estimated surface curvature as a measure of
|
Definition at line 210 of file normal_3d.h.
void pcl::NormalEstimation< PointInT, PointOutT >::getViewPoint | ( | float & | vpx, | |
float & | vpy, | |||
float & | vpz | |||
) | [inline] |
Get the viewpoint.
Definition at line 273 of file normal_3d.h.
void pcl::NormalEstimation< PointInT, PointOutT >::setViewPoint | ( | float | vpx, | |
float | vpy, | |||
float | vpz | |||
) | [inline] |
Set the viewpoint.
vpx | the X coordinate of the viewpoint | |
vpy | the Y coordinate of the viewpoint | |
vpz | the Z coordinate of the viewpoint |
Definition at line 264 of file normal_3d.h.
EIGEN_ALIGN16 Eigen::Matrix3f pcl::NormalEstimation< PointInT, PointOutT >::covariance_matrix_ [private] |
Placeholder for the 3x3 covariance matrix at each surface patch.
Definition at line 294 of file normal_3d.h.
float pcl::NormalEstimation< PointInT, PointOutT >::vpx_ [private] |
Values describing the viewpoint ("pinhole" camera model assumed). For per point viewpoints, inherit from NormalEstimation and provide your own computeFeature (). By default, the viewpoint is set to 0,0,0.
Definition at line 291 of file normal_3d.h.
float pcl::NormalEstimation< PointInT, PointOutT >::vpy_ [private] |
Definition at line 291 of file normal_3d.h.
float pcl::NormalEstimation< PointInT, PointOutT >::vpz_ [private] |
Definition at line 291 of file normal_3d.h.
Eigen::Vector4f pcl::NormalEstimation< PointInT, PointOutT >::xyz_centroid_ [private] |
16-bytes aligned placeholder for the XYZ centroid of a surface patch.
Definition at line 297 of file normal_3d.h.