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

SpinImageGeneric is the base class for descriptors that compute spin images as described in:
Johnson and Hebert, "Using Spin-Images for Efficient Object Recognition in Cluttered 3-D Scenes", PAMI 1999. More...

#include <spin_image_generic.h>

Inheritance diagram for SpinImageGeneric:
Inheritance graph
[legend]

List of all members.

Public Member Functions

 SpinImageGeneric ()
 Abstract constructor.
virtual ~SpinImageGeneric ()=0

Protected Member Functions

virtual void computeNeighborhoodFeature (const sensor_msgs::PointCloud &data, const std::vector< int > &neighbor_indices, const unsigned int interest_sample_idx, std::vector< float > &result) const
 Computes the spin image descriptor for the given neighborhood of points.
void display (const std::vector< float > &spin_image) const

Protected Attributes

double col_res_
 The cell resolution along the alpha axis.
unsigned int nbr_cols_
 The number of cells along the alpha axis.
unsigned int nbr_rows_
 The number of cells along the beta axis.
double row_res_
 The cell resolution along the beta axis.
const std::vector< const
Eigen3::Vector3d * > * 
spin_axes_
 The spinning (beta) axis for each interest point/region.
std::vector< Eigen3::Vector3d > spin_image_centers_
 The point that the image is spinning around.

Detailed Description

SpinImageGeneric is the base class for descriptors that compute spin images as described in:
Johnson and Hebert, "Using Spin-Images for Efficient Object Recognition in Cluttered 3-D Scenes", PAMI 1999.

See the inheriting class' descriptions

Definition at line 70 of file spin_image_generic.h.


Constructor & Destructor Documentation

Abstract constructor.

Definition at line 42 of file spin_image_generic.cpp.

Definition at line 50 of file spin_image_generic.cpp.


Member Function Documentation

void SpinImageGeneric::computeNeighborhoodFeature ( const sensor_msgs::PointCloud data,
const std::vector< int > &  neighbor_indices,
const unsigned int  interest_sample_idx,
std::vector< float > &  result 
) const [protected, virtual]

Computes the spin image descriptor for the given neighborhood of points.

Parameters:
dataThe overall point cloud data
neighbor_indicesList of indices in data that constitute the neighborhood
interest_sample_idxThe interest point/region that is being processed.
resultThe vector to hold the resulting spin image feature vector

Implements NeighborhoodFeature.

Definition at line 91 of file spin_image_generic.cpp.

void SpinImageGeneric::display ( const std::vector< float > &  spin_image) const [protected]

Definition at line 54 of file spin_image_generic.cpp.


Member Data Documentation

double SpinImageGeneric::col_res_ [protected]

The cell resolution along the alpha axis.

Definition at line 112 of file spin_image_generic.h.

unsigned int SpinImageGeneric::nbr_cols_ [protected]

The number of cells along the alpha axis.

Definition at line 118 of file spin_image_generic.h.

unsigned int SpinImageGeneric::nbr_rows_ [protected]

The number of cells along the beta axis.

Definition at line 115 of file spin_image_generic.h.

double SpinImageGeneric::row_res_ [protected]

The cell resolution along the beta axis.

Definition at line 109 of file spin_image_generic.h.

const std::vector<const Eigen3::Vector3d*>* SpinImageGeneric::spin_axes_ [protected]

The spinning (beta) axis for each interest point/region.

Definition at line 103 of file spin_image_generic.h.

std::vector<Eigen3::Vector3d> SpinImageGeneric::spin_image_centers_ [protected]

The point that the image is spinning around.

Definition at line 106 of file spin_image_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