A Position descriptor defines a feature from the z-coordinate of the interest point or the interest region's centroid. More...
#include <position.h>
Public Member Functions | |
virtual void | clearShared () |
This descriptor uses no shared precomputation, so this method has no affect. | |
std::string | getName () const |
Returns a name that is unique for any given setting of the parameters. | |
Position () | |
Instantiates the position descriptor such that the z-coordinate is absolute. i.e. the feature is the interest point/region's z-coordinate. | |
Position (float ref_z) | |
Instantiates the position descriptor such that the z coordinate is relative to the given height. i.e. the feature is the interest point/region's z-coordinate minus ref_z. | |
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) |
Extract the z-coordinate of the 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) |
Extract the z-coordinate of the interest regions' centroids. | |
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 | |
float | ref_z_ |
A Position descriptor defines a feature from the z-coordinate of the interest point or the interest region's centroid.
TODO: use map information such as distance from walls
Definition at line 65 of file position.h.
Instantiates the position descriptor such that the z-coordinate is absolute. i.e. the feature is the interest point/region's z-coordinate.
Definition at line 42 of file position.cpp.
Position::Position | ( | float | ref_z | ) |
Instantiates the position descriptor such that the z coordinate is relative to the given height. i.e. the feature is the interest point/region's z-coordinate minus ref_z.
ref_z | The reference z (elevation) coordinate. |
Definition at line 70 of file position.cpp.
void Position::clearShared | ( | ) | [virtual] |
This descriptor uses no shared precomputation, so this method has no affect.
Implements Descriptor3D.
Definition at line 53 of file position.cpp.
void Position::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] |
Extract the z-coordinate of the interest points.
Implements Descriptor3D.
Definition at line 101 of file position.cpp.
virtual void Position::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] |
Extract the z-coordinate of the interest regions' centroids.
Implements Descriptor3D.
std::string Position::getName | ( | void | ) | const [virtual] |
Returns a name that is unique for any given setting of the parameters.
Implements Descriptor3D.
Definition at line 60 of file position.cpp.
int Position::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 81 of file position.cpp.
int Position::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 91 of file position.cpp.
float Position::ref_z_ [private] |
Definition at line 154 of file position.h.