KdTreeFLANN is a generic type of 3D spatial locator using kD-tree structures. The class is making use of the FLANN (Fast Library for Approximate Nearest Neighbor) project by Marius Muja and David Lowe. More...
#include <kdtree_flann.h>
Public Types | |
typedef boost::shared_ptr < const KdTreeFLANN< PointT > > | ConstPtr |
typedef flann::Index< Dist > | FLANNIndex |
typedef boost::shared_ptr < const std::vector< int > > | IndicesConstPtr |
typedef boost::shared_ptr < std::vector< int > > | IndicesPtr |
typedef KdTree< PointT > ::PointCloud | PointCloud |
typedef KdTree< PointT > ::PointCloudConstPtr | PointCloudConstPtr |
typedef boost::shared_ptr < KdTreeFLANN< PointT > > | Ptr |
Public Member Functions | |
KdTreeFLANN (bool sorted=true) | |
Default Constructor for KdTreeFLANN. | |
KdTreeFLANN (const KdTreeFLANN< PointT > &k) | |
Copy constructor. | |
Ptr | makeShared () |
int | nearestKSearch (const PointT &point, int k, std::vector< int > &k_indices, std::vector< float > &k_sqr_distances) const |
Search for k-nearest neighbors for the given query point. | |
KdTreeFLANN< PointT > & | operator= (const KdTreeFLANN< PointT > &k) |
Copy operator. | |
int | radiusSearch (const PointT &point, double radius, std::vector< int > &k_indices, std::vector< float > &k_sqr_distances, unsigned int max_nn=0) const |
Search for all the nearest neighbors of the query point in a given radius. | |
void | setEpsilon (float eps) |
Set the search epsilon precision (error bound) for nearest neighbors searches. | |
void | setInputCloud (const PointCloudConstPtr &cloud, const IndicesConstPtr &indices=IndicesConstPtr()) |
Provide a pointer to the input dataset. | |
void | setSortedResults (bool sorted) |
virtual | ~KdTreeFLANN () |
Destructor for KdTreeFLANN. Deletes all allocated data arrays and destroys the kd-tree structures. | |
Private Member Functions | |
void | cleanup () |
Internal cleanup method. | |
void | convertCloudToArray (const PointCloud &cloud) |
Converts a PointCloud to the internal FLANN point array representation. Returns the number of points. | |
void | convertCloudToArray (const PointCloud &cloud, const std::vector< int > &indices) |
Converts a PointCloud with a given set of indices to the internal FLANN point array representation. Returns the number of points. | |
virtual std::string | getName () const |
Class getName method. | |
Private Attributes | |
float * | cloud_ |
Internal pointer to data. | |
int | dim_ |
Tree dimensionality (i.e. the number of dimensions per point). | |
FLANNIndex * | flann_index_ |
A FLANN index object. | |
bool | identity_mapping_ |
whether the mapping bwwteen internal and external indices is identity | |
std::vector< int > | index_mapping_ |
mapping between internal and external indices. | |
flann::SearchParams | param_k_ |
The KdTree search parameters for K-nearest neighbors. | |
flann::SearchParams | param_radius_ |
The KdTree search parameters for radius search. | |
int | total_nr_points_ |
The total size of the data (either equal to the number of points in the input cloud or to the number of indices - if passed). |
KdTreeFLANN is a generic type of 3D spatial locator using kD-tree structures. The class is making use of the FLANN (Fast Library for Approximate Nearest Neighbor) project by Marius Muja and David Lowe.
Definition at line 57 of file kdtree_flann.h.
typedef boost::shared_ptr<const KdTreeFLANN<PointT> > pcl::KdTreeFLANN< PointT, Dist >::ConstPtr |
Reimplemented from pcl::KdTree< PointT >.
Definition at line 78 of file kdtree_flann.h.
typedef flann::Index<Dist> pcl::KdTreeFLANN< PointT, Dist >::FLANNIndex |
Definition at line 74 of file kdtree_flann.h.
typedef boost::shared_ptr<const std::vector<int> > pcl::KdTreeFLANN< PointT, Dist >::IndicesConstPtr |
Reimplemented from pcl::KdTree< PointT >.
Definition at line 72 of file kdtree_flann.h.
typedef boost::shared_ptr<std::vector<int> > pcl::KdTreeFLANN< PointT, Dist >::IndicesPtr |
Reimplemented from pcl::KdTree< PointT >.
Definition at line 71 of file kdtree_flann.h.
typedef KdTree<PointT>::PointCloud pcl::KdTreeFLANN< PointT, Dist >::PointCloud |
Reimplemented from pcl::KdTree< PointT >.
Definition at line 68 of file kdtree_flann.h.
typedef KdTree<PointT>::PointCloudConstPtr pcl::KdTreeFLANN< PointT, Dist >::PointCloudConstPtr |
Reimplemented from pcl::KdTree< PointT >.
Definition at line 69 of file kdtree_flann.h.
typedef boost::shared_ptr<KdTreeFLANN<PointT> > pcl::KdTreeFLANN< PointT, Dist >::Ptr |
Reimplemented from pcl::KdTree< PointT >.
Definition at line 77 of file kdtree_flann.h.
pcl::KdTreeFLANN< PointT, Dist >::KdTreeFLANN | ( | bool | sorted = true | ) | [inline] |
Default Constructor for KdTreeFLANN.
[in] | sorted | set to true if the application that the tree will be used for requires sorted nearest neighbor indices (default). False otherwise. |
By setting sorted to false, the radiusSearch operations will be faster.
Definition at line 85 of file kdtree_flann.h.
pcl::KdTreeFLANN< PointT, Dist >::KdTreeFLANN | ( | const KdTreeFLANN< PointT > & | k | ) | [inline] |
Copy constructor.
[in] | tree | the tree to copy into this |
Definition at line 98 of file kdtree_flann.h.
virtual pcl::KdTreeFLANN< PointT, Dist >::~KdTreeFLANN | ( | ) | [inline, virtual] |
Destructor for KdTreeFLANN. Deletes all allocated data arrays and destroys the kd-tree structures.
Definition at line 151 of file kdtree_flann.h.
void pcl::KdTreeFLANN< PointT, Dist >::cleanup | ( | ) | [private] |
Internal cleanup method.
Definition at line 161 of file kdtree_flann.hpp.
void pcl::KdTreeFLANN< PointT, Dist >::convertCloudToArray | ( | const PointCloud & | cloud | ) | [private] |
Converts a PointCloud to the internal FLANN point array representation. Returns the number of points.
cloud | the PointCloud |
Definition at line 180 of file kdtree_flann.hpp.
void pcl::KdTreeFLANN< PointT, Dist >::convertCloudToArray | ( | const PointCloud & | cloud, |
const std::vector< int > & | indices | ||
) | [private] |
Converts a PointCloud with a given set of indices to the internal FLANN point array representation. Returns the number of points.
[in] | cloud | the PointCloud data |
[in] | indices | the point cloud indices |
Definition at line 214 of file kdtree_flann.hpp.
virtual std::string pcl::KdTreeFLANN< PointT, Dist >::getName | ( | ) | const [inline, private, virtual] |
Class getName method.
Implements pcl::KdTree< PointT >.
Definition at line 224 of file kdtree_flann.h.
Ptr pcl::KdTreeFLANN< PointT, Dist >::makeShared | ( | ) | [inline] |
Definition at line 146 of file kdtree_flann.h.
int pcl::KdTreeFLANN< PointT, Dist >::nearestKSearch | ( | const PointT & | point, |
int | k, | ||
std::vector< int > & | k_indices, | ||
std::vector< float > & | k_sqr_distances | ||
) | const [virtual] |
Search for k-nearest neighbors for the given query point.
[in] | point | a given valid (i.e., finite) query point |
[in] | k | the number of neighbors to search for |
[out] | k_indices | the resultant indices of the neighboring points (must be resized to k a priori!) |
[out] | k_sqr_distances | the resultant squared distances to the neighboring points (must be resized to k a priori!) |
asserts | in debug mode if the index is not between 0 and the maximum number of points |
Implements pcl::KdTree< PointT >.
Definition at line 79 of file kdtree_flann.hpp.
KdTreeFLANN<PointT>& pcl::KdTreeFLANN< PointT, Dist >::operator= | ( | const KdTreeFLANN< PointT > & | k | ) | [inline] |
Copy operator.
[in] | tree | the tree to copy into this |
Definition at line 113 of file kdtree_flann.h.
int pcl::KdTreeFLANN< PointT, Dist >::radiusSearch | ( | const PointT & | point, |
double | radius, | ||
std::vector< int > & | k_indices, | ||
std::vector< float > & | k_sqr_distances, | ||
unsigned int | max_nn = 0 |
||
) | const [virtual] |
Search for all the nearest neighbors of the query point in a given radius.
[in] | point | a given valid (i.e., finite) query point |
[in] | radius | the radius of the sphere bounding all of p_q's neighbors |
[out] | k_indices | the resultant indices of the neighboring points |
[out] | k_sqr_distances | the resultant squared distances to the neighboring points |
[in] | max_nn | if given, bounds the maximum returned neighbors to this value. If max_nn is set to 0 or to a number higher than the number of points in the input cloud, all neighbors in radius will be returned. |
asserts | in debug mode if the index is not between 0 and the maximum number of points |
Implements pcl::KdTree< PointT >.
Definition at line 116 of file kdtree_flann.hpp.
void pcl::KdTreeFLANN< PointT, Dist >::setEpsilon | ( | float | eps | ) | [inline, virtual] |
Set the search epsilon precision (error bound) for nearest neighbors searches.
[in] | eps | precision (error bound) for nearest neighbors searches |
Reimplemented from pcl::KdTree< PointT >.
Definition at line 131 of file kdtree_flann.h.
void pcl::KdTreeFLANN< PointT, Dist >::setInputCloud | ( | const PointCloudConstPtr & | cloud, |
const IndicesConstPtr & | indices = IndicesConstPtr () |
||
) | [virtual] |
Provide a pointer to the input dataset.
[in] | cloud | the const boost shared pointer to a PointCloud message |
[in] | indices | the point indices subset that is to be used from cloud - if NULL the whole cloud is used |
Reimplemented from pcl::KdTree< PointT >.
Definition at line 46 of file kdtree_flann.hpp.
void pcl::KdTreeFLANN< PointT, Dist >::setSortedResults | ( | bool | sorted | ) | [inline] |
Definition at line 139 of file kdtree_flann.h.
float* pcl::KdTreeFLANN< PointT, Dist >::cloud_ [private] |
Internal pointer to data.
Definition at line 230 of file kdtree_flann.h.
int pcl::KdTreeFLANN< PointT, Dist >::dim_ [private] |
Tree dimensionality (i.e. the number of dimensions per point).
Definition at line 239 of file kdtree_flann.h.
FLANNIndex* pcl::KdTreeFLANN< PointT, Dist >::flann_index_ [private] |
A FLANN index object.
Definition at line 227 of file kdtree_flann.h.
bool pcl::KdTreeFLANN< PointT, Dist >::identity_mapping_ [private] |
whether the mapping bwwteen internal and external indices is identity
Definition at line 236 of file kdtree_flann.h.
std::vector<int> pcl::KdTreeFLANN< PointT, Dist >::index_mapping_ [private] |
mapping between internal and external indices.
Definition at line 233 of file kdtree_flann.h.
flann::SearchParams pcl::KdTreeFLANN< PointT, Dist >::param_k_ [private] |
The KdTree search parameters for K-nearest neighbors.
Definition at line 245 of file kdtree_flann.h.
flann::SearchParams pcl::KdTreeFLANN< PointT, Dist >::param_radius_ [private] |
The KdTree search parameters for radius search.
Definition at line 248 of file kdtree_flann.h.
int pcl::KdTreeFLANN< PointT, Dist >::total_nr_points_ [private] |
The total size of the data (either equal to the number of points in the input cloud or to the number of indices - if passed).
Definition at line 242 of file kdtree_flann.h.