An OrientationTangent descriptor uses extracted local tangents around each interest point/region to use as the local directions. More...
#include <orientation_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. | |
OrientationTangent (const double ref_x, const double ref_y, const double ref_z, SpectralAnalysis &spectral_information) | |
Instantiates the orientation descriptor with given reference direction information and spectral information. | |
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) |
Extracts the tangents around 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) |
Extracts the tangents around each interest region. | |
Private Attributes | |
SpectralAnalysis * | spectral_information_ |
An OrientationTangent descriptor uses extracted local tangents around each interest point/region to use as the local directions.
TODO: use sensor location so the extracted directions have meaningful signs
Definition at line 69 of file orientation_tangent.h.
OrientationTangent::OrientationTangent | ( | const double | ref_x, |
const double | ref_y, | ||
const double | ref_z, | ||
SpectralAnalysis & | spectral_information | ||
) |
Instantiates the orientation descriptor with given reference direction information and spectral information.
ref_x | The x dimension of the reference direction |
ref_y | The y dimension of the reference direction |
ref_z | The z dimension of the reference direction |
spectral_information | The class to retrieve the tangents from for each interest point/region |
Definition at line 42 of file orientation_tangent.cpp.
void OrientationTangent::clearShared | ( | ) | [virtual] |
Clears any already-computed spectral information.
Implements Descriptor3D.
Definition at line 68 of file orientation_tangent.cpp.
string OrientationTangent::getName | ( | ) | const [virtual] |
Returns a string that is unique for the current param settings.
Implements Descriptor3D.
Definition at line 60 of file orientation_tangent.cpp.
int OrientationTangent::precompute | ( | const sensor_msgs::PointCloud & | data, |
cloud_kdtree::KdTree & | data_kdtree, | ||
const std::vector< const geometry_msgs::Point32 * > & | interest_pts | ||
) | [protected, virtual] |
Extracts the tangents around each interest point.
Implements Descriptor3D.
Definition at line 76 of file orientation_tangent.cpp.
int OrientationTangent::precompute | ( | const sensor_msgs::PointCloud & | data, |
cloud_kdtree::KdTree & | data_kdtree, | ||
const std::vector< const std::vector< int > * > & | interest_region_indices | ||
) | [protected, virtual] |
Extracts the tangents around each interest region.
Implements Descriptor3D.
Definition at line 106 of file orientation_tangent.cpp.
Definition at line 121 of file orientation_tangent.h.