Estimates spin-image descriptors in the given input points. More...
#include <spin_image.h>
Public Member Functions | |
SpinImageEstimation (unsigned int image_width=8, double support_angle_cos=0.0, unsigned int min_pts_neighb=0) | |
Constructs empty spin image estimator. | |
Private Member Functions | |
void | compute (pcl::PointCloud< pcl::Normal > &) |
Make the compute (&PointCloudOut); inaccessible from outside the class. | |
virtual void | computeFeatureEigen (pcl::PointCloud< Eigen::MatrixXf > &output) |
Estimate the Spin Image descriptors at a set of points given by setInputWithNormals() using the surface in setSearchSurfaceWithNormals() and the spatial locator. |
Estimates spin-image descriptors in the given input points.
This class represents spin image descriptor. Spin image is a histogram of point locations summed along the bins of the image. A 2D accumulator indexed by a and b is created. Next, the coordinates (a, b) are computed for a vertex in the surface mesh that is within the support of the spin image (explained below). The bin indexed by (a, b) in the accumulator is then incremented; bilinear interpolation is used to smooth the contribution of the vertex. This procedure is repeated for all vertices within the support of the spin image. The resulting accumulator can be thought of as an image; dark areas in the image correspond to bins that contain many projected points. As long as the size of the bins in the accumulator is greater than the median distance between vertices in the mesh (the definition of mesh resolution), the position of individual vertices will be averaged out during spin image generation.
For further information please see:
The class also implements radial spin images and spin-images in angular domain (or both).
Definition at line 316 of file spin_image.h.
pcl::SpinImageEstimation< PointInT, PointNT, Eigen::MatrixXf >::SpinImageEstimation | ( | unsigned int | image_width = 8 , |
double | support_angle_cos = 0.0 , |
||
unsigned int | min_pts_neighb = 0 |
||
) | [inline] |
Constructs empty spin image estimator.
[in] | image_width | spin-image resolution, number of bins along one dimension |
[in] | support_angle_cos | minimal allowed cosine of the angle between the normals of input point and search surface point for the point to be retained in the support |
[in] | min_pts_neighb | min number of points in the support to correctly estimate spin-image. If at some point the support contains less points, exception is thrown |
Reimplemented from pcl::SpinImageEstimation< PointInT, PointNT, pcl::Histogram< 153 > >.
Definition at line 335 of file spin_image.h.
void pcl::SpinImageEstimation< PointInT, PointNT, Eigen::MatrixXf >::compute | ( | pcl::PointCloud< pcl::Normal > & | ) | [inline, private] |
Make the compute (&PointCloudOut); inaccessible from outside the class.
[out] | output | the output point cloud |
Definition at line 352 of file spin_image.h.
void pcl::SpinImageEstimation< PointInT, PointNT, Eigen::MatrixXf >::computeFeatureEigen | ( | pcl::PointCloud< Eigen::MatrixXf > & | output | ) | [private, virtual] |
Estimate the Spin Image descriptors at a set of points given by setInputWithNormals() using the surface in setSearchSurfaceWithNormals() and the spatial locator.
[out] | output | the resultant point cloud that contains the Spin Image feature estimates |
Reimplemented from pcl::SpinImageEstimation< PointInT, PointNT, pcl::Histogram< 153 > >.
Definition at line 342 of file spin_image.hpp.