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>
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. | |
SpectralAnalysis * | spectral_information_ |
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.
ShapeSpectral::ShapeSpectral | ( | ) | [inline] |
Instantiates the shape descriptor to use the given spectral information.
spectral_information | Class 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.
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.
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.
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.
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.
data | The point cloud to process from Descriptor3D::compute() |
data_kdtree | The efficient neighborhood data structure |
interest_pts | The list of interest points to be processed |
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.
data | The point cloud to process from Descriptor3D::compute() |
data_kdtree | The efficient neighborhood data structure |
interest_pts | The list of interest regions to be processed |
Implements Descriptor3D.
Definition at line 101 of file shape_spectral.cpp.
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.