Public Member Functions | Protected Member Functions | Private Attributes
OrientationNormal Class Reference

An OrientationNormal descriptor uses extracted local normals around each interest point/region to use as the local directions. More...

#include <orientation_normal.h>

Inheritance diagram for OrientationNormal:
Inheritance graph
[legend]

List of all members.

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.
 OrientationNormal (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 normals 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 normals around each interest region.

Private Attributes

SpectralAnalysisspectral_information_

Detailed Description

An OrientationNormal descriptor uses extracted local normals around each interest point/region to use as the local directions.

Warning:
This descriptor ignores the sign of the extracted normal and the computed feature is always between 0 and 1

TODO: use sensor location so the extracted directions have meaningful signs

Definition at line 69 of file orientation_normal.h.


Constructor & Destructor Documentation

OrientationNormal::OrientationNormal ( 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.

Parameters:
ref_xThe x dimension of the reference direction
ref_yThe y dimension of the reference direction
ref_zThe z dimension of the reference direction
spectral_informationThe class to retrieve the normals from for each interest point/region

Definition at line 42 of file orientation_normal.cpp.


Member Function Documentation

void OrientationNormal::clearShared ( ) [virtual]

Clears any already-computed spectral information.

Implements Descriptor3D.

Definition at line 68 of file orientation_normal.cpp.

string OrientationNormal::getName ( ) const [virtual]

Returns a string that is unique for the current param settings.

Returns:
the name of this feature.

Implements Descriptor3D.

Definition at line 60 of file orientation_normal.cpp.

int OrientationNormal::precompute ( const sensor_msgs::PointCloud data,
cloud_kdtree::KdTree &  data_kdtree,
const std::vector< const geometry_msgs::Point32 * > &  interest_pts 
) [protected, virtual]

Extracts the normals around each interest point.

See also:
Descriptor3D::precompute()

Implements Descriptor3D.

Definition at line 76 of file orientation_normal.cpp.

int OrientationNormal::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 normals around each interest region.

See also:
Descriptor3D::precompute()

Implements Descriptor3D.

Definition at line 106 of file orientation_normal.cpp.


Member Data Documentation

Definition at line 122 of file orientation_normal.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