Public Member Functions | Protected Member Functions | Protected Attributes
OrientationGeneric Class Reference

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>

Inheritance diagram for OrientationGeneric:
Inheritance graph
[legend]

List of all members.

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_.

Detailed Description

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.


Constructor & Destructor Documentation

Abstract constructor.

Definition at line 42 of file orientation_generic.cpp.

Definition at line 48 of file orientation_generic.cpp.


Member Function Documentation

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.

Parameters:
interest_sample_idxThe interest point/region being processed
resultContainer 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.

See also:
Descriptor3D::compute

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.

See also:
Descriptor3D::compute

Implements Descriptor3D.

Definition at line 73 of file orientation_generic.cpp.


Member Data Documentation

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.

The negative of reference_direction_.

Definition at line 124 of file orientation_generic.h.


The documentation for this class was generated from the following files:
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Properties Friends


ias_descriptors_3d
Author(s): Daniel Munoz/ dmunoz@willowgarage.com, Dejan Pangercic (patched version)
autogenerated on Thu May 23 2013 14:01:18