OrientationGeneric is an abstract base class for descriptors that compute the angle between a locally extracted direction and a specified reference direction. the Orientation descriptor. More...
#include <orientation_generic.h>
Public Member Functions | |
OrientationGeneric () | |
Abstract constructor. | |
virtual | ~OrientationGeneric ()=0 |
Protected Member Functions | |
virtual void | computeOrientation (const unsigned int interest_sample_idx, std::vector< float > &result) const |
Computes the angle for an 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 angle between the local around each interest point and the reference direction. | |
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 angle between the local around each interest region and the reference direction. | |
Protected Attributes | |
const std::vector< const Eigen3::Vector3d * > * | local_directions_ |
Container of the extracted local direction for each interest point/region. | |
Eigen3::Vector3d | reference_direction_ |
The reference direction to compare the local direction against. | |
Eigen3::Vector3d | reference_direction_flipped_ |
The negative of reference_direction_. |
OrientationGeneric is an abstract base class for descriptors that compute the angle between a locally extracted direction and a specified reference direction. the Orientation descriptor.
The computed feature is the cosine of the angle between the two vectors. See the inheriting class for the definition of the extracted local direction.
Definition at line 67 of file orientation_generic.h.
Abstract constructor.
Definition at line 42 of file orientation_generic.cpp.
OrientationGeneric::~OrientationGeneric | ( | ) | [pure virtual] |
Definition at line 48 of file orientation_generic.cpp.
void OrientationGeneric::computeOrientation | ( | const unsigned int | interest_sample_idx, |
std::vector< float > & | result | ||
) | const [inline, protected, virtual] |
Computes the angle for an interest point/region.
interest_sample_idx | The interest point/region being processed |
result | Container to hold cosine(theta) |
Definition at line 92 of file orientation_generic.cpp.
void OrientationGeneric::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 angle between the local around each interest point and the reference direction.
Implements Descriptor3D.
Definition at line 55 of file orientation_generic.cpp.
void OrientationGeneric::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 angle between the local around each interest region and the reference direction.
Implements Descriptor3D.
Definition at line 73 of file orientation_generic.cpp.
const std::vector<const Eigen3::Vector3d*>* OrientationGeneric::local_directions_ [protected] |
Container of the extracted local direction for each interest point/region.
Definition at line 118 of file orientation_generic.h.
Eigen3::Vector3d OrientationGeneric::reference_direction_ [protected] |
The reference direction to compare the local direction against.
Definition at line 121 of file orientation_generic.h.
Eigen3::Vector3d OrientationGeneric::reference_direction_flipped_ [protected] |
The negative of reference_direction_.
Definition at line 124 of file orientation_generic.h.