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

A ShapeSpectral descriptor computes features that indicate the flat-ness (F), linear-ness (L), and scattered-ness (S) of a local neighborhood around an interest point/region. More...

#include <shape_spectral.h>

Inheritance diagram for ShapeSpectral:
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.
 ShapeSpectral ()
 Instantiates the shape descriptor to use the given spectral information.
 ShapeSpectral (SpectralAnalysis &spectral_information)

Protected Member Functions

virtual void computeShapeFeatures (const unsigned int interest_sample_idx, std::vector< float > &result) const
 Computes local shape features for the specified interest point/region.
virtual void doComputation (const sensor_msgs::PointCloud &data, cloud_kdtree::KdTree &data_kdtree, const std::vector< const geometry_msgs::Point32 * > &interest_pts, std::vector< std::vector< float > > &results)
 Computes the saliency features that describe the local shape around each interest point.
virtual void doComputation (const sensor_msgs::PointCloud &data, cloud_kdtree::KdTree &data_kdtree, const std::vector< const std::vector< int > * > &interest_region_indices, std::vector< std::vector< float > > &results)
 Computes the saliency features that describe the local shape around/in each interest region.
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 eigenvalues 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 eigenvalues for each interest region.

Private Attributes

const std::vector< const
Eigen3::Vector3d * > * 
eig_vals_
 The eigenvalues for each interest point/region to be processed.
SpectralAnalysisspectral_information_

Detailed Description

A ShapeSpectral descriptor computes features that indicate the flat-ness (F), linear-ness (L), and scattered-ness (S) of a local neighborhood around an interest point/region.

It is based from the Tensor Voting framework from Medioni et al., "A Computational Framework for Segmentation and Grouping", Elsevier 2000.

The features are based on the eigenvalues from the scatter matrix constructed from the neighborhood of points. The feature vector format is: [S L F]

Definition at line 69 of file shape_spectral.h.


Constructor & Destructor Documentation

Instantiates the shape descriptor to use the given spectral information.

Parameters:
spectral_informationClass to retrieve the eigenvalues from

Definition at line 80 of file shape_spectral.h.

ShapeSpectral::ShapeSpectral ( SpectralAnalysis spectral_information)

Definition at line 42 of file shape_spectral.cpp.


Member Function Documentation

void ShapeSpectral::clearShared ( ) [virtual]

Clears any already-computed spectral information.

Implements Descriptor3D.

Definition at line 54 of file shape_spectral.cpp.

void ShapeSpectral::computeShapeFeatures ( const unsigned int  interest_sample_idx,
std::vector< float > &  result 
) const [protected, virtual]

Computes local shape features for the specified interest point/region.

Definition at line 168 of file shape_spectral.cpp.

void ShapeSpectral::doComputation ( const sensor_msgs::PointCloud data,
cloud_kdtree::KdTree &  data_kdtree,
const std::vector< const geometry_msgs::Point32 * > &  interest_pts,
std::vector< std::vector< float > > &  results 
) [protected, virtual]

Computes the saliency features that describe the local shape around each interest point.

See also:
Descriptor3D::compute

Implements Descriptor3D.

Definition at line 131 of file shape_spectral.cpp.

void ShapeSpectral::doComputation ( const sensor_msgs::PointCloud data,
cloud_kdtree::KdTree &  data_kdtree,
const std::vector< const std::vector< int > * > &  interest_region_indices,
std::vector< std::vector< float > > &  results 
) [protected, virtual]

Computes the saliency features that describe the local shape around/in each interest region.

See also:
Descriptor3D::compute

Implements Descriptor3D.

Definition at line 149 of file shape_spectral.cpp.

std::string ShapeSpectral::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 59 of file shape_spectral.cpp.

int ShapeSpectral::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 eigenvalues 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 71 of file shape_spectral.cpp.

int ShapeSpectral::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 eigenvalues for each interest region.

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

Implements Descriptor3D.

Definition at line 101 of file shape_spectral.cpp.


Member Data Documentation

const std::vector<const Eigen3::Vector3d*>* ShapeSpectral::eig_vals_ [private]

The eigenvalues for each interest point/region to be processed.

Definition at line 160 of file shape_spectral.h.

Definition at line 162 of file shape_spectral.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