NormalEstimation estimates local surface properties (surface normals and curvatures)at each 3D point. If PointOutT is specified as pcl::Normal, the normal is stored in the first 3 components (0-2), and the curvature is stored in component 3. More...
#include <normal_3d.h>
Public Types | |
typedef Feature< PointInT, PointOutT > ::PointCloudConstPtr | PointCloudConstPtr |
typedef Feature< PointInT, PointOutT >::PointCloudOut | PointCloudOut |
Public Member Functions | |
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 | 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 | getViewPoint (float &vpx, float &vpy, float &vpz) |
Get the viewpoint. | |
NormalEstimation () | |
Empty constructor. | |
virtual void | setInputCloud (const PointCloudConstPtr &cloud) |
Provide a pointer to the input dataset. | |
void | setViewPoint (float vpx, float vpy, float vpz) |
Set the viewpoint. | |
void | useSensorOriginAsViewPoint () |
sets whether the sensor origin or a user given viewpoint should be used. After this method, the normal estimation method uses the sensor origin of the input cloud. to use a user defined view point, use the method setViewPoint | |
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 () | |
Protected Attributes | |
EIGEN_ALIGN16 Eigen::Matrix3f | covariance_matrix_ |
Placeholder for the 3x3 covariance matrix at each surface patch. | |
bool | use_sensor_origin_ |
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. | |
Private Member Functions | |
void | computeFeatureEigen (pcl::PointCloud< Eigen::MatrixXf > &) |
Make the computeFeature (&Eigen::MatrixXf); inaccessible from outside the class. |
NormalEstimation estimates local surface properties (surface normals and curvatures)at each 3D point. If PointOutT is specified as pcl::Normal, the normal is stored in the first 3 components (0-2), and the curvature is stored in component 3.
Definition at line 193 of file normal_3d.h.
typedef Feature<PointInT, PointOutT>::PointCloudConstPtr pcl::NormalEstimation< PointInT, PointOutT >::PointCloudConstPtr |
Reimplemented from pcl::PCLBase< PointInT >.
Definition at line 206 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 >, pcl::NormalEstimationOMP< PointInT, pcl::Normal >, and pcl::NormalEstimationOMP< PointType, pcl::Normal >.
Definition at line 205 of file normal_3d.h.
pcl::NormalEstimation< PointInT, PointOutT >::NormalEstimation | ( | ) | [inline] |
Empty constructor.
Definition at line 209 of file normal_3d.h.
void pcl::NormalEstimation< PointInT, PointOutT >::computeFeature | ( | PointCloudOut & | output | ) | [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 >, pcl::NormalEstimationOMP< PointInT, pcl::Normal >, and pcl::NormalEstimationOMP< PointType, pcl::Normal >.
Definition at line 47 of file normal_3d.hpp.
void pcl::NormalEstimation< PointInT, 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::NormalEstimation< PointInT, Eigen::MatrixXf >, pcl::NormalEstimationOMP< PointInT, Eigen::MatrixXf >, pcl::NormalEstimationOMP< PointInT, PointOutT >, pcl::NormalEstimationOMP< PointInT, pcl::Normal >, and pcl::NormalEstimationOMP< PointType, pcl::Normal >.
Definition at line 363 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 231 of file normal_3d.h.
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 257 of file normal_3d.h.
void pcl::NormalEstimation< PointInT, PointOutT >::getViewPoint | ( | float & | vpx, |
float & | vpy, | ||
float & | vpz | ||
) | [inline] |
Get the viewpoint.
[out] | vpx | x-coordinate of the view point |
[out] | vpy | y-coordinate of the view point |
[out] | vpz | z-coordinate of the view point |
Definition at line 307 of file normal_3d.h.
virtual void pcl::NormalEstimation< PointInT, PointOutT >::setInputCloud | ( | const PointCloudConstPtr & | cloud | ) | [inline, virtual] |
Provide a pointer to the input dataset.
cloud | the const boost shared pointer to a PointCloud message |
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 290 of file normal_3d.h.
void pcl::NormalEstimation< PointInT, PointOutT >::useSensorOriginAsViewPoint | ( | ) | [inline] |
sets whether the sensor origin or a user given viewpoint should be used. After this method, the normal estimation method uses the sensor origin of the input cloud. to use a user defined view point, use the method setViewPoint
Definition at line 319 of file normal_3d.h.
EIGEN_ALIGN16 Eigen::Matrix3f pcl::NormalEstimation< PointInT, PointOutT >::covariance_matrix_ [protected] |
Placeholder for the 3x3 covariance matrix at each surface patch.
Definition at line 350 of file normal_3d.h.
bool pcl::NormalEstimation< PointInT, PointOutT >::use_sensor_origin_ [protected] |
whether the sensor origin of the input cloud or a user given viewpoint should be used.
Definition at line 356 of file normal_3d.h.
float pcl::NormalEstimation< PointInT, PointOutT >::vpx_ [protected] |
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 347 of file normal_3d.h.
float pcl::NormalEstimation< PointInT, PointOutT >::vpy_ [protected] |
Definition at line 347 of file normal_3d.h.
float pcl::NormalEstimation< PointInT, PointOutT >::vpz_ [protected] |
Definition at line 347 of file normal_3d.h.
Eigen::Vector4f pcl::NormalEstimation< PointInT, PointOutT >::xyz_centroid_ [protected] |
16-bytes aligned placeholder for the XYZ centroid of a surface patch.
Definition at line 353 of file normal_3d.h.