cloud_kdtree::KdTree Class Reference

#include <kdtree.h>

Inheritance diagram for cloud_kdtree::KdTree:
Inheritance graph
[legend]

List of all members.

Public Member Functions

 KdTree (const sensor_msgs::PointCloud &points, const std::vector< int > &indices)
 Constructor for KdTree.
 KdTree (const sensor_msgs::PointCloud &points)
 Constructor for KdTree.
 KdTree ()
 Empty constructor for KdTree. Sets some internal values to their defaults.
virtual void nearestKSearch (int index, int k, std::vector< int > &k_indices, std::vector< float > &k_distances)=0
virtual void nearestKSearch (const sensor_msgs::PointCloud &points, int index, int k, std::vector< int > &k_indices, std::vector< float > &k_distances)=0
virtual void nearestKSearch (const geometry_msgs::Point32 &p_q, int k, std::vector< int > &k_indices, std::vector< float > &k_distances)=0
virtual bool radiusSearch (int index, double radius, std::vector< int > &k_indices, std::vector< float > &k_distances, int max_nn=INT_MAX)=0
virtual bool radiusSearch (const sensor_msgs::PointCloud &points, int index, double radius, std::vector< int > &k_indices, std::vector< float > &k_distances, int max_nn=INT_MAX)=0
virtual bool radiusSearch (const geometry_msgs::Point32 &p_q, double radius, std::vector< int > &k_indices, std::vector< float > &k_distances, int max_nn=INT_MAX)=0
virtual ~KdTree ()
 Destructor for KdTree. Deletes all allocated data arrays and destroys the kd-tree structures.

Protected Attributes

double epsilon_
 Epsilon precision (error bound) for nearest neighbors searches.

Detailed Description

Definition at line 42 of file kdtree.h.


Constructor & Destructor Documentation

cloud_kdtree::KdTree::KdTree (  )  [inline]

Empty constructor for KdTree. Sets some internal values to their defaults.

Definition at line 49 of file kdtree.h.

cloud_kdtree::KdTree::KdTree ( const sensor_msgs::PointCloud &  points  ) 

Constructor for KdTree.

Parameters:
points the ROS point cloud data array
cloud_kdtree::KdTree::KdTree ( const sensor_msgs::PointCloud &  points,
const std::vector< int > &  indices 
)

Constructor for KdTree.

Note:
ATTENTION: This method breaks the 1-1 mapping between the indices returned using getNeighborsIndices and the ones from the points message ! When using this method, make sure to get the underlying point data using the getPoint method
Parameters:
points the ROS point cloud data array
indices the point cloud indices
virtual cloud_kdtree::KdTree::~KdTree (  )  [inline, virtual]

Destructor for KdTree. Deletes all allocated data arrays and destroys the kd-tree structures.

Definition at line 72 of file kdtree.h.


Member Function Documentation

virtual void cloud_kdtree::KdTree::nearestKSearch ( int  index,
int  k,
std::vector< int > &  k_indices,
std::vector< float > &  k_distances 
) [pure virtual]

Implemented in cloud_kdtree::KdTreeANN.

virtual void cloud_kdtree::KdTree::nearestKSearch ( const sensor_msgs::PointCloud &  points,
int  index,
int  k,
std::vector< int > &  k_indices,
std::vector< float > &  k_distances 
) [pure virtual]

Implemented in cloud_kdtree::KdTreeANN.

virtual void cloud_kdtree::KdTree::nearestKSearch ( const geometry_msgs::Point32 &  p_q,
int  k,
std::vector< int > &  k_indices,
std::vector< float > &  k_distances 
) [pure virtual]

Implemented in cloud_kdtree::KdTreeANN.

virtual bool cloud_kdtree::KdTree::radiusSearch ( int  index,
double  radius,
std::vector< int > &  k_indices,
std::vector< float > &  k_distances,
int  max_nn = INT_MAX 
) [pure virtual]

Implemented in cloud_kdtree::KdTreeANN.

virtual bool cloud_kdtree::KdTree::radiusSearch ( const sensor_msgs::PointCloud &  points,
int  index,
double  radius,
std::vector< int > &  k_indices,
std::vector< float > &  k_distances,
int  max_nn = INT_MAX 
) [pure virtual]

Implemented in cloud_kdtree::KdTreeANN.

virtual bool cloud_kdtree::KdTree::radiusSearch ( const geometry_msgs::Point32 &  p_q,
double  radius,
std::vector< int > &  k_indices,
std::vector< float > &  k_distances,
int  max_nn = INT_MAX 
) [pure virtual]

Implemented in cloud_kdtree::KdTreeANN.


Member Data Documentation

double cloud_kdtree::KdTree::epsilon_ [protected]

Epsilon precision (error bound) for nearest neighbors searches.

Definition at line 88 of file kdtree.h.


The documentation for this class was generated from the following file:
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Defines


stereo_wall_detection
Author(s): Radu Bogdan Rusu
autogenerated on Fri Jan 11 09:37:23 2013