A Curvature descriptor computes the local curvature around an intersest point/region. More...
#include <curvature.h>
Public Member Functions | |
virtual void | clearShared () |
Clears any already-computed spectral information. | |
Curvature (SpectralAnalysis &spectral_information) | |
Instantiates the curvature descriptor to use the given spectral information. | |
std::string | getName () const |
Returns a string that is unique for the current param settings. | |
Protected Member Functions | |
virtual void | computeCurvature (const unsigned int interest_sample_idx, std::vector< float > &result) const |
Computes local curvature feature 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 local curvature 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 local curvature around/for 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 Curvature descriptor computes the local curvature around an intersest point/region.
The feature value is / ( + + ) where are the 3 eigenvalues such that < <
Definition at line 64 of file curvature.h.
Curvature::Curvature | ( | SpectralAnalysis & | spectral_information | ) |
Instantiates the curvature descriptor to use the given spectral information.
spectral_information | Class to retrieve the eigenvalues from |
Definition at line 42 of file curvature.cpp.
void Curvature::clearShared | ( | ) | [virtual] |
Clears any already-computed spectral information.
Implements Descriptor3D.
Definition at line 54 of file curvature.cpp.
void Curvature::computeCurvature | ( | const unsigned int | interest_sample_idx, |
std::vector< float > & | result | ||
) | const [protected, virtual] |
Computes local curvature feature for the specified interest point/region.
Definition at line 168 of file curvature.cpp.
void Curvature::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 local curvature around each interest point.
Implements Descriptor3D.
Definition at line 131 of file curvature.cpp.
void Curvature::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 local curvature around/for each interest region.
Implements Descriptor3D.
Definition at line 149 of file curvature.cpp.
std::string Curvature::getName | ( | ) | const [virtual] |
Returns a string that is unique for the current param settings.
Implements Descriptor3D.
Definition at line 62 of file curvature.cpp.
int Curvature::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 70 of file curvature.cpp.
int Curvature::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 100 of file curvature.cpp.
const std::vector<const Eigen3::Vector3d*>* Curvature::eig_vals_ [private] |
The eigenvalues for each interest point/region to be processed.
Definition at line 151 of file curvature.h.
SpectralAnalysis* Curvature::spectral_information_ [private] |
Definition at line 153 of file curvature.h.