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 boost::shared_ptr < KdTreeFLANN< PointT > > | Ptr |
Public Member Functions | |
KdTreeFLANN (const KdTreeFLANN &tree) | |
Copy constructor. | |
KdTreeFLANN (bool sorted=true) | |
Constructor for KdTree. | |
Ptr | makeShared () const |
int | 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 (zero-copy). | |
int | nearestKSearch (const PointCloud &cloud, int index, int k, std::vector< int > &k_indices, std::vector< float > &k_distances) |
Search for k-nearest neighbors for the given query point. | |
int | nearestKSearch (const PointT &point, int k, std::vector< int > &k_indices, std::vector< float > &k_distances) |
Search for k-nearest neighbors for the given query point. | |
KdTreeFLANN & | operator= (const KdTreeFLANN &tree) |
int | radiusSearch (int index, double radius, std::vector< int > &k_indices, std::vector< float > &k_distances, int max_nn=-1) const |
Search for all the nearest neighbors of the query point in a given radius (zero-copy). | |
int | radiusSearch (const PointCloud &cloud, int index, double radius, std::vector< int > &k_indices, std::vector< float > &k_distances, int max_nn=-1) const |
Search for all the nearest neighbors of the query point in a given radius. | |
int | radiusSearch (const PointT &point, double radius, std::vector< int > &k_indices, std::vector< float > &k_distances, int max_nn=-1) const |
Search for all the nearest neighbors of the query point in a given radius. | |
void | setInputCloud (const PointCloudConstPtr &cloud, const IndicesConstPtr &indices=IndicesConstPtr()) |
Provide a pointer to the input dataset. | |
void | shallowCopy (const KdTreeFLANN &tree) |
virtual | ~KdTreeFLANN () |
Destructor for KdTreeFLANN. Deletes all allocated data arrays and destroys the kd-tree structures. | |
Private Types | |
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 KdTree< PointT > ::PointCloud | PointCloud |
typedef KdTree< PointT > ::PointCloudConstPtr | PointCloudConstPtr |
Private Member Functions | |
void | cleanup () |
Internal cleanup method. | |
void | convertCloudToArray (const PointCloud &ros_cloud, const std::vector< int > &indices) |
Converts a ROS PointCloud message with a given set of indices to the internal FLANN point array representation. Returns the number of points. | |
void | convertCloudToArray (const PointCloud &ros_cloud) |
Converts a ROS PointCloud message to the internal FLANN point array representation. Returns the number of points. | |
virtual std::string | getName () const |
Class getName method. | |
void | initData () |
Simple initialization method for internal data buffers. | |
bool | initParameters () |
Simple initialization method for internal parameters. | |
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. | |
std::vector< int > | index_mapping_ |
mapping between internal and external indices. | |
boost::mutex | m_lock_ |
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 56 of file kdtree_flann.h.
typedef boost::shared_ptr<const KdTreeFLANN<PointT> > pcl::KdTreeFLANN< PointT >::ConstPtr |
Reimplemented from pcl::KdTree< PointT >.
Definition at line 75 of file kdtree_flann.h.
typedef flann::Index< flann::L2_Simple<float> > pcl::KdTreeFLANN< PointT >::FLANNIndex [private] |
Definition at line 70 of file kdtree_flann.h.
typedef boost::shared_ptr<const std::vector<int> > pcl::KdTreeFLANN< PointT >::IndicesConstPtr [private] |
Reimplemented from pcl::KdTree< PointT >.
Definition at line 68 of file kdtree_flann.h.
typedef boost::shared_ptr<std::vector<int> > pcl::KdTreeFLANN< PointT >::IndicesPtr [private] |
Reimplemented from pcl::KdTree< PointT >.
Definition at line 67 of file kdtree_flann.h.
typedef KdTree<PointT>::PointCloud pcl::KdTreeFLANN< PointT >::PointCloud [private] |
Reimplemented from pcl::KdTree< PointT >.
Definition at line 64 of file kdtree_flann.h.
typedef KdTree<PointT>::PointCloudConstPtr pcl::KdTreeFLANN< PointT >::PointCloudConstPtr [private] |
Reimplemented from pcl::KdTree< PointT >.
Definition at line 65 of file kdtree_flann.h.
typedef boost::shared_ptr<KdTreeFLANN<PointT> > pcl::KdTreeFLANN< PointT >::Ptr |
Reimplemented from pcl::KdTree< PointT >.
Definition at line 74 of file kdtree_flann.h.
pcl::KdTreeFLANN< PointT >::KdTreeFLANN | ( | bool | sorted = true |
) | [inline] |
Constructor for KdTree.
Definition at line 85 of file kdtree_flann.h.
pcl::KdTreeFLANN< PointT >::KdTreeFLANN | ( | const KdTreeFLANN< PointT > & | tree | ) | [inline] |
Copy constructor.
This copy constructor does shallow copy of the tree, the only reason why it's needed is because boost::mutex is non-copyable, so the default copy constructor would not work
Definition at line 97 of file kdtree_flann.h.
virtual pcl::KdTreeFLANN< PointT >::~KdTreeFLANN | ( | ) | [inline, virtual] |
Destructor for KdTreeFLANN. Deletes all allocated data arrays and destroys the kd-tree structures.
Definition at line 125 of file kdtree_flann.h.
void pcl::KdTreeFLANN< PointT >::cleanup | ( | ) | [inline, private] |
Internal cleanup method.
Definition at line 165 of file kdtree_flann.hpp.
void pcl::KdTreeFLANN< PointT >::convertCloudToArray | ( | const PointCloud & | ros_cloud, | |
const std::vector< int > & | indices | |||
) | [inline, private] |
Converts a ROS PointCloud message with a given set of indices to the internal FLANN point array representation. Returns the number of points.
ros_cloud | the ROS PointCloud message | |
indices | the point cloud indices |
Definition at line 233 of file kdtree_flann.hpp.
void pcl::KdTreeFLANN< PointT >::convertCloudToArray | ( | const PointCloud & | ros_cloud | ) | [inline, private] |
Converts a ROS PointCloud message to the internal FLANN point array representation. Returns the number of points.
ros_cloud | the ROS PointCloud message |
Definition at line 202 of file kdtree_flann.hpp.
virtual std::string pcl::KdTreeFLANN< PointT >::getName | ( | ) | const [inline, private, virtual] |
Class getName method.
Implements pcl::KdTree< PointT >.
Definition at line 278 of file kdtree_flann.h.
void pcl::KdTreeFLANN< PointT >::initData | ( | ) | [inline, private] |
Simple initialization method for internal data buffers.
Definition at line 193 of file kdtree_flann.hpp.
bool pcl::KdTreeFLANN< PointT >::initParameters | ( | ) | [inline, private] |
Simple initialization method for internal parameters.
Definition at line 183 of file kdtree_flann.hpp.
Ptr pcl::KdTreeFLANN< PointT >::makeShared | ( | ) | const [inline] |
Definition at line 102 of file kdtree_flann.h.
int pcl::KdTreeFLANN< PointT >::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 (zero-copy).
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 | |
k | the number of neighbors to search for | |
k_indices | the resultant indices of the neighboring points (must be resized to k a priori!) | |
k_distances | the resultant squared distances to the neighboring points (must be resized to k a priori!) |
Implements pcl::KdTree< PointT >.
Definition at line 176 of file kdtree_flann.h.
int pcl::KdTreeFLANN< PointT >::nearestKSearch | ( | const PointCloud & | cloud, | |
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.
cloud | the point cloud data | |
index | the index in cloud representing the query point | |
k | the number of neighbors to search for | |
k_indices | the resultant indices of the neighboring points (must be resized to k a priori!) | |
k_distances | the resultant squared distances to the neighboring points (must be resized to k a priori!) |
Implements pcl::KdTree< PointT >.
Definition at line 158 of file kdtree_flann.h.
int pcl::KdTreeFLANN< PointT >::nearestKSearch | ( | const PointT & | point, | |
int | k, | |||
std::vector< int > & | k_indices, | |||
std::vector< float > & | k_distances | |||
) | [inline, virtual] |
Search for k-nearest neighbors for the given query point.
point | the given query point | |
k | the number of neighbors to search for | |
k_indices | the resultant indices of the neighboring points (must be resized to k a priori!) | |
k_distances | the resultant squared distances to the neighboring points (must be resized to k a priori!) |
Implements pcl::KdTree< PointT >.
Definition at line 76 of file kdtree_flann.hpp.
KdTreeFLANN& pcl::KdTreeFLANN< PointT >::operator= | ( | const KdTreeFLANN< PointT > & | tree | ) | [inline] |
Definition at line 104 of file kdtree_flann.h.
int pcl::KdTreeFLANN< PointT >::radiusSearch | ( | int | index, | |
double | radius, | |||
std::vector< int > & | k_indices, | |||
std::vector< float > & | k_distances, | |||
int | max_nn = -1 | |||
) | const [inline, virtual] |
Search for all the nearest neighbors of the query point in a given radius (zero-copy).
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 | |
radius | the radius of the sphere bounding all of p_q's neighbors | |
k_indices | the resultant indices of the neighboring points | |
k_distances | the resultant squared distances to the neighboring points | |
max_nn | if given, bounds the maximum returned neighbors to this value |
Implements pcl::KdTree< PointT >.
Definition at line 233 of file kdtree_flann.h.
int pcl::KdTreeFLANN< PointT >::radiusSearch | ( | const PointCloud & | cloud, | |
int | index, | |||
double | radius, | |||
std::vector< int > & | k_indices, | |||
std::vector< float > & | k_distances, | |||
int | max_nn = -1 | |||
) | const [inline, virtual] |
Search for all the nearest neighbors of the query point in a given radius.
cloud | the point cloud data | |
index | the index in cloud representing the query point | |
radius | the radius of the sphere bounding all of p_q's neighbors | |
k_indices | the resultant indices of the neighboring points | |
k_distances | the resultant squared distances to the neighboring points | |
max_nn | if given, bounds the maximum returned neighbors to this value |
Implements pcl::KdTree< PointT >.
Definition at line 214 of file kdtree_flann.h.
int pcl::KdTreeFLANN< PointT >::radiusSearch | ( | const PointT & | point, | |
double | radius, | |||
std::vector< int > & | k_indices, | |||
std::vector< float > & | k_distances, | |||
int | max_nn = -1 | |||
) | const [inline, virtual] |
Search for all the nearest neighbors of the query point in a given radius.
point | the given query point | |
radius | the radius of the sphere bounding all of p_q's neighbors | |
k_indices | the resultant indices of the neighboring points | |
k_distances | the resultant squared distances to the neighboring points | |
max_nn | if given, bounds the maximum returned neighbors to this value |
Implements pcl::KdTree< PointT >.
Definition at line 105 of file kdtree_flann.hpp.
void pcl::KdTreeFLANN< PointT >::setInputCloud | ( | const PointCloudConstPtr & | cloud, | |
const IndicesConstPtr & | indices = IndicesConstPtr() | |||
) | [inline, virtual] |
Provide a pointer to the input dataset.
cloud | the const boost shared pointer to a PointCloud message | |
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 45 of file kdtree_flann.hpp.
void pcl::KdTreeFLANN< PointT >::shallowCopy | ( | const KdTreeFLANN< PointT > & | tree | ) | [inline] |
Definition at line 114 of file kdtree_flann.h.
float* pcl::KdTreeFLANN< PointT >::cloud_ [private] |
Internal pointer to data.
Definition at line 286 of file kdtree_flann.h.
int pcl::KdTreeFLANN< PointT >::dim_ [private] |
Tree dimensionality (i.e. the number of dimensions per point).
Definition at line 292 of file kdtree_flann.h.
FLANNIndex* pcl::KdTreeFLANN< PointT >::flann_index_ [private] |
A FLANN index object.
Definition at line 283 of file kdtree_flann.h.
std::vector<int> pcl::KdTreeFLANN< PointT >::index_mapping_ [private] |
mapping between internal and external indices.
Definition at line 289 of file kdtree_flann.h.
boost::mutex pcl::KdTreeFLANN< PointT >::m_lock_ [private] |
Definition at line 280 of file kdtree_flann.h.