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

A Channel descriptor uses the value in a specified channel of a sensor_msgs::PointCloud as the feature value. More...

#include <channel.h>

Inheritance diagram for Channel:
Inheritance graph
[legend]

List of all members.

Public Member Functions

 Channel (const std::string &channel_name)
 Instantiates the channel descriptor to use the specified channel as the feature value.
virtual void clearShared ()
 This descriptor uses no shared precomputation, so this method has no affect.
std::string getName () const
 Returns a string that is unique for the current param settings.

Protected Member Functions

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)
 Extracts the value from the channel corresponding to the specified interest points.
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)
 Extracts the average value from the channel corresponding to each point in the specified interest region.
virtual int precompute (const sensor_msgs::PointCloud &data, cloud_kdtree::KdTree &data_kdtree, const std::vector< const geometry_msgs::Point32 * > &interest_pts)
 This descriptor requires no pre-computation, so this method has no affect.
virtual int precompute (const sensor_msgs::PointCloud &data, cloud_kdtree::KdTree &data_kdtree, const std::vector< const std::vector< int > * > &interest_region_indices)
 This descriptor requires no pre-computation, so this method has no affect.

Private Attributes

std::string channel_name_
 The name of the channel to use.

Detailed Description

A Channel descriptor uses the value in a specified channel of a sensor_msgs::PointCloud as the feature value.

Definition at line 68 of file channel.h.


Constructor & Destructor Documentation

Channel::Channel ( const std::string &  channel_name)

Instantiates the channel descriptor to use the specified channel as the feature value.

Parameters:
channel_nameThe name of the channel to use

Definition at line 42 of file channel.cpp.


Member Function Documentation

void Channel::clearShared ( ) [virtual]

This descriptor uses no shared precomputation, so this method has no affect.

Implements Descriptor3D.

Definition at line 52 of file channel.cpp.

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

Extracts the value from the channel corresponding to the specified interest points.

If the exact interest point i cannot be found in data, then results[i].size == 0

See also:
Descriptor3D::compute

Implements Descriptor3D.

Definition at line 87 of file channel.cpp.

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

Extracts the average value from the channel corresponding to each point in the specified interest region.

See also:
Descriptor3D::compute

Implements Descriptor3D.

std::string Channel::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 59 of file channel.cpp.

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

This descriptor requires no pre-computation, so this method has no affect.

Returns:
0 always

Implements Descriptor3D.

Definition at line 67 of file channel.cpp.

int Channel::precompute ( const sensor_msgs::PointCloud data,
cloud_kdtree::KdTree &  data_kdtree,
const std::vector< const std::vector< int > * > &  interest_region_indices 
) [protected, virtual]

This descriptor requires no pre-computation, so this method has no affect.

Returns:
0 always

Implements Descriptor3D.

Definition at line 77 of file channel.cpp.


Member Data Documentation

std::string Channel::channel_name_ [private]

The name of the channel to use.

Definition at line 145 of file channel.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