IntensityGradientEstimation estimates the intensity gradient for a point cloud that contains position and intensity values. The intensity gradient at a given point will be a vector orthogonal to the surface normal and pointing in the direction of the greatest increase in local intensity; the vector's magnitude indicates the rate of intensity change. More...
#include <intensity_gradient.h>
Public Types | |
typedef Feature< PointInT, PointOutT >::PointCloudOut | PointCloudOut |
Public Member Functions | |
IntensityGradientEstimation () | |
Empty constructor. | |
Protected Member Functions | |
void | computeFeature (PointCloudOut &output) |
Estimate the intensity gradients for a set of points given in <setInputCloud (), setIndices ()> using the surface in setSearchSurface () and the spatial locator in setSearchMethod (). | |
Private Member Functions | |
void | computePointIntensityGradient (const pcl::PointCloud< PointInT > &cloud, const std::vector< int > &indices, const Eigen::Vector3f &point, const Eigen::Vector3f &normal, Eigen::Vector3f &gradient) |
Estimate the intensity gradient around a given point based on its spatial neighborhood of points. |
IntensityGradientEstimation estimates the intensity gradient for a point cloud that contains position and intensity values. The intensity gradient at a given point will be a vector orthogonal to the surface normal and pointing in the direction of the greatest increase in local intensity; the vector's magnitude indicates the rate of intensity change.
Definition at line 51 of file intensity_gradient.h.
typedef Feature<PointInT, PointOutT>::PointCloudOut pcl::IntensityGradientEstimation< PointInT, PointNT, PointOutT >::PointCloudOut |
Reimplemented from pcl::FeatureFromNormals< PointInT, PointNT, PointOutT >.
Definition at line 62 of file intensity_gradient.h.
pcl::IntensityGradientEstimation< PointInT, PointNT, PointOutT >::IntensityGradientEstimation | ( | ) | [inline] |
Empty constructor.
Definition at line 65 of file intensity_gradient.h.
void pcl::IntensityGradientEstimation< PointInT, PointNT, PointOutT >::computeFeature | ( | PointCloudOut & | output | ) | [inline, protected, virtual] |
Estimate the intensity gradients for a set of points given in <setInputCloud (), setIndices ()> using the surface in setSearchSurface () and the spatial locator in setSearchMethod ().
output | the resultant point cloud that contains the intensity gradient vectors |
Implements pcl::Feature< PointInT, PointOutT >.
Definition at line 44 of file intensity_gradient.hpp.
void pcl::IntensityGradientEstimation< PointInT, PointNT, PointOutT >::computePointIntensityGradient | ( | const pcl::PointCloud< PointInT > & | cloud, | |
const std::vector< int > & | indices, | |||
const Eigen::Vector3f & | point, | |||
const Eigen::Vector3f & | normal, | |||
Eigen::Vector3f & | gradient | |||
) | [inline, private] |
Estimate the intensity gradient around a given point based on its spatial neighborhood of points.
cloud | a point cloud dataset containing XYZI coordinates (Cartesian coordinates + intensity) | |
indices | the indices of the neighoring points in the dataset | |
point | the 3D Cartesian coordinates of the point at which to estimate the gradient | |
normal | the 3D surface normal of the given point | |
gradient | the resultant 3D gradient vector |
Definition at line 77 of file intensity_gradient.hpp.