#include <kdtree_flann.h>
Public Member Functions | |
KdTreeFLANN (const sensor_msgs::PointCloud &points) | |
Constructor for KdTree. | |
KdTreeFLANN (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) |
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 (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 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 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 (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 | ~KdTreeFLANN () |
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) |
Converts a ROS PointCloud message to the internal ANN point array representation. Returns the number of points. | |
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. | |
Private Attributes | |
int | dim_ |
Tree dimensionality (i.e. the number of dimensions per point) | |
FLANNParameters | flann_param_ |
A pointer to a FL-ANN parameter structure. | |
FLANN_INDEX | index_id_ |
A FL-ANN type index reference. | |
boost::mutex | m_lock_ |
int | nr_points_ |
Number of points in the tree. | |
float * | points_ |
Internal pointer to data. |
Definition at line 46 of file kdtree_flann.h.
cloud_kdtree::KdTreeFLANN::KdTreeFLANN | ( | const sensor_msgs::PointCloud & | points | ) | [inline] |
Constructor for KdTree.
points | the ROS point cloud data array |
Definition at line 54 of file kdtree_flann.h.
cloud_kdtree::KdTreeFLANN::KdTreeFLANN | ( | const sensor_msgs::PointCloud & | points, |
const std::vector< int > & | indices | ||
) | [inline] |
Constructor for KdTree.
points | the ROS point cloud data array |
indices | the point cloud indices |
Definition at line 92 of file kdtree_flann.h.
virtual cloud_kdtree::KdTreeFLANN::~KdTreeFLANN | ( | ) | [inline, virtual] |
Destructor for KdTree. Deletes all allocated data arrays and destroys the kd-tree structures.
Definition at line 122 of file kdtree_flann.h.
int cloud_kdtree::KdTreeFLANN::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.
ros_cloud | the ROS PointCloud message |
Definition at line 206 of file kdtree_flann.cpp.
int cloud_kdtree::KdTreeFLANN::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.
ros_cloud | the ROS PointCloud message |
indices | the point cloud indices |
Definition at line 241 of file kdtree_flann.cpp.
void cloud_kdtree::KdTreeFLANN::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.
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 |
0 12 198 1 127 18 132 10 11 197
0 12 198 1 2 125 26 278 42 248 0 12 198 1 18 132 10 197 16 9 0 12 198 1 18 132 10 197 16 9 0 12 198 1 18 132 10 197 16 9
Implements cloud_kdtree::KdTree.
Definition at line 45 of file kdtree_flann.cpp.
void cloud_kdtree::KdTreeFLANN::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.
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 99 of file kdtree_flann.cpp.
virtual void cloud_kdtree::KdTreeFLANN::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.
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 147 of file kdtree_flann.h.
bool cloud_kdtree::KdTreeFLANN::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.
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 127 of file kdtree_flann.cpp.
bool cloud_kdtree::KdTreeFLANN::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.
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 168 of file kdtree_flann.cpp.
virtual bool cloud_kdtree::KdTreeFLANN::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.
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 170 of file kdtree_flann.h.
int cloud_kdtree::KdTreeFLANN::dim_ [private] |
Tree dimensionality (i.e. the number of dimensions per point)
Definition at line 220 of file kdtree_flann.h.
FLANNParameters cloud_kdtree::KdTreeFLANN::flann_param_ [private] |
A pointer to a FL-ANN parameter structure.
Definition at line 212 of file kdtree_flann.h.
FLANN_INDEX cloud_kdtree::KdTreeFLANN::index_id_ [private] |
A FL-ANN type index reference.
Definition at line 209 of file kdtree_flann.h.
boost::mutex cloud_kdtree::KdTreeFLANN::m_lock_ [private] |
Definition at line 206 of file kdtree_flann.h.
int cloud_kdtree::KdTreeFLANN::nr_points_ [private] |
Number of points in the tree.
Definition at line 218 of file kdtree_flann.h.
float* cloud_kdtree::KdTreeFLANN::points_ [private] |
Internal pointer to data.
Definition at line 215 of file kdtree_flann.h.