Public Member Functions | Protected Member Functions | Private Attributes
SpinImageTangent Class Reference

A SpinImageTangent descriptor computes a spin image spinning around the locally extracted tangent vector. More...

#include <spin_image_tangent.h>

Inheritance diagram for SpinImageTangent:
Inheritance graph
[legend]

List of all members.

Public Member Functions

virtual void clearShared ()
 Clears any already-computed spectral information.
std::string getName () const
 Returns a string that is unique for the current param settings.
 SpinImageTangent (const double row_res, const double col_res, const unsigned int nbr_rows, const unsigned int nbr_cols, const bool use_interest_regions_only, SpectralAnalysis &spectral_information)
 Instantiates the spin image descriptor to use the given specifications.

Protected Member Functions

virtual int precompute (const sensor_msgs::PointCloud &data, cloud_kdtree::KdTree &data_kdtree, const std::vector< const geometry_msgs::Point32 * > &interest_pts)
 Computes/retrieves the tangent for each interest point.
virtual int precompute (const sensor_msgs::PointCloud &data, cloud_kdtree::KdTree &data_kdtree, const std::vector< const std::vector< int > * > &interest_region_indices)
 Computes/retrieves the tangent for each interest region.

Private Attributes

SpectralAnalysisspectral_information_

Detailed Description

A SpinImageTangent descriptor computes a spin image spinning around the locally extracted tangent vector.

The tangent vector is the "beta" axis as described in Johnson & Hebert 1999.

Example spin image definition with 3 rows and 4 cols:
beta
^
|_ _ _ _
|_|_|_|_|
x_|_|_|_|
|_|_|_|_|
-----------> alpha
(x = center point of spin image, beta = [tangent vector])

The center point of the spin image is the given interest point or the centroid of given regions of interest points

Definition at line 78 of file spin_image_tangent.h.


Constructor & Destructor Documentation

SpinImageTangent::SpinImageTangent ( const double  row_res,
const double  col_res,
const unsigned int  nbr_rows,
const unsigned int  nbr_cols,
const bool  use_interest_regions_only,
SpectralAnalysis spectral_information 
)

Instantiates the spin image descriptor to use the given specifications.

Warning:
The number of rows (nbr_rows) must be odd
Parameters:
row_resThe cell resolution along the beta axis
col_resThe cell resolution along the alpha axis
nbr_rowsThe number of cells along the beta axis
nbr_colsThe number of cells along the alpha axis
use_interest_regions_onlyWhen computing for interest regions, true indicates to use only the points within the interest region to compute the spin image
spectral_informationThe class to retrieve the tangent vectors from for each interest point/region

Definition at line 42 of file spin_image_tangent.cpp.


Member Function Documentation

void SpinImageTangent::clearShared ( ) [virtual]

Clears any already-computed spectral information.

Implements Descriptor3D.

Definition at line 72 of file spin_image_tangent.cpp.

std::string SpinImageTangent::getName ( ) const [virtual]

Returns a string that is unique for the current param settings.

Returns:
the name of this feature.

Implements Descriptor3D.

Definition at line 80 of file spin_image_tangent.cpp.

int SpinImageTangent::precompute ( const sensor_msgs::PointCloud data,
cloud_kdtree::KdTree &  data_kdtree,
const std::vector< const geometry_msgs::Point32 * > &  interest_pts 
) [protected, virtual]

Computes/retrieves the tangent for each interest point.

Parameters:
dataThe point cloud to process from Descriptor3D::compute()
data_kdtreeThe efficient neighborhood data structure
interest_ptsThe list of interest points to be processed
Returns:
0 on success, otherwise negative value on error

Implements Descriptor3D.

Definition at line 88 of file spin_image_tangent.cpp.

int SpinImageTangent::precompute ( const sensor_msgs::PointCloud data,
cloud_kdtree::KdTree &  data_kdtree,
const std::vector< const std::vector< int > * > &  interest_region_indices 
) [protected, virtual]

Computes/retrieves the tangent for each interest region.

Parameters:
dataThe point cloud to process from Descriptor3D::compute()
data_kdtreeThe efficient neighborhood data structure
interest_ptsThe list of interest points to be processed
Returns:
0 on success, otherwise negative value on error

Implements Descriptor3D.

Definition at line 132 of file spin_image_tangent.cpp.


Member Data Documentation

Definition at line 145 of file spin_image_tangent.h.


The documentation for this class was generated from the following files:
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Properties Friends


ias_descriptors_3d
Author(s): Daniel Munoz/ dmunoz@willowgarage.com, Dejan Pangercic (patched version)
autogenerated on Thu May 23 2013 14:01:18