A Channel descriptor uses the value in a specified channel of a sensor_msgs::PointCloud as the feature value. More...
#include <channel.h>
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. |
A Channel descriptor uses the value in a specified channel of a sensor_msgs::PointCloud as the feature value.
Channel::Channel | ( | const std::string & | channel_name | ) |
Instantiates the channel descriptor to use the specified channel as the feature value.
channel_name | The name of the channel to use |
Definition at line 42 of file channel.cpp.
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
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.
Implements Descriptor3D.
std::string Channel::getName | ( | ) | const [virtual] |
Returns a string that is unique for the current param settings.
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.
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.
Implements Descriptor3D.
Definition at line 77 of file channel.cpp.
std::string Channel::channel_name_ [private] |