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

IntensitySpinEstimation estimates the intensity-domain spin image descriptors for a given point cloud dataset containing points and intensity. For more information about the intensity-domain spin image descriptor, see: More...

#include <intensity_spin.h>

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

List of all members.

Public Types

typedef pcl::PointCloud< PointInT > PointCloudIn
typedef Feature< PointInT,
PointOutT >::PointCloudOut 
PointCloudOut

Public Member Functions

void computeFeature (PointCloudOut &output)
 Estimate the intensity-domain descriptors at a set of points given by <setInputCloud (), setIndices ()> using the surface in setSearchSurface (), and the spatial locator in setSearchMethod ().
void computeIntensitySpinImage (const PointCloudIn &cloud, float radius, float sigma, int k, const std::vector< int > &indices, const std::vector< float > &squared_distances, Eigen::MatrixXf &intensity_spin_image)
 Estimate the intensity-domain spin image descriptor for a given point based on its spatial neighborhood of 3D points and their intensities.
int getNrDistanceBins ()
 Returns the number of bins in the distance dimension of the spin image.
int getNrIntensityBins ()
 Returns the number of bins in the intensity dimension of the spin image.
float getSmoothingBandwith ()
 Returns the standard deviation of the Gaussian smoothing kernel used to construct the spin images.
 IntensitySpinEstimation ()
 Empty constructor.
void setNrDistanceBins (size_t nr_distance_bins)
 Set the number of bins to use in the distance dimension of the spin image.
void setNrIntensityBins (size_t nr_intensity_bins)
 Set the number of bins to use in the intensity dimension of the spin image.
void setSmoothingBandwith (float sigma)
 Set the standard deviation of the Gaussian smoothing kernel to use when constructing the spin images.

Public Attributes

int nr_distance_bins_
 The number of distance bins in the descriptor.
int nr_intensity_bins_
 The number of intensity bins in the descriptor.
float sigma_
 The standard deviation of the Gaussian smoothing kernel used to construct the spin images.

Private Member Functions

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

Detailed Description

template<typename PointInT, typename PointOutT>
class pcl::IntensitySpinEstimation< PointInT, PointOutT >

IntensitySpinEstimation estimates the intensity-domain spin image descriptors for a given point cloud dataset containing points and intensity. For more information about the intensity-domain spin image descriptor, see:

Svetlana Lazebnik, Cordelia Schmid, and Jean Ponce. A sparse texture representation using local affine regions. In IEEE Transactions on Pattern Analysis and Machine Intelligence, volume 27, pages 1265-1278, August 2005.

Author:
Michael Dixon

Definition at line 57 of file intensity_spin.h.


Member Typedef Documentation

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

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

Definition at line 70 of file intensity_spin.h.

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

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

Definition at line 71 of file intensity_spin.h.


Constructor & Destructor Documentation

template<typename PointInT, typename PointOutT>
pcl::IntensitySpinEstimation< PointInT, PointOutT >::IntensitySpinEstimation ( ) [inline]

Empty constructor.

Definition at line 74 of file intensity_spin.h.


Member Function Documentation

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

Estimate the intensity-domain descriptors at a set of points given by <setInputCloud (), setIndices ()> using the surface in setSearchSurface (), and the spatial locator in setSearchMethod ().

Parameters:
[out]outputthe resultant point cloud model dataset that contains the intensity-domain spin image features

Implements pcl::Feature< PointInT, PointOutT >.

Definition at line 109 of file intensity_spin.hpp.

template<typename PointInT, typename PointOutT>
void pcl::IntensitySpinEstimation< PointInT, 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::IntensitySpinEstimation< PointInT, Eigen::MatrixXf >.

Definition at line 148 of file intensity_spin.h.

template<typename PointInT , typename PointOutT >
void pcl::IntensitySpinEstimation< PointInT, PointOutT >::computeIntensitySpinImage ( const PointCloudIn cloud,
float  radius,
float  sigma,
int  k,
const std::vector< int > &  indices,
const std::vector< float > &  squared_distances,
Eigen::MatrixXf &  intensity_spin_image 
)

Estimate the intensity-domain spin image descriptor for a given point based on its spatial neighborhood of 3D points and their intensities.

Parameters:
[in]cloudthe dataset containing the Cartesian coordinates and intensity values of the points
[in]radiusthe radius of the feature
[in]sigmathe standard deviation of the Gaussian smoothing kernel to use during the soft histogram update
[in]kthe number of neighbors to use from indices and squared_distances
[in]indicesthe indices of the points that comprise the query point's neighborhood
[in]squared_distancesthe squared distances from the query point to each point in the neighborhood
[out]intensity_spin_imagethe resultant intensity-domain spin image descriptor

Definition at line 47 of file intensity_spin.hpp.

template<typename PointInT, typename PointOutT>
int pcl::IntensitySpinEstimation< PointInT, PointOutT >::getNrDistanceBins ( ) [inline]

Returns the number of bins in the distance dimension of the spin image.

Definition at line 104 of file intensity_spin.h.

template<typename PointInT, typename PointOutT>
int pcl::IntensitySpinEstimation< PointInT, PointOutT >::getNrIntensityBins ( ) [inline]

Returns the number of bins in the intensity dimension of the spin image.

Definition at line 114 of file intensity_spin.h.

template<typename PointInT, typename PointOutT>
float pcl::IntensitySpinEstimation< PointInT, PointOutT >::getSmoothingBandwith ( ) [inline]

Returns the standard deviation of the Gaussian smoothing kernel used to construct the spin images.

Definition at line 124 of file intensity_spin.h.

template<typename PointInT, typename PointOutT>
void pcl::IntensitySpinEstimation< PointInT, PointOutT >::setNrDistanceBins ( size_t  nr_distance_bins) [inline]

Set the number of bins to use in the distance dimension of the spin image.

Parameters:
[in]nr_distance_binsthe number of bins to use in the distance dimension of the spin image

Definition at line 100 of file intensity_spin.h.

template<typename PointInT, typename PointOutT>
void pcl::IntensitySpinEstimation< PointInT, PointOutT >::setNrIntensityBins ( size_t  nr_intensity_bins) [inline]

Set the number of bins to use in the intensity dimension of the spin image.

Parameters:
[in]nr_intensity_binsthe number of bins to use in the intensity dimension of the spin image

Definition at line 110 of file intensity_spin.h.

template<typename PointInT, typename PointOutT>
void pcl::IntensitySpinEstimation< PointInT, PointOutT >::setSmoothingBandwith ( float  sigma) [inline]

Set the standard deviation of the Gaussian smoothing kernel to use when constructing the spin images.

Parameters:
[in]sigmathe standard deviation of the Gaussian smoothing kernel to use when constructing the spin images

Definition at line 120 of file intensity_spin.h.


Member Data Documentation

template<typename PointInT, typename PointOutT>
int pcl::IntensitySpinEstimation< PointInT, PointOutT >::nr_distance_bins_

The number of distance bins in the descriptor.

Definition at line 135 of file intensity_spin.h.

template<typename PointInT, typename PointOutT>
int pcl::IntensitySpinEstimation< PointInT, PointOutT >::nr_intensity_bins_

The number of intensity bins in the descriptor.

Definition at line 138 of file intensity_spin.h.

template<typename PointInT, typename PointOutT>
float pcl::IntensitySpinEstimation< PointInT, PointOutT >::sigma_

The standard deviation of the Gaussian smoothing kernel used to construct the spin images.

Definition at line 141 of file intensity_spin.h.


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


pcl
Author(s): Open Perception
autogenerated on Mon Oct 6 2014 03:19:30