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

A NeighborhoodFeature is an abstract base class for descriptors that use a local neighborhood of points to compute features. More...

#include <neighborhood_feature.h>

Inheritance diagram for NeighborhoodFeature:
Inheritance graph
[legend]

List of all members.

Public Member Functions

 NeighborhoodFeature ()
 Abstract constructor.
virtual ~NeighborhoodFeature ()=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 =0
 The prototype of the method that computes the features as defined in the inheriting class.
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)
 Retrieves the local neighborhood around each interest point and then computes features.
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)
 Retrieves the local neighborhood around each interest region and then computes features.

Protected Attributes

float neighborhood_radius_
 The radius to define the bounding box.
bool neighborhood_radius_defined_
 Flag if neighborhood_radius_ has been defined.

Detailed Description

A NeighborhoodFeature is an abstract base class for descriptors that use a local neighborhood of points to compute features.

Example: a spin image uses neighboring points to compute a histogram

Definition at line 69 of file neighborhood_feature.h.


Constructor & Destructor Documentation

Abstract constructor.

Definition at line 42 of file neighborhood_feature.cpp.

Definition at line 51 of file neighborhood_feature.cpp.


Member Function Documentation

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

The prototype of the method that computes the features as defined in the inheriting class.

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

Implemented in BoundingBoxSpectral, BoundingBoxRaw, and SpinImageGeneric.

void NeighborhoodFeature::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]

Retrieves the local neighborhood around each interest point and then computes features.

See also:
Descriptor3D::compute

Implements Descriptor3D.

Definition at line 58 of file neighborhood_feature.cpp.

virtual void NeighborhoodFeature::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]

Retrieves the local neighborhood around each interest region and then computes features.

See also:
Descriptor3D::compute

Implements Descriptor3D.


Member Data Documentation

The radius to define the bounding box.

Definition at line 126 of file neighborhood_feature.h.

Flag if neighborhood_radius_ has been defined.

Definition at line 129 of file neighborhood_feature.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