A SpinImageTangent descriptor computes a spin image spinning around the locally extracted tangent vector. More...
#include <spin_image_tangent.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. | |
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 | |
SpectralAnalysis * | spectral_information_ |
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.
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.
row_res | The cell resolution along the beta axis |
col_res | The cell resolution along the alpha axis |
nbr_rows | The number of cells along the beta axis |
nbr_cols | The number of cells along the alpha axis |
use_interest_regions_only | When computing for interest regions, true indicates to use only the points within the interest region to compute the spin image |
spectral_information | The class to retrieve the tangent vectors from for each interest point/region |
Definition at line 42 of file spin_image_tangent.cpp.
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.
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.
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 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.
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 132 of file spin_image_tangent.cpp.
Definition at line 145 of file spin_image_tangent.h.