KdTree represents the base spatial locator class for nearest neighbor estimation. All types of spatial locators should inherit from KdTree. More...
#include <kdtree.h>

Public Types | |
| typedef boost::shared_ptr < const KdTree< PointT > > | ConstPtr |
| typedef pcl::PointCloud< PointT > | PointCloud |
| 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 | |
| double | getEpsilon () |
| Get the search epsilon precision (error bound) for nearest neighbors searches. | |
| IndicesConstPtr const | getIndices () |
| Get a pointer to the vector of indices used. | |
| PointCloudConstPtr | getInputCloud () |
| Get a pointer to the input point cloud dataset. | |
| float | getMinPts () |
| Get the minimum allowed number of k nearest neighbors points that a viable result must contain. | |
| PointRepresentationConstPtr const | getPointRepresentation () |
| 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 (int index, int k, std::vector< int > &k_indices, std::vector< float > &k_sqr_distances)=0 |
| Search for k-nearest neighbors for the given query point (zero-copy). | |
| virtual int | nearestKSearch (const PointT &p_q, int k, std::vector< int > &k_indices, std::vector< float > &k_sqr_distances)=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)=0 |
| Search for k-nearest neighbors for the given query point. | |
| virtual int | radiusSearch (int index, double radius, std::vector< int > &k_indices, std::vector< float > &k_sqr_distances, int max_nn=INT_MAX) const =0 |
| Search for all the nearest neighbors of the query point in a given radius (zero-copy). | |
| virtual int | radiusSearch (const PointT &p_q, double radius, std::vector< int > &k_indices, std::vector< float > &k_sqr_distances, int max_nn=INT_MAX) 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, int max_nn=INT_MAX) const =0 |
| Search for all the nearest neighbors of the query point in a given radius. | |
| void | setEpsilon (double 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 | |
| double | 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. | |
Private Types | |
| typedef boost::shared_ptr < const std::vector< int > > | IndicesConstPtr |
| typedef boost::shared_ptr < std::vector< int > > | IndicesPtr |
KdTree represents the base spatial locator class for nearest neighbor estimation. All types of spatial locators should inherit from KdTree.
Definition at line 56 of file kdtree.h.
| typedef boost::shared_ptr<const KdTree<PointT> > pcl::KdTree< PointT >::ConstPtr |
Reimplemented in pcl::KdTreeFLANN< PointT >, pcl::OrganizedDataIndex< PointT >, and pcl::KdTreeFLANN< FeatureT >.
typedef boost::shared_ptr<const std::vector<int> > pcl::KdTree< PointT >::IndicesConstPtr [private] |
Reimplemented in pcl::KdTreeFLANN< PointT >, and pcl::KdTreeFLANN< FeatureT >.
typedef boost::shared_ptr<std::vector<int> > pcl::KdTree< PointT >::IndicesPtr [private] |
Reimplemented in pcl::KdTreeFLANN< PointT >, and pcl::KdTreeFLANN< FeatureT >.
| typedef pcl::PointCloud<PointT> pcl::KdTree< PointT >::PointCloud |
Reimplemented in pcl::KdTreeFLANN< PointT >, pcl::OrganizedDataIndex< PointT >, and pcl::KdTreeFLANN< FeatureT >.
| typedef boost::shared_ptr<const PointCloud> pcl::KdTree< PointT >::PointCloudConstPtr |
Reimplemented in pcl::KdTreeFLANN< PointT >, pcl::OrganizedDataIndex< PointT >, and pcl::KdTreeFLANN< FeatureT >.
| typedef boost::shared_ptr<PointCloud> pcl::KdTree< PointT >::PointCloudPtr |
| typedef pcl::PointRepresentation<PointT> pcl::KdTree< PointT >::PointRepresentation |
| typedef boost::shared_ptr<const PointRepresentation> pcl::KdTree< PointT >::PointRepresentationConstPtr |
| typedef boost::shared_ptr<KdTree<PointT> > pcl::KdTree< PointT >::Ptr |
Reimplemented in pcl::KdTreeFLANN< PointT >, pcl::OrganizedDataIndex< PointT >, and pcl::KdTreeFLANN< FeatureT >.
| pcl::KdTree< PointT >::KdTree | ( | bool | sorted = true |
) | [inline] |
| virtual pcl::KdTree< PointT >::~KdTree | ( | ) | [inline, virtual] |
| double pcl::KdTree< PointT >::getEpsilon | ( | ) | [inline] |
| IndicesConstPtr const pcl::KdTree< PointT >::getIndices | ( | ) | [inline] |
| PointCloudConstPtr pcl::KdTree< PointT >::getInputCloud | ( | ) | [inline] |
| float pcl::KdTree< PointT >::getMinPts | ( | ) | [inline] |
| virtual std::string pcl::KdTree< PointT >::getName | ( | ) | const [protected, pure virtual] |
Class getName method.
Implemented in pcl::KdTreeFLANN< PointT >, pcl::OrganizedDataIndex< PointT >, and pcl::KdTreeFLANN< FeatureT >.
| PointRepresentationConstPtr const pcl::KdTree< PointT >::getPointRepresentation | ( | ) | [inline] |
| virtual int pcl::KdTree< PointT >::nearestKSearch | ( | int | index, | |
| int | k, | |||
| std::vector< int > & | k_indices, | |||
| std::vector< float > & | k_sqr_distances | |||
| ) | [pure 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_sqr_distances | the resultant squared distances to the neighboring points (must be resized to k a priori!) |
Implemented in pcl::KdTreeFLANN< PointT >, pcl::OrganizedDataIndex< PointT >, and pcl::KdTreeFLANN< FeatureT >.
| virtual int pcl::KdTree< PointT >::nearestKSearch | ( | const PointT & | p_q, | |
| int | k, | |||
| std::vector< int > & | k_indices, | |||
| std::vector< float > & | k_sqr_distances | |||
| ) | [pure 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_sqr_distances | the resultant squared distances to the neighboring points (must be resized to k a priori!) |
Implemented in pcl::KdTreeFLANN< PointT >, pcl::OrganizedDataIndex< PointT >, and pcl::KdTreeFLANN< FeatureT >.
| virtual int pcl::KdTree< PointT >::nearestKSearch | ( | const PointCloud & | cloud, | |
| int | index, | |||
| int | k, | |||
| std::vector< int > & | k_indices, | |||
| std::vector< float > & | k_sqr_distances | |||
| ) | [pure 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_sqr_distances | the resultant squared distances to the neighboring points (must be resized to k a priori!) |
Implemented in pcl::KdTreeFLANN< PointT >, pcl::OrganizedDataIndex< PointT >, and pcl::KdTreeFLANN< FeatureT >.
| virtual int pcl::KdTree< PointT >::radiusSearch | ( | int | index, | |
| double | radius, | |||
| std::vector< int > & | k_indices, | |||
| std::vector< float > & | k_sqr_distances, | |||
| int | max_nn = INT_MAX | |||
| ) | const [pure 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_sqr_distances | the resultant squared distances to the neighboring points | |
| max_nn | if given, bounds the maximum returned neighbors to this value |
Implemented in pcl::KdTreeFLANN< PointT >, pcl::OrganizedDataIndex< PointT >, and pcl::KdTreeFLANN< FeatureT >.
| virtual int pcl::KdTree< PointT >::radiusSearch | ( | const PointT & | p_q, | |
| double | radius, | |||
| std::vector< int > & | k_indices, | |||
| std::vector< float > & | k_sqr_distances, | |||
| int | max_nn = INT_MAX | |||
| ) | const [pure 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_sqr_distances | the resultant squared distances to the neighboring points | |
| max_nn | if given, bounds the maximum returned neighbors to this value |
Implemented in pcl::KdTreeFLANN< PointT >, pcl::OrganizedDataIndex< PointT >, and pcl::KdTreeFLANN< FeatureT >.
| virtual int pcl::KdTree< PointT >::radiusSearch | ( | const PointCloud & | cloud, | |
| int | index, | |||
| double | radius, | |||
| std::vector< int > & | k_indices, | |||
| std::vector< float > & | k_sqr_distances, | |||
| int | max_nn = INT_MAX | |||
| ) | const [pure 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_sqr_distances | the resultant squared distances to the neighboring points | |
| max_nn | if given, bounds the maximum returned neighbors to this value |
Implemented in pcl::KdTreeFLANN< PointT >, pcl::OrganizedDataIndex< PointT >, and pcl::KdTreeFLANN< FeatureT >.
| void pcl::KdTree< PointT >::setEpsilon | ( | double | eps | ) | [inline] |
| virtual void pcl::KdTree< 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 point cloud is used |
Reimplemented in pcl::KdTreeFLANN< PointT >, and pcl::KdTreeFLANN< FeatureT >.
| void pcl::KdTree< PointT >::setMinPts | ( | int | min_pts | ) | [inline] |
| 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.
| point_representation | the const boost shared pointer to a PointRepresentation |
double pcl::KdTree< PointT >::epsilon_ [protected] |
IndicesConstPtr pcl::KdTree< PointT >::indices_ [protected] |
PointCloudConstPtr pcl::KdTree< PointT >::input_ [protected] |
int pcl::KdTree< PointT >::min_pts_ [protected] |
PointRepresentationConstPtr pcl::KdTree< PointT >::point_representation_ [protected] |
bool pcl::KdTree< PointT >::sorted_ [protected] |