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 < Eigen::MatrixXf > > | ConstPtr |
typedef flann::Index < flann::L2_Simple< float > > | FLANNIndex |
typedef boost::shared_ptr < const std::vector< int > > | IndicesConstPtr |
typedef boost::shared_ptr < std::vector< int > > | IndicesPtr |
typedef pcl::PointCloud < Eigen::MatrixXf > | PointCloud |
typedef PointCloud::ConstPtr | PointCloudConstPtr |
typedef pcl::PointRepresentation < Eigen::MatrixXf > | PointRepresentation |
typedef boost::shared_ptr < const PointRepresentation > | PointRepresentationConstPtr |
typedef boost::shared_ptr < KdTreeFLANN< Eigen::MatrixXf > > | Ptr |
Public Member Functions | |
float | getEpsilon () const |
Get the search epsilon precision (error bound) for nearest neighbors searches. | |
IndicesConstPtr | getIndices () const |
Get a pointer to the vector of indices used. | |
PointCloudConstPtr | getInputCloud () const |
Get a pointer to the input point cloud dataset. | |
KdTreeFLANN (bool sorted=true) | |
Default Constructor for KdTreeFLANN. | |
KdTreeFLANN (const KdTreeFLANN< Eigen::MatrixXf > &k) | |
Copy constructor. | |
Ptr | makeShared () |
template<typename T > | |
int | nearestKSearch (const T &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. | |
int | nearestKSearch (const PointCloud &cloud, int index, int k, std::vector< int > &k_indices, std::vector< float > &k_sqr_distances) const |
Search for k-nearest neighbors for the given query point. | |
int | nearestKSearch (int index, int k, std::vector< int > &k_indices, std::vector< float > &k_sqr_distances) const |
Search for k-nearest neighbors for the given query point (zero-copy). | |
KdTreeFLANN & | operator= (const KdTreeFLANN< Eigen::MatrixXf > &k) |
Copy operator. | |
template<typename T > | |
int | radiusSearch (const T &point, double radius, std::vector< int > &k_indices, std::vector< float > &k_sqr_dists, unsigned int max_nn=0) const |
Search for all the nearest neighbors of the query point in a given radius. | |
int | radiusSearch (const PointCloud &cloud, int index, 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. | |
int | radiusSearch (int index, 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 (zero-copy). | |
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. | |
virtual | ~KdTreeFLANN () |
Destructor for KdTreeFLANN. Deletes all allocated data arrays and destroys the kd-tree structures. | |
Protected Attributes | |
float | epsilon_ |
Epsilon precision (error bound) for nearest neighbors searches. | |
IndicesConstPtr | indices_ |
A pointer to the vector of point indices to use. | |
PointCloudConstPtr | input_ |
The input point cloud dataset containing the points we need to use. | |
bool | sorted_ |
Return the radius search neighbours sorted. | |
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. | |
std::string | getName () const |
Class getName method. | |
template<typename Expr > | |
bool | isRowValid (const Expr &pt) const |
Check if a given expression is valid (i.e., contains only finite values) | |
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 258 of file kdtree_flann.h.
typedef boost::shared_ptr<const KdTreeFLANN<Eigen::MatrixXf> > pcl::KdTreeFLANN< Eigen::MatrixXf >::ConstPtr |
Definition at line 274 of file kdtree_flann.h.
typedef flann::Index<flann::L2_Simple<float> > pcl::KdTreeFLANN< Eigen::MatrixXf >::FLANNIndex |
Definition at line 267 of file kdtree_flann.h.
typedef boost::shared_ptr<const std::vector<int> > pcl::KdTreeFLANN< Eigen::MatrixXf >::IndicesConstPtr |
Definition at line 265 of file kdtree_flann.h.
typedef boost::shared_ptr<std::vector<int> > pcl::KdTreeFLANN< Eigen::MatrixXf >::IndicesPtr |
Definition at line 264 of file kdtree_flann.h.
typedef pcl::PointCloud<Eigen::MatrixXf> pcl::KdTreeFLANN< Eigen::MatrixXf >::PointCloud |
Definition at line 261 of file kdtree_flann.h.
typedef PointCloud::ConstPtr pcl::KdTreeFLANN< Eigen::MatrixXf >::PointCloudConstPtr |
Definition at line 262 of file kdtree_flann.h.
typedef pcl::PointRepresentation<Eigen::MatrixXf> pcl::KdTreeFLANN< Eigen::MatrixXf >::PointRepresentation |
Definition at line 269 of file kdtree_flann.h.
typedef boost::shared_ptr<const PointRepresentation> pcl::KdTreeFLANN< Eigen::MatrixXf >::PointRepresentationConstPtr |
Definition at line 270 of file kdtree_flann.h.
typedef boost::shared_ptr<KdTreeFLANN<Eigen::MatrixXf> > pcl::KdTreeFLANN< Eigen::MatrixXf >::Ptr |
Definition at line 273 of file kdtree_flann.h.
pcl::KdTreeFLANN< Eigen::MatrixXf >::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 281 of file kdtree_flann.h.
pcl::KdTreeFLANN< Eigen::MatrixXf >::KdTreeFLANN | ( | const KdTreeFLANN< Eigen::MatrixXf > & | k | ) | [inline] |
Copy constructor.
[in] | tree | the tree to copy into this |
Definition at line 294 of file kdtree_flann.h.
virtual pcl::KdTreeFLANN< Eigen::MatrixXf >::~KdTreeFLANN | ( | ) | [inline, virtual] |
Destructor for KdTreeFLANN. Deletes all allocated data arrays and destroys the kd-tree structures.
Definition at line 342 of file kdtree_flann.h.
void pcl::KdTreeFLANN< Eigen::MatrixXf >::cleanup | ( | ) | [inline, private] |
Internal cleanup method.
Definition at line 599 of file kdtree_flann.h.
void pcl::KdTreeFLANN< Eigen::MatrixXf >::convertCloudToArray | ( | const PointCloud & | cloud | ) | [inline, private] |
Converts a PointCloud to the internal FLANN point array representation. Returns the number of points.
cloud | the PointCloud |
Definition at line 634 of file kdtree_flann.h.
void pcl::KdTreeFLANN< Eigen::MatrixXf >::convertCloudToArray | ( | const PointCloud & | cloud, |
const std::vector< int > & | indices | ||
) | [inline, 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 675 of file kdtree_flann.h.
float pcl::KdTreeFLANN< Eigen::MatrixXf >::getEpsilon | ( | ) | const [inline] |
Get the search epsilon precision (error bound) for nearest neighbors searches.
Definition at line 591 of file kdtree_flann.h.
IndicesConstPtr pcl::KdTreeFLANN< Eigen::MatrixXf >::getIndices | ( | ) | const [inline] |
Get a pointer to the vector of indices used.
Definition at line 384 of file kdtree_flann.h.
PointCloudConstPtr pcl::KdTreeFLANN< Eigen::MatrixXf >::getInputCloud | ( | ) | const [inline] |
Get a pointer to the input point cloud dataset.
Definition at line 391 of file kdtree_flann.h.
std::string pcl::KdTreeFLANN< Eigen::MatrixXf >::getName | ( | ) | const [inline, private] |
Class getName method.
Definition at line 727 of file kdtree_flann.h.
bool pcl::KdTreeFLANN< Eigen::MatrixXf >::isRowValid | ( | const Expr & | pt | ) | const [inline, private] |
Check if a given expression is valid (i.e., contains only finite values)
[in] | pt | the expression to evaluate |
Definition at line 620 of file kdtree_flann.h.
Ptr pcl::KdTreeFLANN< Eigen::MatrixXf >::makeShared | ( | ) | [inline] |
Definition at line 337 of file kdtree_flann.h.
int pcl::KdTreeFLANN< Eigen::MatrixXf >::nearestKSearch | ( | const T & | point, |
int | k, | ||
std::vector< int > & | k_indices, | ||
std::vector< float > & | k_sqr_distances | ||
) | const [inline] |
Search for k-nearest neighbors for the given query point.
[in] | point | the given 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!) |
Definition at line 405 of file kdtree_flann.h.
int pcl::KdTreeFLANN< Eigen::MatrixXf >::nearestKSearch | ( | const PointCloud & | cloud, |
int | index, | ||
int | k, | ||
std::vector< int > & | k_indices, | ||
std::vector< float > & | k_sqr_distances | ||
) | const [inline] |
Search for k-nearest neighbors for the given query point.
[in] | cloud | the point cloud data |
[in] | index | the index in cloud representing the 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!) |
Definition at line 454 of file kdtree_flann.h.
int pcl::KdTreeFLANN< Eigen::MatrixXf >::nearestKSearch | ( | int | index, |
int | k, | ||
std::vector< int > & | k_indices, | ||
std::vector< float > & | k_sqr_distances | ||
) | const [inline] |
Search for k-nearest neighbors for the given query point (zero-copy).
[in] | index | the index representing the query point in the dataset given by setInputCloud if indices were given in setInputCloud, index will be the position in the indices vector |
[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!) |
Definition at line 471 of file kdtree_flann.h.
KdTreeFLANN& pcl::KdTreeFLANN< Eigen::MatrixXf >::operator= | ( | const KdTreeFLANN< Eigen::MatrixXf > & | k | ) | [inline] |
Copy operator.
[in] | tree | the tree to copy into this |
Definition at line 308 of file kdtree_flann.h.
int pcl::KdTreeFLANN< Eigen::MatrixXf >::radiusSearch | ( | const T & | point, |
double | radius, | ||
std::vector< int > & | k_indices, | ||
std::vector< float > & | k_sqr_dists, | ||
unsigned int | max_nn = 0 |
||
) | const [inline] |
Search for all the nearest neighbors of the query point in a given radius.
[in] | point | the given 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_dists | 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. |
Definition at line 497 of file kdtree_flann.h.
int pcl::KdTreeFLANN< Eigen::MatrixXf >::radiusSearch | ( | const PointCloud & | cloud, |
int | index, | ||
double | radius, | ||
std::vector< int > & | k_indices, | ||
std::vector< float > & | k_sqr_distances, | ||
unsigned int | max_nn = 0 |
||
) | const [inline] |
Search for all the nearest neighbors of the query point in a given radius.
[in] | cloud | the point cloud data |
[in] | index | the index in cloud representing the 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. |
Definition at line 554 of file kdtree_flann.h.
int pcl::KdTreeFLANN< Eigen::MatrixXf >::radiusSearch | ( | int | index, |
double | radius, | ||
std::vector< int > & | k_indices, | ||
std::vector< float > & | k_sqr_distances, | ||
unsigned int | max_nn = 0 |
||
) | const [inline] |
Search for all the nearest neighbors of the query point in a given radius (zero-copy).
[in] | index | the index representing the query point in the dataset given by setInputCloud if indices were given in setInputCloud, index will be the position in the indices vector |
[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. |
Definition at line 574 of file kdtree_flann.h.
void pcl::KdTreeFLANN< Eigen::MatrixXf >::setEpsilon | ( | float | eps | ) | [inline] |
Set the search epsilon precision (error bound) for nearest neighbors searches.
[in] | eps | precision (error bound) for nearest neighbors searches |
Definition at line 329 of file kdtree_flann.h.
void pcl::KdTreeFLANN< Eigen::MatrixXf >::setInputCloud | ( | const PointCloudConstPtr & | cloud, |
const IndicesConstPtr & | indices = IndicesConstPtr () |
||
) | [inline] |
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 |
Definition at line 352 of file kdtree_flann.h.
float* pcl::KdTreeFLANN< Eigen::MatrixXf >::cloud_ [private] |
Internal pointer to data.
Definition at line 733 of file kdtree_flann.h.
int pcl::KdTreeFLANN< Eigen::MatrixXf >::dim_ [private] |
Tree dimensionality (i.e. the number of dimensions per point).
Definition at line 742 of file kdtree_flann.h.
float pcl::KdTreeFLANN< Eigen::MatrixXf >::epsilon_ [protected] |
Epsilon precision (error bound) for nearest neighbors searches.
Definition at line 719 of file kdtree_flann.h.
FLANNIndex* pcl::KdTreeFLANN< Eigen::MatrixXf >::flann_index_ [private] |
A FLANN index object.
Definition at line 730 of file kdtree_flann.h.
bool pcl::KdTreeFLANN< Eigen::MatrixXf >::identity_mapping_ [private] |
whether the mapping bwwteen internal and external indices is identity
Definition at line 739 of file kdtree_flann.h.
std::vector<int> pcl::KdTreeFLANN< Eigen::MatrixXf >::index_mapping_ [private] |
mapping between internal and external indices.
Definition at line 736 of file kdtree_flann.h.
IndicesConstPtr pcl::KdTreeFLANN< Eigen::MatrixXf >::indices_ [protected] |
A pointer to the vector of point indices to use.
Definition at line 716 of file kdtree_flann.h.
PointCloudConstPtr pcl::KdTreeFLANN< Eigen::MatrixXf >::input_ [protected] |
The input point cloud dataset containing the points we need to use.
Definition at line 713 of file kdtree_flann.h.
flann::SearchParams pcl::KdTreeFLANN< Eigen::MatrixXf >::param_k_ [private] |
The KdTree search parameters for K-nearest neighbors.
Definition at line 745 of file kdtree_flann.h.
flann::SearchParams pcl::KdTreeFLANN< Eigen::MatrixXf >::param_radius_ [private] |
The KdTree search parameters for radius search.
Definition at line 748 of file kdtree_flann.h.
bool pcl::KdTreeFLANN< Eigen::MatrixXf >::sorted_ [protected] |
Return the radius search neighbours sorted.
Definition at line 722 of file kdtree_flann.h.
int pcl::KdTreeFLANN< Eigen::MatrixXf >::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 751 of file kdtree_flann.h.