A SpinImageCustom descriptor computes a spin image spinning around a custom reference direction/axis. More...
#include <spin_image_custom.h>
Public Member Functions | |
virtual void | clearShared () |
This descriptor uses no shared precomputation, so this method has no affect. | |
std::string | getName () const |
Returns a name that is unique for any given setting of the parameters. | |
SpinImageCustom (const double ref_x, const double ref_y, const double ref_z, const double row_res, const double col_res, const unsigned int nbr_rows, const unsigned int nbr_cols, const bool use_interest_regions_only) | |
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) |
Defines the spin axis to be the custom direction 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) |
Defines the spin axis to be the custom direction for each interest region. | |
Private Attributes | |
Eigen3::Vector3d | custom_axis_ |
The custom spinning axis. | |
std::vector< const Eigen3::Vector3d * > | custom_axis_duplicated_ |
The custom axis duplicated for each interest point/region. |
A SpinImageCustom descriptor computes a spin image spinning around a custom reference direction/axis.
The custom axis 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 = [custom reference direction]
The center point of the spin image is the given interest point or the centroid of given regions of interest points
Definition at line 76 of file spin_image_custom.h.
SpinImageCustom::SpinImageCustom | ( | const double | ref_x, |
const double | ref_y, | ||
const double | ref_z, | ||
const double | row_res, | ||
const double | col_res, | ||
const unsigned int | nbr_rows, | ||
const unsigned int | nbr_cols, | ||
const bool | use_interest_regions_only | ||
) |
Instantiates the spin image descriptor to use the given specifications.
ref_x | The x dimension of the beta vector |
ref_y | The y dimension of the beta vector |
ref_z | The z dimension of the beta vector |
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 |
Definition at line 42 of file spin_image_custom.cpp.
void SpinImageCustom::clearShared | ( | ) | [virtual] |
This descriptor uses no shared precomputation, so this method has no affect.
Implements Descriptor3D.
Definition at line 76 of file spin_image_custom.cpp.
std::string SpinImageCustom::getName | ( | void | ) | const [virtual] |
Returns a name that is unique for any given setting of the parameters.
Implements Descriptor3D.
Definition at line 85 of file spin_image_custom.cpp.
int SpinImageCustom::precompute | ( | const sensor_msgs::PointCloud & | data, |
cloud_kdtree::KdTree & | data_kdtree, | ||
const std::vector< const geometry_msgs::Point32 * > & | interest_pts | ||
) | [protected, virtual] |
Defines the spin axis to be the custom direction 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 98 of file spin_image_custom.cpp.
int SpinImageCustom::precompute | ( | const sensor_msgs::PointCloud & | data, |
cloud_kdtree::KdTree & | data_kdtree, | ||
const std::vector< const std::vector< int > * > & | interest_region_indices | ||
) | [protected, virtual] |
Defines the spin axis to be the custom direction 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 126 of file spin_image_custom.cpp.
Eigen3::Vector3d SpinImageCustom::custom_axis_ [private] |
The custom spinning axis.
Definition at line 156 of file spin_image_custom.h.
std::vector<const Eigen3::Vector3d*> SpinImageCustom::custom_axis_duplicated_ [private] |
The custom axis duplicated for each interest point/region.
Definition at line 159 of file spin_image_custom.h.