Public Member Functions | Private Member Functions | Private Attributes
SpectralAnalysis Class Reference

A SpectralAnalysis performs eigen-analysis on neighborhoods of point clouds and saves the resulting eigenvectors and eigenvalues. More...

#include <spectral_analysis.h>

List of all members.

Public Member Functions

int analyzeInterestPoints (const sensor_msgs::PointCloud &data, cloud_kdtree::KdTree &data_kdtree, const std::vector< const geometry_msgs::Point32 * > &interest_pts)
 Performs eigen-decomposition for each neighborhood around the interest points.
int analyzeInterestRegions (const sensor_msgs::PointCloud &data, cloud_kdtree::KdTree &data_kdtree, const std::vector< const std::vector< int > * > &interest_region_indices)
 Performs eigen-decomposition for each neighborhood in/around the interest regions.
void clearSpectral ()
 Clears & frees previously computed spectral data.
 SpectralAnalysis ()
 Instantiates the class to perform eigen-analysis on neighborhoods of points around each interest point/region within the specified support radius.
 SpectralAnalysis (double support_radius)
 ~SpectralAnalysis ()
Accessors
bool isSpectralComputed () const
 Returns flag if spectral information has been computed.
const std::vector< const
Eigen3::Vector3d * > & 
getNormals () const
 Returns the saved normals (smallest eigenvector) estimated for each interest point/region.
double getRadius () const
 Returns the support radius.
const std::vector< const
Eigen3::Vector3d * > & 
getTangents () const
 Returns the saved tangents (biggest eigenvector) estimated for each interest point/region.
const std::vector< const
Eigen3::Vector3d * > & 
getMiddleEigenVectors () const
 Returns the saved middle/2nd eigenvector estimated for each interest ponit/region.
const std::vector< const
Eigen3::Vector3d * > & 
getEigenValues () const
 Returns the saved eigenvalues of the covariance matrix for each interest point/region.

Private Member Functions

void computeSpectralInfo (const sensor_msgs::PointCloud &data, const std::vector< int > &curr_region_indices, const size_t idx)
 Common method that computes the eigen-vector/values of the scattered matrix constructed from the given neighborhood.

Private Attributes

std::vector< const
Eigen3::Vector3d * > 
eigenvalues_
 The extracted eigenvalues.
std::vector< const
Eigen3::Vector3d * > 
middle_eig_vecs_
 The 2nd/middle extracted eigenvectors.
std::vector< const
Eigen3::Vector3d * > 
normals_
 The smallest extracted eigenvectors.
bool spectral_computed_
 Flag indicating if eigen-decomposition has been performed.
double support_radius_
 The radius used to define the local neighborhood.
std::vector< const
Eigen3::Vector3d * > 
tangents_
 The biggest extracted eigenvectors.

Detailed Description

A SpectralAnalysis performs eigen-analysis on neighborhoods of point clouds and saves the resulting eigenvectors and eigenvalues.

SpectralAnalysis does NOT inherit from Descriptor3D. Instead, this class is meant to hold intermediate computations to be shared with requiring Descriptor3Ds that use spectral information such that computation is not unnecessarily repeated.

Definition at line 73 of file spectral_analysis.h.


Constructor & Destructor Documentation

Instantiates the class to perform eigen-analysis on neighborhoods of points around each interest point/region within the specified support radius.

After instantiation, NO other methods need to be called before passing this to a Descriptor3D for computation.

TODO add sensor location (for aligning normals to viewpoint)

Parameters:
support_radiusThe radius to define the local neighborhood around each interest point/region. For interest regions, a negative value indicates to use the region itself for spectral analysis

Definition at line 93 of file spectral_analysis.h.

SpectralAnalysis::SpectralAnalysis ( double  support_radius)

Definition at line 42 of file spectral_analysis.cpp.

Definition at line 51 of file spectral_analysis.cpp.


Member Function Documentation

int SpectralAnalysis::analyzeInterestPoints ( const sensor_msgs::PointCloud data,
cloud_kdtree::KdTree &  data_kdtree,
const std::vector< const geometry_msgs::Point32 * > &  interest_pts 
)

Performs eigen-decomposition for each neighborhood around the interest points.

This method does NOT need to be called by the user before passing to a Descriptor3D

Definition at line 82 of file spectral_analysis.cpp.

int SpectralAnalysis::analyzeInterestRegions ( const sensor_msgs::PointCloud data,
cloud_kdtree::KdTree &  data_kdtree,
const std::vector< const std::vector< int > * > &  interest_region_indices 
)

Performs eigen-decomposition for each neighborhood in/around the interest regions.

This method does NOT need to be called by the user before passing to a Descriptor3D

Definition at line 146 of file spectral_analysis.cpp.

Clears & frees previously computed spectral data.

This function should be called when calling Descriptor3D::compute() on DIFFERENT point clouds.

Definition at line 59 of file spectral_analysis.cpp.

void SpectralAnalysis::computeSpectralInfo ( const sensor_msgs::PointCloud data,
const std::vector< int > &  curr_region_indices,
const size_t  idx 
) [private]

Common method that computes the eigen-vector/values of the scattered matrix constructed from the given neighborhood.

Definition at line 215 of file spectral_analysis.cpp.

const std::vector<const Eigen3::Vector3d*>& SpectralAnalysis::getEigenValues ( ) const [inline]

Returns the saved eigenvalues of the covariance matrix for each interest point/region.

Definition at line 171 of file spectral_analysis.h.

const std::vector<const Eigen3::Vector3d*>& SpectralAnalysis::getMiddleEigenVectors ( ) const [inline]

Returns the saved middle/2nd eigenvector estimated for each interest ponit/region.

Definition at line 160 of file spectral_analysis.h.

const std::vector<const Eigen3::Vector3d*>& SpectralAnalysis::getNormals ( ) const [inline]

Returns the saved normals (smallest eigenvector) estimated for each interest point/region.

Definition at line 128 of file spectral_analysis.h.

double SpectralAnalysis::getRadius ( ) const [inline]

Returns the support radius.

Definition at line 138 of file spectral_analysis.h.

const std::vector<const Eigen3::Vector3d*>& SpectralAnalysis::getTangents ( ) const [inline]

Returns the saved tangents (biggest eigenvector) estimated for each interest point/region.

Definition at line 149 of file spectral_analysis.h.

Returns flag if spectral information has been computed.

Definition at line 117 of file spectral_analysis.h.


Member Data Documentation

std::vector<const Eigen3::Vector3d*> SpectralAnalysis::eigenvalues_ [private]

The extracted eigenvalues.

Definition at line 230 of file spectral_analysis.h.

std::vector<const Eigen3::Vector3d*> SpectralAnalysis::middle_eig_vecs_ [private]

The 2nd/middle extracted eigenvectors.

Definition at line 227 of file spectral_analysis.h.

std::vector<const Eigen3::Vector3d*> SpectralAnalysis::normals_ [private]

The smallest extracted eigenvectors.

Definition at line 221 of file spectral_analysis.h.

Flag indicating if eigen-decomposition has been performed.

Definition at line 218 of file spectral_analysis.h.

The radius used to define the local neighborhood.

Definition at line 215 of file spectral_analysis.h.

std::vector<const Eigen3::Vector3d*> SpectralAnalysis::tangents_ [private]

The biggest extracted eigenvectors.

Definition at line 224 of file spectral_analysis.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