Public Types | Public Member Functions | Protected Attributes
pcl::search::KdTree< PointT > Class Template Reference

search::KdTree is a wrapper class which inherits the pcl::KdTree class for performing search functions using KdTree structure. KdTree 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.h>

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

List of all members.

Public Types

typedef boost::shared_ptr
< const KdTree< PointT > > 
ConstPtr
typedef boost::shared_ptr
< const std::vector< int > > 
IndicesConstPtr
typedef boost::shared_ptr
< std::vector< int > > 
IndicesPtr
typedef boost::shared_ptr
< const pcl::KdTreeFLANN
< PointT > > 
KdTreeFLANNConstPtr
typedef boost::shared_ptr
< pcl::KdTreeFLANN< PointT > > 
KdTreeFLANNPtr
typedef Search< PointT >
::PointCloud 
PointCloud
typedef Search< PointT >
::PointCloudConstPtr 
PointCloudConstPtr
typedef boost::shared_ptr
< const PointRepresentation
< PointT > > 
PointRepresentationConstPtr
typedef boost::shared_ptr
< KdTree< PointT > > 
Ptr

Public Member Functions

float getEpsilon () const
 Get the search epsilon precision (error bound) for nearest neighbors searches.
PointRepresentationConstPtr getPointRepresentation () const
 Get a pointer to the point representation used when converting points into k-D vectors.
 KdTree (bool sorted=true)
 Constructor for KdTree.
int nearestKSearch (const PointT &point, int k, std::vector< int > &k_indices, std::vector< float > &k_sqr_distances) const
 Search for the k-nearest neighbors for the given query point.
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 setPointRepresentation (const PointRepresentationConstPtr &point_representation)
 Provide a pointer to the point representation to use to convert points into k-D vectors.
void setSortedResults (bool sorted_results)
 Sets whether the results have to be sorted or not.
virtual ~KdTree ()
 Destructor for KdTree.

Protected Attributes

KdTreeFLANNPtr tree_
 A pointer to the internal KdTreeFLANN object.

Detailed Description

template<typename PointT>
class pcl::search::KdTree< PointT >

search::KdTree is a wrapper class which inherits the pcl::KdTree class for performing search functions using KdTree structure. KdTree 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

Definition at line 62 of file search/include/pcl/search/kdtree.h.


Member Typedef Documentation

template<typename PointT>
typedef boost::shared_ptr<const KdTree<PointT> > pcl::search::KdTree< PointT >::ConstPtr

Reimplemented from pcl::search::Search< PointT >.

Definition at line 80 of file search/include/pcl/search/kdtree.h.

template<typename PointT>
typedef boost::shared_ptr<const std::vector<int> > pcl::search::KdTree< PointT >::IndicesConstPtr

Reimplemented from pcl::search::Search< PointT >.

Definition at line 69 of file search/include/pcl/search/kdtree.h.

template<typename PointT>
typedef boost::shared_ptr<std::vector<int> > pcl::search::KdTree< PointT >::IndicesPtr

Reimplemented from pcl::search::Search< PointT >.

Definition at line 68 of file search/include/pcl/search/kdtree.h.

template<typename PointT>
typedef boost::shared_ptr<const pcl::KdTreeFLANN<PointT> > pcl::search::KdTree< PointT >::KdTreeFLANNConstPtr

Definition at line 83 of file search/include/pcl/search/kdtree.h.

template<typename PointT>
typedef boost::shared_ptr<pcl::KdTreeFLANN<PointT> > pcl::search::KdTree< PointT >::KdTreeFLANNPtr

Definition at line 82 of file search/include/pcl/search/kdtree.h.

template<typename PointT>
typedef Search<PointT>::PointCloud pcl::search::KdTree< PointT >::PointCloud

Reimplemented from pcl::search::Search< PointT >.

Definition at line 65 of file search/include/pcl/search/kdtree.h.

Reimplemented from pcl::search::Search< PointT >.

Definition at line 66 of file search/include/pcl/search/kdtree.h.

template<typename PointT>
typedef boost::shared_ptr<const PointRepresentation<PointT> > pcl::search::KdTree< PointT >::PointRepresentationConstPtr

Definition at line 84 of file search/include/pcl/search/kdtree.h.

template<typename PointT>
typedef boost::shared_ptr<KdTree<PointT> > pcl::search::KdTree< PointT >::Ptr

Reimplemented from pcl::search::Search< PointT >.

Definition at line 79 of file search/include/pcl/search/kdtree.h.


Constructor & Destructor Documentation

template<typename PointT >
pcl::search::KdTree< PointT >::KdTree ( bool  sorted = true)

Constructor for KdTree.

Parameters:
[in]sortedset to true if the nearest neighbor search results need to be sorted in ascending order based on their distance to the query point

Definition at line 46 of file kdtree.hpp.

template<typename PointT>
virtual pcl::search::KdTree< PointT >::~KdTree ( ) [inline, virtual]

Destructor for KdTree.

Definition at line 97 of file search/include/pcl/search/kdtree.h.


Member Function Documentation

template<typename PointT>
float pcl::search::KdTree< PointT >::getEpsilon ( ) const [inline]

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

Definition at line 128 of file search/include/pcl/search/kdtree.h.

template<typename PointT>
PointRepresentationConstPtr pcl::search::KdTree< PointT >::getPointRepresentation ( ) const [inline]

Get a pointer to the point representation used when converting points into k-D vectors.

Definition at line 109 of file search/include/pcl/search/kdtree.h.

template<typename PointT>
int pcl::search::KdTree< PointT >::nearestKSearch ( const PointT point,
int  k,
std::vector< int > &  k_indices,
std::vector< float > &  k_sqr_distances 
) const [virtual]

Search for the k-nearest neighbors for the given query point.

Parameters:
[in]pointthe given 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

Implements pcl::search::Search< PointT >.

Definition at line 88 of file kdtree.hpp.

template<typename PointT>
int pcl::search::KdTree< PointT >::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.

Parameters:
[in]pointthe given 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

Implements pcl::search::Search< PointT >.

Definition at line 97 of file kdtree.hpp.

template<typename PointT >
void pcl::search::KdTree< PointT >::setEpsilon ( float  eps)

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

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

Definition at line 70 of file kdtree.hpp.

template<typename PointT >
void pcl::search::KdTree< PointT >::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

Reimplemented from pcl::search::Search< PointT >.

Definition at line 77 of file kdtree.hpp.

template<typename PointT >
void pcl::search::KdTree< PointT >::setPointRepresentation ( const PointRepresentationConstPtr point_representation)

Provide a pointer to the point representation to use to convert points into k-D vectors.

Parameters:
[in]point_representationthe const boost shared pointer to a PointRepresentation

Definition at line 54 of file kdtree.hpp.

template<typename PointT >
void pcl::search::KdTree< PointT >::setSortedResults ( bool  sorted_results) [virtual]

Sets whether the results have to be sorted or not.

Parameters:
[in]sorted_resultsset to true if the radius search results should be sorted

Reimplemented from pcl::search::Search< PointT >.

Definition at line 62 of file kdtree.hpp.


Member Data Documentation

template<typename PointT>
KdTreeFLANNPtr pcl::search::KdTree< PointT >::tree_ [protected]

A pointer to the internal KdTreeFLANN object.

Definition at line 171 of file search/include/pcl/search/kdtree.h.


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


pcl
Author(s): Open Perception
autogenerated on Wed Aug 26 2015 15:46:56