Public Types | Public Member Functions | Protected Member Functions | Private Member Functions | Private Attributes
pcl::SpinImageEstimation< PointInT, PointNT, PointOutT > Class Template Reference

Estimates spin-image descriptors in the given input points. More...

#include <spin_image.h>

Inheritance diagram for pcl::SpinImageEstimation< PointInT, PointNT, PointOutT >:
Inheritance graph
[legend]

List of all members.

Public Types

typedef boost::shared_ptr
< const SpinImageEstimation
< PointInT, PointNT, PointOutT > > 
ConstPtr
typedef pcl::PointCloud< PointInT > PointCloudIn
typedef PointCloudIn::ConstPtr PointCloudInConstPtr
typedef PointCloudIn::Ptr PointCloudInPtr
typedef pcl::PointCloud< PointNT > PointCloudN
typedef PointCloudN::ConstPtr PointCloudNConstPtr
typedef PointCloudN::Ptr PointCloudNPtr
typedef Feature< PointInT,
PointOutT >::PointCloudOut 
PointCloudOut
typedef boost::shared_ptr
< SpinImageEstimation
< PointInT, PointNT, PointOutT > > 
Ptr

Public Member Functions

void setAngularDomain (bool is_angular=true)
 Sets/unsets flag for angular spin-image domain.
void setImageWidth (unsigned int bin_count)
 Sets spin-image resolution.
void setInputNormals (const PointCloudNConstPtr &normals)
 Provide a pointer to the input dataset that contains the point normals of the input XYZ dataset given by setInputCloud.
void setInputRotationAxes (const PointCloudNConstPtr &axes)
 Sets array of vectors as rotation axes for input points.
void setMinPointCountInNeighbourhood (unsigned int min_pts_neighb)
 Sets minimal points count for spin image computation.
void setRadialStructure (bool is_radial=true)
 Sets/unsets flag for radial spin-image structure.
void setRotationAxis (const PointNT &axis)
 Sets single vector a rotation axis for all input points.
void setSupportAngle (double support_angle_cos)
 Sets the maximum angle for the point normal to get to support region.
 SpinImageEstimation (unsigned int image_width=8, double support_angle_cos=0.0, unsigned int min_pts_neighb=0)
 Constructs empty spin image estimator.
void useNormalsAsRotationAxis ()
 Sets input normals as rotation axes (default setting).

Protected Member Functions

virtual void computeFeature (PointCloudOut &output)
 Estimate the Spin Image descriptors at a set of points given by setInputWithNormals() using the surface in setSearchSurfaceWithNormals() and the spatial locator.
Eigen::ArrayXXd computeSiForPoint (int index) const
 Computes a spin-image for the point of the scan.
virtual bool initCompute ()
 initializes computations specific to spin-image.

Private Member Functions

void computeFeatureEigen (pcl::PointCloud< Eigen::MatrixXf > &)
 Make the computeFeature (&Eigen::MatrixXf); inaccessible from outside the class.

Private Attributes

unsigned int image_width_
PointCloudNConstPtr input_normals_
bool is_angular_
bool is_radial_
unsigned int min_pts_neighb_
PointCloudNConstPtr rotation_axes_cloud_
PointNT rotation_axis_
double support_angle_cos_
bool use_custom_axes_cloud_
bool use_custom_axis_

Detailed Description

template<typename PointInT, typename PointNT, typename PointOutT>
class pcl::SpinImageEstimation< PointInT, PointNT, PointOutT >

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.

Attention:
The input normals given by setInputNormals have to match the input point cloud given by setInputCloud. This behavior is different than feature estimation methods that extend FeatureFromNormals, which match the normals with the search surface.

With the default paramters, pcl::Histogram<153> is a good choice for PointOutT. Of course the dimension of this descriptor must change to match the number of bins set by the parameters.

For further information please see:

The class also implements radial spin images and spin-images in angular domain (or both).

Author:
Roman Shapovalov, Alexander Velizhev

Definition at line 87 of file spin_image.h.


Member Typedef Documentation

template<typename PointInT, typename PointNT, typename PointOutT>
typedef boost::shared_ptr<const SpinImageEstimation<PointInT, PointNT, PointOutT> > pcl::SpinImageEstimation< PointInT, PointNT, PointOutT >::ConstPtr

Reimplemented from pcl::Feature< PointInT, PointOutT >.

Definition at line 110 of file spin_image.h.

template<typename PointInT, typename PointNT, typename PointOutT>
typedef pcl::PointCloud<PointInT> pcl::SpinImageEstimation< PointInT, PointNT, PointOutT >::PointCloudIn

Reimplemented from pcl::Feature< PointInT, PointOutT >.

Definition at line 105 of file spin_image.h.

template<typename PointInT, typename PointNT, typename PointOutT>
typedef PointCloudIn::ConstPtr pcl::SpinImageEstimation< PointInT, PointNT, PointOutT >::PointCloudInConstPtr

Reimplemented from pcl::Feature< PointInT, PointOutT >.

Definition at line 107 of file spin_image.h.

template<typename PointInT, typename PointNT, typename PointOutT>
typedef PointCloudIn::Ptr pcl::SpinImageEstimation< PointInT, PointNT, PointOutT >::PointCloudInPtr

Reimplemented from pcl::Feature< PointInT, PointOutT >.

Definition at line 106 of file spin_image.h.

template<typename PointInT, typename PointNT, typename PointOutT>
typedef pcl::PointCloud<PointNT> pcl::SpinImageEstimation< PointInT, PointNT, PointOutT >::PointCloudN

Definition at line 101 of file spin_image.h.

template<typename PointInT, typename PointNT, typename PointOutT>
typedef PointCloudN::ConstPtr pcl::SpinImageEstimation< PointInT, PointNT, PointOutT >::PointCloudNConstPtr

Definition at line 103 of file spin_image.h.

template<typename PointInT, typename PointNT, typename PointOutT>
typedef PointCloudN::Ptr pcl::SpinImageEstimation< PointInT, PointNT, PointOutT >::PointCloudNPtr

Definition at line 102 of file spin_image.h.

template<typename PointInT, typename PointNT, typename PointOutT>
typedef Feature<PointInT, PointOutT>::PointCloudOut pcl::SpinImageEstimation< PointInT, PointNT, PointOutT >::PointCloudOut

Reimplemented from pcl::Feature< PointInT, PointOutT >.

Definition at line 99 of file spin_image.h.

template<typename PointInT, typename PointNT, typename PointOutT>
typedef boost::shared_ptr<SpinImageEstimation<PointInT, PointNT, PointOutT> > pcl::SpinImageEstimation< PointInT, PointNT, PointOutT >::Ptr

Reimplemented from pcl::Feature< PointInT, PointOutT >.

Definition at line 109 of file spin_image.h.


Constructor & Destructor Documentation

template<typename PointInT , typename PointNT , typename PointOutT >
pcl::SpinImageEstimation< PointInT, PointNT, PointOutT >::SpinImageEstimation ( unsigned int  image_width = 8,
double  support_angle_cos = 0.0,
unsigned int  min_pts_neighb = 0 
)

Constructs empty spin image estimator.

Parameters:
[in]image_widthspin-image resolution, number of bins along one dimension
[in]support_angle_cosminimal 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_neighbmin number of points in the support to correctly estimate spin-image. If at some point the support contains less points, exception is thrown

Reimplemented in pcl::SpinImageEstimation< PointInT, PointNT, Eigen::MatrixXf >.

Definition at line 53 of file spin_image.hpp.


Member Function Documentation

template<typename PointInT , typename PointNT , typename PointOutT >
void pcl::SpinImageEstimation< PointInT, PointNT, PointOutT >::computeFeature ( PointCloudOut output) [protected, virtual]

Estimate the Spin Image descriptors at a set of points given by setInputWithNormals() using the surface in setSearchSurfaceWithNormals() and the spatial locator.

Parameters:
[out]outputthe resultant point cloud that contains the Spin Image feature estimates

Implements pcl::Feature< PointInT, PointOutT >.

Definition at line 323 of file spin_image.hpp.

template<typename PointInT, typename PointNT, typename PointOutT>
void pcl::SpinImageEstimation< PointInT, PointNT, PointOutT >::computeFeatureEigen ( pcl::PointCloud< Eigen::MatrixXf > &  ) [inline, private, virtual]

Make the computeFeature (&Eigen::MatrixXf); inaccessible from outside the class.

Parameters:
[out]outputthe output point cloud

Implements pcl::Feature< PointInT, PointOutT >.

Reimplemented in pcl::SpinImageEstimation< PointInT, PointNT, Eigen::MatrixXf >.

Definition at line 282 of file spin_image.h.

template<typename PointInT , typename PointNT , typename PointOutT >
Eigen::ArrayXXd pcl::SpinImageEstimation< PointInT, PointNT, PointOutT >::computeSiForPoint ( int  index) const [protected]

Computes a spin-image for the point of the scan.

Parameters:
[in]indexthe index of the reference point in the input cloud
Returns:
estimated spin-image (or its variant) as a matrix

Definition at line 68 of file spin_image.hpp.

template<typename PointInT , typename PointNT , typename PointOutT >
bool pcl::SpinImageEstimation< PointInT, PointNT, PointOutT >::initCompute ( ) [protected, virtual]

initializes computations specific to spin-image.

Returns:
true iff input data and initialization are correct

Reimplemented from pcl::Feature< PointInT, PointOutT >.

Definition at line 238 of file spin_image.hpp.

template<typename PointInT, typename PointNT, typename PointOutT>
void pcl::SpinImageEstimation< PointInT, PointNT, PointOutT >::setAngularDomain ( bool  is_angular = true) [inline]

Sets/unsets flag for angular spin-image domain.

Angular spin-image differs from the vanilla one in the way that not the points are collected in the bins but the angles between their normals and the normal to the reference point. For further information please see Endres, F., Plagemann, C., Stachniss, C., & Burgard, W. (2009). Unsupervised Discovery of Object Classes from Range Data using Latent Dirichlet Allocation. In Robotics: Science and Systems. Seattle, USA.

Parameters:
[in]is_angulartrue for angular domain, false for point domain

Definition at line 228 of file spin_image.h.

template<typename PointInT, typename PointNT, typename PointOutT>
void pcl::SpinImageEstimation< PointInT, PointNT, PointOutT >::setImageWidth ( unsigned int  bin_count) [inline]

Sets spin-image resolution.

Parameters:
[in]bin_countspin-image resolution, number of bins along one dimension

Definition at line 130 of file spin_image.h.

template<typename PointInT, typename PointNT, typename PointOutT>
void pcl::SpinImageEstimation< PointInT, PointNT, PointOutT >::setInputNormals ( const PointCloudNConstPtr normals) [inline]

Provide a pointer to the input dataset that contains the point normals of the input XYZ dataset given by setInputCloud.

Attention:
The input normals given by setInputNormals have to match the input point cloud given by setInputCloud. This behavior is different than feature estimation methods that extend FeatureFromNormals, which match the normals with the search surface.
Parameters:
[in]normalsthe const boost shared pointer to a PointCloud of normals. By convention, L2 norm of each normal should be 1.

Definition at line 175 of file spin_image.h.

template<typename PointInT, typename PointNT, typename PointOutT>
void pcl::SpinImageEstimation< PointInT, PointNT, PointOutT >::setInputRotationAxes ( const PointCloudNConstPtr axes) [inline]

Sets array of vectors as rotation axes for input points.

Useful e.g. when one wants to use tangents instead of normals as rotation axes

Parameters:
[in]axesunit-length vectors that serves as rotation axes for the corresponding input points' reference frames

Definition at line 200 of file spin_image.h.

template<typename PointInT, typename PointNT, typename PointOutT>
void pcl::SpinImageEstimation< PointInT, PointNT, PointOutT >::setMinPointCountInNeighbourhood ( unsigned int  min_pts_neighb) [inline]

Sets minimal points count for spin image computation.

Parameters:
[in]min_pts_neighbmin number of points in the support to correctly estimate spin-image. If at some point the support contains less points, exception is thrown

Definition at line 159 of file spin_image.h.

template<typename PointInT, typename PointNT, typename PointOutT>
void pcl::SpinImageEstimation< PointInT, PointNT, PointOutT >::setRadialStructure ( bool  is_radial = true) [inline]

Sets/unsets flag for radial spin-image structure.

Instead of rectangular coordinate system for reference frame polar coordinates are used. Binning is done depending on the distance and inclination angle from the reference point

Parameters:
[in]is_radialtrue for radial spin-image structure, false for rectangular

Definition at line 238 of file spin_image.h.

template<typename PointInT, typename PointNT, typename PointOutT>
void pcl::SpinImageEstimation< PointInT, PointNT, PointOutT >::setRotationAxis ( const PointNT &  axis) [inline]

Sets single vector a rotation axis for all input points.

It could be useful e.g. when the vertical axis is known.

Parameters:
[in]axisunit-length vector that serves as rotation axis for reference frame

Definition at line 186 of file spin_image.h.

template<typename PointInT, typename PointNT, typename PointOutT>
void pcl::SpinImageEstimation< PointInT, PointNT, PointOutT >::setSupportAngle ( double  support_angle_cos) [inline]

Sets the maximum angle for the point normal to get to support region.

Parameters:
[in]support_angle_cosminimal allowed cosine of the angle between the normals of input point and search surface point for the point to be retained in the support

Definition at line 142 of file spin_image.h.

template<typename PointInT, typename PointNT, typename PointOutT>
void pcl::SpinImageEstimation< PointInT, PointNT, PointOutT >::useNormalsAsRotationAxis ( ) [inline]

Sets input normals as rotation axes (default setting).

Definition at line 210 of file spin_image.h.


Member Data Documentation

template<typename PointInT, typename PointNT, typename PointOutT>
unsigned int pcl::SpinImageEstimation< PointInT, PointNT, PointOutT >::image_width_ [private]

Definition at line 274 of file spin_image.h.

template<typename PointInT, typename PointNT, typename PointOutT>
PointCloudNConstPtr pcl::SpinImageEstimation< PointInT, PointNT, PointOutT >::input_normals_ [private]

Definition at line 263 of file spin_image.h.

template<typename PointInT, typename PointNT, typename PointOutT>
bool pcl::SpinImageEstimation< PointInT, PointNT, PointOutT >::is_angular_ [private]

Definition at line 266 of file spin_image.h.

template<typename PointInT, typename PointNT, typename PointOutT>
bool pcl::SpinImageEstimation< PointInT, PointNT, PointOutT >::is_radial_ [private]

Definition at line 272 of file spin_image.h.

template<typename PointInT, typename PointNT, typename PointOutT>
unsigned int pcl::SpinImageEstimation< PointInT, PointNT, PointOutT >::min_pts_neighb_ [private]

Definition at line 276 of file spin_image.h.

template<typename PointInT, typename PointNT, typename PointOutT>
PointCloudNConstPtr pcl::SpinImageEstimation< PointInT, PointNT, PointOutT >::rotation_axes_cloud_ [private]

Definition at line 264 of file spin_image.h.

template<typename PointInT, typename PointNT, typename PointOutT>
PointNT pcl::SpinImageEstimation< PointInT, PointNT, PointOutT >::rotation_axis_ [private]

Definition at line 268 of file spin_image.h.

template<typename PointInT, typename PointNT, typename PointOutT>
double pcl::SpinImageEstimation< PointInT, PointNT, PointOutT >::support_angle_cos_ [private]

Definition at line 275 of file spin_image.h.

template<typename PointInT, typename PointNT, typename PointOutT>
bool pcl::SpinImageEstimation< PointInT, PointNT, PointOutT >::use_custom_axes_cloud_ [private]

Definition at line 270 of file spin_image.h.

template<typename PointInT, typename PointNT, typename PointOutT>
bool pcl::SpinImageEstimation< PointInT, PointNT, PointOutT >::use_custom_axis_ [private]

Definition at line 269 of file spin_image.h.


The documentation for this class was generated from the following files:


pcl
Author(s): Open Perception
autogenerated on Mon Oct 6 2014 03:20:13