Public Types | Public Member Functions | Private Member Functions | Private Attributes
pcl::KdTreeFLANN< PointT, Dist > 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, Dist >:
Inheritance graph
[legend]

List of all members.

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).
boost::shared_ptr< FLANNIndexflann_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.
boost::shared_ptr
< flann::SearchParams > 
param_k_
 The KdTree search parameters for K-nearest neighbors.
boost::shared_ptr
< 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).

Detailed Description

template<typename PointT, typename Dist = ::flann::L2_Simple<float>>
class pcl::KdTreeFLANN< PointT, Dist >

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.

Author:
Radu B. Rusu, Marius Muja

Definition at line 66 of file kdtree_flann.h.


Member Typedef Documentation

template<typename PointT, typename Dist = ::flann::L2_Simple<float>>
typedef boost::shared_ptr<const KdTreeFLANN<PointT> > pcl::KdTreeFLANN< PointT, Dist >::ConstPtr

Reimplemented from pcl::KdTree< PointT >.

Definition at line 87 of file kdtree_flann.h.

template<typename PointT, typename Dist = ::flann::L2_Simple<float>>
typedef ::flann::Index<Dist> pcl::KdTreeFLANN< PointT, Dist >::FLANNIndex

Definition at line 83 of file kdtree_flann.h.

template<typename PointT, typename Dist = ::flann::L2_Simple<float>>
typedef boost::shared_ptr<const std::vector<int> > pcl::KdTreeFLANN< PointT, Dist >::IndicesConstPtr

Reimplemented from pcl::KdTree< PointT >.

Definition at line 81 of file kdtree_flann.h.

template<typename PointT, typename Dist = ::flann::L2_Simple<float>>
typedef boost::shared_ptr<std::vector<int> > pcl::KdTreeFLANN< PointT, Dist >::IndicesPtr

Reimplemented from pcl::KdTree< PointT >.

Definition at line 80 of file kdtree_flann.h.

template<typename PointT, typename Dist = ::flann::L2_Simple<float>>
typedef KdTree<PointT>::PointCloud pcl::KdTreeFLANN< PointT, Dist >::PointCloud

Reimplemented from pcl::KdTree< PointT >.

Definition at line 77 of file kdtree_flann.h.

template<typename PointT, typename Dist = ::flann::L2_Simple<float>>
typedef KdTree<PointT>::PointCloudConstPtr pcl::KdTreeFLANN< PointT, Dist >::PointCloudConstPtr

Reimplemented from pcl::KdTree< PointT >.

Definition at line 78 of file kdtree_flann.h.

template<typename PointT, typename Dist = ::flann::L2_Simple<float>>
typedef boost::shared_ptr<KdTreeFLANN<PointT> > pcl::KdTreeFLANN< PointT, Dist >::Ptr

Reimplemented from pcl::KdTree< PointT >.

Definition at line 86 of file kdtree_flann.h.


Constructor & Destructor Documentation

template<typename PointT , typename Dist >
pcl::KdTreeFLANN< PointT, Dist >::KdTreeFLANN ( bool  sorted = true)

Default Constructor for KdTreeFLANN.

Parameters:
[in]sortedset 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 49 of file kdtree_flann.hpp.

template<typename PointT, typename Dist >
pcl::KdTreeFLANN< PointT, Dist >::KdTreeFLANN ( const KdTreeFLANN< PointT > &  k)

Copy constructor.

Parameters:
[in]treethe tree to copy into this

Definition at line 61 of file kdtree_flann.hpp.

template<typename PointT, typename Dist = ::flann::L2_Simple<float>>
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 133 of file kdtree_flann.h.


Member Function Documentation

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

Internal cleanup method.

Definition at line 214 of file kdtree_flann.hpp.

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

Parameters:
cloudthe PointCloud

Definition at line 230 of file kdtree_flann.hpp.

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

Parameters:
[in]cloudthe PointCloud data
[in]indicesthe point cloud indices

Definition at line 264 of file kdtree_flann.hpp.

template<typename PointT, typename Dist = ::flann::L2_Simple<float>>
virtual std::string pcl::KdTreeFLANN< PointT, Dist >::getName ( ) const [inline, private, virtual]

Class getName method.

Implements pcl::KdTree< PointT >.

Definition at line 206 of file kdtree_flann.h.

template<typename PointT, typename Dist = ::flann::L2_Simple<float>>
Ptr pcl::KdTreeFLANN< PointT, Dist >::makeShared ( ) [inline]

Definition at line 128 of file kdtree_flann.h.

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

Attention:
This method does not do any bounds checking for the input index (i.e., index >= cloud.points.size () || index < 0), and assumes valid (i.e., finite) data.
Parameters:
[in]pointa given valid (i.e., finite) query point
[in]kthe number of neighbors to search for
[out]k_indicesthe resultant indices of the neighboring points (must be resized to k a priori!)
[out]k_sqr_distancesthe resultant squared distances to the neighboring points (must be resized to k a priori!)
Returns:
number of neighbors found
Exceptions:
assertsin debug mode if the index is not between 0 and the maximum number of points

Implements pcl::KdTree< PointT >.

Definition at line 132 of file kdtree_flann.hpp.

template<typename PointT, typename Dist = ::flann::L2_Simple<float>>
KdTreeFLANN<PointT>& pcl::KdTreeFLANN< PointT, Dist >::operator= ( const KdTreeFLANN< PointT > &  k) [inline]

Copy operator.

Parameters:
[in]treethe tree to copy into this

Definition at line 105 of file kdtree_flann.h.

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

Attention:
This method does not do any bounds checking for the input index (i.e., index >= cloud.points.size () || index < 0), and assumes valid (i.e., finite) data.
Parameters:
[in]pointa given valid (i.e., finite) query point
[in]radiusthe radius of the sphere bounding all of p_q's neighbors
[out]k_indicesthe resultant indices of the neighboring points
[out]k_sqr_distancesthe resultant squared distances to the neighboring points
[in]max_nnif 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.
Returns:
number of neighbors found in radius
Exceptions:
assertsin debug mode if the index is not between 0 and the maximum number of points

Implements pcl::KdTree< PointT >.

Definition at line 169 of file kdtree_flann.hpp.

template<typename PointT , typename Dist >
void pcl::KdTreeFLANN< PointT, Dist >::setEpsilon ( float  eps) [virtual]

Set the search epsilon precision (error bound) for nearest neighbors searches.

Parameters:
[in]epsprecision (error bound) for nearest neighbors searches

Reimplemented from pcl::KdTree< PointT >.

Definition at line 74 of file kdtree_flann.hpp.

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

Provide a pointer to the input dataset.

Parameters:
[in]cloudthe const boost shared pointer to a PointCloud message
[in]indicesthe 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 92 of file kdtree_flann.hpp.

template<typename PointT , typename Dist >
void pcl::KdTreeFLANN< PointT, Dist >::setSortedResults ( bool  sorted)

Definition at line 83 of file kdtree_flann.hpp.


Member Data Documentation

template<typename PointT, typename Dist = ::flann::L2_Simple<float>>
float* pcl::KdTreeFLANN< PointT, Dist >::cloud_ [private]

Internal pointer to data.

Definition at line 212 of file kdtree_flann.h.

template<typename PointT, typename Dist = ::flann::L2_Simple<float>>
int pcl::KdTreeFLANN< PointT, Dist >::dim_ [private]

Tree dimensionality (i.e. the number of dimensions per point).

Definition at line 221 of file kdtree_flann.h.

template<typename PointT, typename Dist = ::flann::L2_Simple<float>>
boost::shared_ptr<FLANNIndex> pcl::KdTreeFLANN< PointT, Dist >::flann_index_ [private]

A FLANN index object.

Definition at line 209 of file kdtree_flann.h.

template<typename PointT, typename Dist = ::flann::L2_Simple<float>>
bool pcl::KdTreeFLANN< PointT, Dist >::identity_mapping_ [private]

whether the mapping bwwteen internal and external indices is identity

Definition at line 218 of file kdtree_flann.h.

template<typename PointT, typename Dist = ::flann::L2_Simple<float>>
std::vector<int> pcl::KdTreeFLANN< PointT, Dist >::index_mapping_ [private]

mapping between internal and external indices.

Definition at line 215 of file kdtree_flann.h.

template<typename PointT, typename Dist = ::flann::L2_Simple<float>>
boost::shared_ptr<flann::SearchParams> pcl::KdTreeFLANN< PointT, Dist >::param_k_ [private]

The KdTree search parameters for K-nearest neighbors.

Definition at line 227 of file kdtree_flann.h.

template<typename PointT, typename Dist = ::flann::L2_Simple<float>>
boost::shared_ptr<flann::SearchParams> pcl::KdTreeFLANN< PointT, Dist >::param_radius_ [private]

The KdTree search parameters for radius search.

Definition at line 230 of file kdtree_flann.h.

template<typename PointT, typename Dist = ::flann::L2_Simple<float>>
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 224 of file kdtree_flann.h.


The documentation for this class was generated from the following files:


pcl
Author(s): Open Perception
autogenerated on Wed Aug 26 2015 15:41:59