cloud_kdtree::KdTreeANN Class Reference

#include <kdtree_ann.h>

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

List of all members.

Public Member Functions

 KdTreeANN (const sensor_msgs::PointCloud &points, const std::vector< int > &indices)
 Constructor for KdTree.
 KdTreeANN (const sensor_msgs::PointCloud &points)
 Constructor for KdTree.
virtual void nearestKSearch (int index, int k, std::vector< int > &k_indices, std::vector< float > &k_distances)
 Search for k-nearest neighbors for the given query point.
virtual void nearestKSearch (const sensor_msgs::PointCloud &points, int index, int k, std::vector< int > &k_indices, std::vector< float > &k_distances)
 Search for k-nearest neighbors for the given query point.
virtual void nearestKSearch (const geometry_msgs::Point32 &p_q, int k, std::vector< int > &k_indices, std::vector< float > &k_distances)
 Search for k-nearest neighbors for the given query point.
virtual bool radiusSearch (int index, double radius, std::vector< int > &k_indices, std::vector< float > &k_distances, int max_nn=INT_MAX)
 Search for all the nearest neighbors of the query point in a given radius.
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)
 Search for all the nearest neighbors of the query point in a given radius.
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)
 Search for all the nearest neighbors of the query point in a given radius.
virtual ~KdTreeANN ()
 Destructor for KdTree. Deletes all allocated data arrays and destroys the kd-tree structures.

Private Member Functions

int convertCloudToArray (const sensor_msgs::PointCloud &ros_cloud, const std::vector< int > &indices)
 Converts a ROS PointCloud message with a given set of indices to the internal ANN point array representation. Returns the number of points.
int convertCloudToArray (const sensor_msgs::PointCloud &ros_cloud)
 Converts a ROS PointCloud message to the internal ANN point array representation. Returns the number of points.

Private Attributes

ANNkd_treeann_kd_tree_
 The ANN kd tree object.
double bucket_size_
 Internal tree bucket size.
int dim_
 Tree dimensionality (i.e. the number of dimensions per point).
boost::mutex m_lock_
int nr_points_
 Number of points in the tree.
ANNpointArray points_
 Internal pointer to data.

Detailed Description

Definition at line 44 of file kdtree_ann.h.


Constructor & Destructor Documentation

cloud_kdtree::KdTreeANN::KdTreeANN ( const sensor_msgs::PointCloud &  points  )  [inline]

Constructor for KdTree.

Parameters:
points the ROS point cloud data array

Definition at line 52 of file kdtree_ann.h.

cloud_kdtree::KdTreeANN::KdTreeANN ( const sensor_msgs::PointCloud &  points,
const std::vector< int > &  indices 
) [inline]

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

Definition at line 81 of file kdtree_ann.h.

virtual cloud_kdtree::KdTreeANN::~KdTreeANN (  )  [inline, virtual]

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

Definition at line 104 of file kdtree_ann.h.


Member Function Documentation

int cloud_kdtree::KdTreeANN::convertCloudToArray ( const sensor_msgs::PointCloud &  ros_cloud,
const std::vector< int > &  indices 
) [private]

Converts a ROS PointCloud message with a given set of indices to the internal ANN point array representation. Returns the number of points.

Note:
ATTENTION: This method breaks the 1-1 mapping between the indices returned using getNeighborsIndices and the ones from the ros_cloud message ! When using this method, make sure to get the underlying point data using the getPoint method
Parameters:
ros_cloud the ROS PointCloud message
indices the point cloud indices

Definition at line 209 of file kdtree_ann.cpp.

int cloud_kdtree::KdTreeANN::convertCloudToArray ( const sensor_msgs::PointCloud &  ros_cloud  )  [private]

Converts a ROS PointCloud message to the internal ANN point array representation. Returns the number of points.

Parameters:
ros_cloud the ROS PointCloud message

Definition at line 174 of file kdtree_ann.cpp.

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

Search for k-nearest neighbors for the given query point.

Parameters:
index the index in points representing the query point
k the number of neighbors to search for
k_indices the resultant point indices
k_distances the resultant point distances

Implements cloud_kdtree::KdTree.

Definition at line 131 of file kdtree_ann.h.

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

Search for k-nearest neighbors for the given query point.

Parameters:
points the point cloud data
index the index in points representing the query point
k the number of neighbors to search for
k_indices the resultant point indices
k_distances the resultant point distances

Implements cloud_kdtree::KdTree.

Definition at line 70 of file kdtree_ann.cpp.

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

Search for k-nearest neighbors for the given query point.

Parameters:
p_q the given query point
k the number of neighbors to search for
k_indices the resultant point indices
k_distances the resultant point distances

Implements cloud_kdtree::KdTree.

Definition at line 45 of file kdtree_ann.cpp.

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

Search for all the nearest neighbors of the query point in a given radius.

Parameters:
index the index in points representing the query point
radius the radius of the sphere bounding all of p_q's neighbors
k_indices the resultant point indices
k_distances the resultant point distances
max_nn if given, bounds the maximum returned neighbors to this value

Implements cloud_kdtree::KdTree.

Definition at line 157 of file kdtree_ann.h.

bool cloud_kdtree::KdTreeANN::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 
) [virtual]

Search for all the nearest neighbors of the query point in a given radius.

Parameters:
points the point cloud data
index the index in points representing the query point
radius the radius of the sphere bounding all of p_q's neighbors
k_indices the resultant point indices
k_distances the resultant point distances
max_nn if given, bounds the maximum returned neighbors to this value

Implements cloud_kdtree::KdTree.

Definition at line 138 of file kdtree_ann.cpp.

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

Search for all the nearest neighbors of the query point in a given radius.

Parameters:
p_q the given query point
radius the radius of the sphere bounding all of p_q's neighbors
k_indices the resultant point indices
k_distances the resultant point distances
max_nn if given, bounds the maximum returned neighbors to this value

Implements cloud_kdtree::KdTree.

Definition at line 98 of file kdtree_ann.cpp.


Member Data Documentation

The ANN kd tree object.

Definition at line 191 of file kdtree_ann.h.

Internal tree bucket size.

Definition at line 194 of file kdtree_ann.h.

Tree dimensionality (i.e. the number of dimensions per point).

Definition at line 202 of file kdtree_ann.h.

boost::mutex cloud_kdtree::KdTreeANN::m_lock_ [private]

Definition at line 188 of file kdtree_ann.h.

Number of points in the tree.

Definition at line 200 of file kdtree_ann.h.

Internal pointer to data.

Definition at line 197 of file kdtree_ann.h.


The documentation for this class was generated from the following files:
 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