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

KdTree represents the base spatial locator class for kd-tree implementations. More...

#include <kdtree.h>

Inheritance diagram for pcl::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 pcl::PointCloud< PointTPointCloud
typedef boost::shared_ptr
< const PointCloud
PointCloudConstPtr
typedef boost::shared_ptr
< PointCloud
PointCloudPtr
typedef
pcl::PointRepresentation
< PointT
PointRepresentation
typedef boost::shared_ptr
< const PointRepresentation
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.
IndicesConstPtr getIndices () const
 Get a pointer to the vector of indices used.
PointCloudConstPtr getInputCloud () const
 Get a pointer to the input point cloud dataset.
int getMinPts () const
 Get the minimum allowed number of k nearest neighbors points that a viable result must contain.
PointRepresentationConstPtr getPointRepresentation () const
 Get a pointer to the point representation used when converting points into k-D vectors.
 KdTree (bool sorted=true)
 Empty constructor for KdTree. Sets some internal values to their defaults.
virtual int nearestKSearch (const PointT &p_q, int k, std::vector< int > &k_indices, std::vector< float > &k_sqr_distances) const =0
 Search for k-nearest neighbors for the given query point.
virtual 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.
virtual 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).
template<typename PointTDiff >
int nearestKSearchT (const PointTDiff &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. This method accepts a different template parameter for the point type.
virtual int radiusSearch (const PointT &p_q, double radius, std::vector< int > &k_indices, std::vector< float > &k_sqr_distances, unsigned int max_nn=0) const =0
 Search for all the nearest neighbors of the query point in a given radius.
virtual 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.
virtual 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).
template<typename PointTDiff >
int radiusSearchT (const PointTDiff &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.
virtual void setEpsilon (float eps)
 Set the search epsilon precision (error bound) for nearest neighbors searches.
virtual void setInputCloud (const PointCloudConstPtr &cloud, const IndicesConstPtr &indices=IndicesConstPtr())
 Provide a pointer to the input dataset.
void setMinPts (int min_pts)
 Minimum allowed number of k nearest neighbors points that a viable result must contain.
void setPointRepresentation (const PointRepresentationConstPtr &point_representation)
 Provide a pointer to the point representation to use to convert points into k-D vectors.
virtual ~KdTree ()
 Destructor for KdTree. Deletes all allocated data arrays and destroys the kd-tree structures.

Protected Member Functions

virtual std::string getName () const =0
 Class getName method.

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.
int min_pts_
 Minimum allowed number of k nearest neighbors points that a viable result must contain.
PointRepresentationConstPtr point_representation_
 For converting different point structures into k-dimensional vectors for nearest-neighbor search.
bool sorted_
 Return the radius search neighbours sorted.

Detailed Description

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

KdTree represents the base spatial locator class for kd-tree implementations.

Author:
Radu B Rusu, Bastian Steder, Michael Dixon

Definition at line 56 of file kdtree/include/pcl/kdtree/kdtree.h.


Member Typedef Documentation

template<typename PointT>
typedef boost::shared_ptr<const KdTree<PointT> > pcl::KdTree< PointT >::ConstPtr
template<typename PointT>
typedef boost::shared_ptr<const std::vector<int> > pcl::KdTree< PointT >::IndicesConstPtr
template<typename PointT>
typedef boost::shared_ptr<std::vector<int> > pcl::KdTree< PointT >::IndicesPtr
template<typename PointT>
typedef pcl::PointCloud<PointT> pcl::KdTree< PointT >::PointCloud
template<typename PointT>
typedef boost::shared_ptr<const PointCloud> pcl::KdTree< PointT >::PointCloudConstPtr
template<typename PointT>
typedef boost::shared_ptr<PointCloud> pcl::KdTree< PointT >::PointCloudPtr

Definition at line 63 of file kdtree/include/pcl/kdtree/kdtree.h.

template<typename PointT>
typedef pcl::PointRepresentation<PointT> pcl::KdTree< PointT >::PointRepresentation

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

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

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

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

Constructor & Destructor Documentation

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

Empty constructor for KdTree. Sets some internal values to their defaults.

Parameters:
[in]sortedset to true if the application that the tree will be used for requires sorted nearest neighbor indices (default). False otherwise.

Definition at line 77 of file kdtree/include/pcl/kdtree/kdtree.h.

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

Destructor for KdTree. Deletes all allocated data arrays and destroys the kd-tree structures.

Definition at line 126 of file kdtree/include/pcl/kdtree/kdtree.h.


Member Function Documentation

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

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

Definition at line 328 of file kdtree/include/pcl/kdtree/kdtree.h.

template<typename PointT>
IndicesConstPtr pcl::KdTree< PointT >::getIndices ( ) const [inline]

Get a pointer to the vector of indices used.

Definition at line 96 of file kdtree/include/pcl/kdtree/kdtree.h.

template<typename PointT>
PointCloudConstPtr pcl::KdTree< PointT >::getInputCloud ( ) const [inline]

Get a pointer to the input point cloud dataset.

Definition at line 103 of file kdtree/include/pcl/kdtree/kdtree.h.

template<typename PointT>
int pcl::KdTree< PointT >::getMinPts ( ) const [inline]

Get the minimum allowed number of k nearest neighbors points that a viable result must contain.

Definition at line 344 of file kdtree/include/pcl/kdtree/kdtree.h.

template<typename PointT>
virtual std::string pcl::KdTree< PointT >::getName ( ) const [protected, pure virtual]
template<typename PointT>
PointRepresentationConstPtr pcl::KdTree< PointT >::getPointRepresentation ( ) const [inline]

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

Definition at line 120 of file kdtree/include/pcl/kdtree/kdtree.h.

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

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

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

Implemented in pcl::KdTreeFLANN< PointT, Dist >, pcl::KdTreeFLANN< PointTarget >, pcl::KdTreeFLANN< FeatureT >, pcl::KdTreeFLANN< GlobalDescriptorT >, and pcl::KdTreeFLANN< pcl::FPFHSignature33 >.

template<typename PointT>
virtual int pcl::KdTree< PointT >::nearestKSearch ( const PointCloud cloud,
int  index,
int  k,
std::vector< int > &  k_indices,
std::vector< float > &  k_sqr_distances 
) const [inline, 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]cloudthe point cloud data
[in]indexa valid index in cloud representing a 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

Definition at line 157 of file kdtree/include/pcl/kdtree/kdtree.h.

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

Search for k-nearest neighbors for the given query point (zero-copy).

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]indexa valid index representing a valid query point in the dataset given by setInputCloud. If indices were given in setInputCloud, index will be the position in the indices vector.
[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

Definition at line 204 of file kdtree/include/pcl/kdtree/kdtree.h.

template<typename PointT>
template<typename PointTDiff >
int pcl::KdTree< PointT >::nearestKSearchT ( const PointTDiff &  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. This method accepts a different template parameter for the point type.

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

Definition at line 174 of file kdtree/include/pcl/kdtree/kdtree.h.

template<typename PointT>
virtual int pcl::KdTree< PointT >::radiusSearch ( const PointT p_q,
double  radius,
std::vector< int > &  k_indices,
std::vector< float > &  k_sqr_distances,
unsigned int  max_nn = 0 
) const [pure virtual]

Search for all the nearest neighbors of the query point in a given radius.

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

Implemented in pcl::KdTreeFLANN< PointT, Dist >, pcl::KdTreeFLANN< PointTarget >, pcl::KdTreeFLANN< FeatureT >, pcl::KdTreeFLANN< GlobalDescriptorT >, and pcl::KdTreeFLANN< pcl::FPFHSignature33 >.

template<typename PointT>
virtual int pcl::KdTree< PointT >::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, 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]cloudthe point cloud data
[in]indexa valid index in cloud representing a 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

Definition at line 251 of file kdtree/include/pcl/kdtree/kdtree.h.

template<typename PointT>
virtual int pcl::KdTree< PointT >::radiusSearch ( int  index,
double  radius,
std::vector< int > &  k_indices,
std::vector< float > &  k_sqr_distances,
unsigned int  max_nn = 0 
) const [inline, virtual]

Search for all the nearest neighbors of the query point in a given radius (zero-copy).

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]indexa valid index representing a valid query point in the dataset given by setInputCloud. If indices were given in setInputCloud, index will be the position in the indices vector.
[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

Definition at line 302 of file kdtree/include/pcl/kdtree/kdtree.h.

template<typename PointT>
template<typename PointTDiff >
int pcl::KdTree< PointT >::radiusSearchT ( const PointTDiff &  point,
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.

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

Definition at line 270 of file kdtree/include/pcl/kdtree/kdtree.h.

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

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

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

Reimplemented in pcl::KdTreeFLANN< PointT, Dist >, pcl::KdTreeFLANN< PointTarget >, pcl::KdTreeFLANN< FeatureT >, pcl::KdTreeFLANN< GlobalDescriptorT >, and pcl::KdTreeFLANN< pcl::FPFHSignature33 >.

Definition at line 321 of file kdtree/include/pcl/kdtree/kdtree.h.

template<typename PointT>
virtual void pcl::KdTree< PointT >::setInputCloud ( const PointCloudConstPtr cloud,
const IndicesConstPtr indices = IndicesConstPtr () 
) [inline, 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 in pcl::KdTreeFLANN< PointT, Dist >, pcl::KdTreeFLANN< PointTarget >, pcl::KdTreeFLANN< FeatureT >, pcl::KdTreeFLANN< GlobalDescriptorT >, and pcl::KdTreeFLANN< pcl::FPFHSignature33 >.

Definition at line 88 of file kdtree/include/pcl/kdtree/kdtree.h.

template<typename PointT>
void pcl::KdTree< PointT >::setMinPts ( int  min_pts) [inline]

Minimum allowed number of k nearest neighbors points that a viable result must contain.

Parameters:
[in]min_ptsthe minimum number of neighbors in a viable neighborhood

Definition at line 337 of file kdtree/include/pcl/kdtree/kdtree.h.

template<typename PointT>
void pcl::KdTree< PointT >::setPointRepresentation ( const PointRepresentationConstPtr point_representation) [inline]

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 112 of file kdtree/include/pcl/kdtree/kdtree.h.


Member Data Documentation

template<typename PointT>
float pcl::KdTree< PointT >::epsilon_ [protected]

Epsilon precision (error bound) for nearest neighbors searches.

Definition at line 357 of file kdtree/include/pcl/kdtree/kdtree.h.

template<typename PointT>
IndicesConstPtr pcl::KdTree< PointT >::indices_ [protected]

A pointer to the vector of point indices to use.

Definition at line 354 of file kdtree/include/pcl/kdtree/kdtree.h.

template<typename PointT>
PointCloudConstPtr pcl::KdTree< PointT >::input_ [protected]

The input point cloud dataset containing the points we need to use.

Definition at line 351 of file kdtree/include/pcl/kdtree/kdtree.h.

template<typename PointT>
int pcl::KdTree< PointT >::min_pts_ [protected]

Minimum allowed number of k nearest neighbors points that a viable result must contain.

Definition at line 360 of file kdtree/include/pcl/kdtree/kdtree.h.

template<typename PointT>
PointRepresentationConstPtr pcl::KdTree< PointT >::point_representation_ [protected]

For converting different point structures into k-dimensional vectors for nearest-neighbor search.

Definition at line 366 of file kdtree/include/pcl/kdtree/kdtree.h.

template<typename PointT>
bool pcl::KdTree< PointT >::sorted_ [protected]

Return the radius search neighbours sorted.

Definition at line 363 of file kdtree/include/pcl/kdtree/kdtree.h.


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


pcl
Author(s): Open Perception
autogenerated on Mon Oct 6 2014 03:19:30