#include <kdtree.h>
Public Member Functions | |
KdTree () | |
Empty constructor for KdTree. Sets some internal values to their defaults. | |
KdTree (const sensor_msgs::PointCloud &points) | |
Constructor for KdTree. | |
KdTree (const sensor_msgs::PointCloud &points, const std::vector< int > &indices) | |
Constructor for KdTree. | |
virtual void | nearestKSearch (const geometry_msgs::Point32 &p_q, 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 (int index, int k, std::vector< int > &k_indices, std::vector< float > &k_distances)=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 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 (int index, 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. |
cloud_kdtree::KdTree::KdTree | ( | ) | [inline] |
cloud_kdtree::KdTree::KdTree | ( | const sensor_msgs::PointCloud & | points | ) |
Constructor for KdTree.
points | the ROS point cloud data array |
cloud_kdtree::KdTree::KdTree | ( | const sensor_msgs::PointCloud & | points, |
const std::vector< int > & | indices | ||
) |
Constructor for KdTree.
points | the ROS point cloud data array |
indices | the point cloud indices |
virtual cloud_kdtree::KdTree::~KdTree | ( | ) | [inline, virtual] |
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::KdTreeFLANN, and 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::KdTreeFLANN, and cloud_kdtree::KdTreeANN.
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::KdTreeFLANN, and 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::KdTreeFLANN, and 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::KdTreeFLANN, and 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::KdTreeFLANN, and cloud_kdtree::KdTreeANN.
double cloud_kdtree::KdTree::epsilon_ [protected] |