pcl::KdTreeFLANN< PointT > Class Template Reference

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>

Inheritance diagram for pcl::KdTreeFLANN< PointT >:
Inheritance graph
[legend]

List of all members.

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.
KdTreeFLANNoperator= (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).
FLANNIndexflann_index_
 A FLANN index object.
std::vector< int > index_mapping_
 mapping between internal and external indices.
boost::mutex m_lock_

Detailed Description

template<typename PointT>
class pcl::KdTreeFLANN< PointT >

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.

Note:
libFLANN is not thread safe, so we need mutices in places to make KdTreeFLANN thread safe.
Author:
Radu Bogdan Rusu

Definition at line 56 of file kdtree_flann.h.


Member Typedef Documentation

template<typename PointT>
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.

template<typename PointT>
typedef flann::Index< flann::L2_Simple<float> > pcl::KdTreeFLANN< PointT >::FLANNIndex [private]

Definition at line 70 of file kdtree_flann.h.

template<typename PointT>
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.

template<typename PointT>
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.

template<typename PointT>
typedef KdTree<PointT>::PointCloud pcl::KdTreeFLANN< PointT >::PointCloud [private]

Reimplemented from pcl::KdTree< PointT >.

Definition at line 64 of file kdtree_flann.h.

template<typename PointT>
typedef KdTree<PointT>::PointCloudConstPtr pcl::KdTreeFLANN< PointT >::PointCloudConstPtr [private]

Reimplemented from pcl::KdTree< PointT >.

Definition at line 65 of file kdtree_flann.h.

template<typename PointT>
typedef boost::shared_ptr<KdTreeFLANN<PointT> > pcl::KdTreeFLANN< PointT >::Ptr

Reimplemented from pcl::KdTree< PointT >.

Definition at line 74 of file kdtree_flann.h.


Constructor & Destructor Documentation

template<typename PointT>
pcl::KdTreeFLANN< PointT >::KdTreeFLANN ( bool  sorted = true  )  [inline]

Constructor for KdTree.

Note:
ATTENTION: This method breaks the 1-1 mapping between the indices returned using getNeighborsIndices and the ones from the cloud message ! When using this method, make sure to get the underlying point data using the getPoint method param cloud the point cloud data array param indices the point cloud indices Default Constructor for KdTreeFLANN.

Definition at line 85 of file kdtree_flann.h.

template<typename PointT>
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.

template<typename PointT>
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.


Member Function Documentation

template<typename PointT >
void pcl::KdTreeFLANN< PointT >::cleanup (  )  [inline, private]

Internal cleanup method.

Definition at line 165 of file kdtree_flann.hpp.

template<typename PointT >
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.

Note:
ATTENTION: This method breaks the 1-1 mapping between the indices returned using getNeighborsIndices and the ones from the ros_cloud message ! When using this method, make sure to get the underlying point data using the getPoint method
Parameters:
ros_cloud the ROS PointCloud message
indices the point cloud indices

Definition at line 233 of file kdtree_flann.hpp.

template<typename PointT >
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.

Parameters:
ros_cloud the ROS PointCloud message

Definition at line 202 of file kdtree_flann.hpp.

template<typename PointT>
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.

template<typename PointT >
void pcl::KdTreeFLANN< PointT >::initData (  )  [inline, private]

Simple initialization method for internal data buffers.

Definition at line 193 of file kdtree_flann.hpp.

template<typename PointT >
bool pcl::KdTreeFLANN< PointT >::initParameters (  )  [inline, private]

Simple initialization method for internal parameters.

Definition at line 183 of file kdtree_flann.hpp.

template<typename PointT>
Ptr pcl::KdTreeFLANN< PointT >::makeShared (  )  const [inline]

Definition at line 102 of file kdtree_flann.h.

template<typename PointT>
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).

Parameters:
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!)
Returns:
number of neighbors found

Implements pcl::KdTree< PointT >.

Definition at line 176 of file kdtree_flann.h.

template<typename PointT>
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.

Parameters:
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!)
Returns:
number of neighbors found

Implements pcl::KdTree< PointT >.

Definition at line 158 of file kdtree_flann.h.

template<typename PointT>
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.

Parameters:
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!)
Returns:
number of neighbors found

Implements pcl::KdTree< PointT >.

Definition at line 76 of file kdtree_flann.hpp.

template<typename PointT>
KdTreeFLANN& pcl::KdTreeFLANN< PointT >::operator= ( const KdTreeFLANN< PointT > &  tree  )  [inline]

Definition at line 104 of file kdtree_flann.h.

template<typename PointT>
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).

Parameters:
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
Returns:
number of neighbors found in radius

Implements pcl::KdTree< PointT >.

Definition at line 233 of file kdtree_flann.h.

template<typename PointT>
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.

Parameters:
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
Returns:
number of neighbors found in radius

Implements pcl::KdTree< PointT >.

Definition at line 214 of file kdtree_flann.h.

template<typename PointT>
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.

Parameters:
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
Returns:
number of neighbors found in radius

Implements pcl::KdTree< PointT >.

Definition at line 105 of file kdtree_flann.hpp.

template<typename PointT >
void pcl::KdTreeFLANN< PointT >::setInputCloud ( const PointCloudConstPtr cloud,
const IndicesConstPtr indices = IndicesConstPtr() 
) [inline, virtual]

Provide a pointer to the input dataset.

Parameters:
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.

template<typename PointT>
void pcl::KdTreeFLANN< PointT >::shallowCopy ( const KdTreeFLANN< PointT > &  tree  )  [inline]

Definition at line 114 of file kdtree_flann.h.


Member Data Documentation

template<typename PointT>
float* pcl::KdTreeFLANN< PointT >::cloud_ [private]

Internal pointer to data.

Definition at line 286 of file kdtree_flann.h.

template<typename PointT>
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.

template<typename PointT>
FLANNIndex* pcl::KdTreeFLANN< PointT >::flann_index_ [private]

A FLANN index object.

Definition at line 283 of file kdtree_flann.h.

template<typename PointT>
std::vector<int> pcl::KdTreeFLANN< PointT >::index_mapping_ [private]

mapping between internal and external indices.

Definition at line 289 of file kdtree_flann.h.

template<typename PointT>
boost::mutex pcl::KdTreeFLANN< PointT >::m_lock_ [private]

Definition at line 280 of file kdtree_flann.h.


The documentation for this class was generated from the following files:
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Defines


pcl
Author(s): See http://pcl.ros.org/authors for the complete list of authors.
autogenerated on Fri Jan 11 09:57:18 2013