point_cloud_library / 1.12.1 / classpcl_1_1search_1_1_octree.html /

search::Octree is a wrapper class which implements nearest neighbor search operations based on the pcl::octree::Octree structure. More...

#include <pcl/search/octree.h>

Public Types

using Ptr = shared_ptr< pcl::search::Octree< PointT, LeafTWrap, BranchTWrap, OctreeT > >
using ConstPtr = shared_ptr< const pcl::search::Octree< PointT, LeafTWrap, BranchTWrap, OctreeT > >
using PointCloud = pcl::PointCloud< PointT >
using PointCloudPtr = typename PointCloud::Ptr
using PointCloudConstPtr = typename PointCloud::ConstPtr
using OctreePointCloudSearchPtr = typename pcl::octree::OctreePointCloudSearch< PointT, LeafTWrap, BranchTWrap >::Ptr
using OctreePointCloudSearchConstPtr = typename pcl::octree::OctreePointCloudSearch< PointT, LeafTWrap, BranchTWrap >::ConstPtr

Public Member Functions

Octree (const double resolution)
Octree constructor. More...
~Octree ()
Empty Destructor. More...
void setInputCloud (const PointCloudConstPtr &cloud)
Provide a pointer to the input dataset. More...
void setInputCloud (const PointCloudConstPtr &cloud, const IndicesConstPtr &indices) override
Provide a pointer to the input dataset. More...
int nearestKSearch (const PointCloud &cloud, index_t index, int k, Indices &k_indices, std::vector< float > &k_sqr_distances) const override
Search for the k-nearest neighbors for the given query point. More...
int nearestKSearch (const PointT &point, int k, Indices &k_indices, std::vector< float > &k_sqr_distances) const override
Search for the k-nearest neighbors for the given query point. More...
int nearestKSearch (index_t index, int k, Indices &k_indices, std::vector< float > &k_sqr_distances) const override
Search for the k-nearest neighbors for the given query point (zero-copy). More...
int radiusSearch (const PointCloud &cloud, index_t index, double radius, Indices &k_indices, std::vector< float > &k_sqr_distances, unsigned int max_nn=0) const override
search for all neighbors of query point that are within a given radius. More...
int radiusSearch (const PointT &p_q, double radius, Indices &k_indices, std::vector< float > &k_sqr_distances, unsigned int max_nn=0) const override
search for all neighbors of query point that are within a given radius. More...
int radiusSearch (index_t index, double radius, Indices &k_indices, std::vector< float > &k_sqr_distances, unsigned int max_nn=0) const override
search for all neighbors of query point that are within a given radius. More...
void approxNearestSearch (const PointCloudConstPtr &cloud, index_t query_index, index_t &result_index, float &sqr_distance)
Search for approximate nearest neighbor at the query point. More...
void approxNearestSearch (const PointT &p_q, index_t &result_index, float &sqr_distance)
Search for approximate nearest neighbor at the query point. More...
void approxNearestSearch (index_t query_index, index_t &result_index, float &sqr_distance)
Search for approximate nearest neighbor at the query point. More...
uindex_t boxSearch (const Eigen::Vector3f &min_pt, const Eigen::Vector3f &max_pt, Indices &k_indices) const
Search for points within rectangular search area. More...

Public Attributes

OctreePointCloudSearchPtr tree_

Additional Inherited Members

Detailed Description

template<typename PointT, typename LeafTWrap = pcl::octree::OctreeContainerPointIndices, typename BranchTWrap = pcl::octree::OctreeContainerEmpty, typename OctreeT = pcl::octree::OctreeBase<LeafTWrap, BranchTWrap >>
class pcl::search::Octree< PointT, LeafTWrap, BranchTWrap, OctreeT >

search::Octree is a wrapper class which implements nearest neighbor search operations based on the pcl::octree::Octree structure.

The octree pointcloud class needs to be initialized with its voxel resolution. Its bounding box is automatically adjusted according to the pointcloud dimension or it can be predefined. Note: The tree depth equates to the resolution and the bounding box dimensions of the octree.

Note
typename: PointT: type of point used in pointcloud
typename: LeafT: leaf node class (usuallt templated with integer indices values)
typename: OctreeT: octree implementation ()
Author
Julius Kammerl

Definition at line 68 of file octree.h.

Member Typedef Documentation

ConstPtr

template<typename PointT , typename LeafTWrap = pcl::octree::OctreeContainerPointIndices, typename BranchTWrap = pcl::octree::OctreeContainerEmpty, typename OctreeT = pcl::octree::OctreeBase<LeafTWrap, BranchTWrap >>
using pcl::search::Octree< PointT, LeafTWrap, BranchTWrap, OctreeT >::ConstPtr = shared_ptr<const pcl::search::Octree<PointT,LeafTWrap,BranchTWrap,OctreeT> >

Definition at line 73 of file octree.h.

OctreePointCloudSearchConstPtr

template<typename PointT , typename LeafTWrap = pcl::octree::OctreeContainerPointIndices, typename BranchTWrap = pcl::octree::OctreeContainerEmpty, typename OctreeT = pcl::octree::OctreeBase<LeafTWrap, BranchTWrap >>
using pcl::search::Octree< PointT, LeafTWrap, BranchTWrap, OctreeT >::OctreePointCloudSearchConstPtr = typename pcl::octree::OctreePointCloudSearch<PointT, LeafTWrap, BranchTWrap>::ConstPtr

Definition at line 81 of file octree.h.

OctreePointCloudSearchPtr

template<typename PointT , typename LeafTWrap = pcl::octree::OctreeContainerPointIndices, typename BranchTWrap = pcl::octree::OctreeContainerEmpty, typename OctreeT = pcl::octree::OctreeBase<LeafTWrap, BranchTWrap >>
using pcl::search::Octree< PointT, LeafTWrap, BranchTWrap, OctreeT >::OctreePointCloudSearchPtr = typename pcl::octree::OctreePointCloudSearch<PointT, LeafTWrap, BranchTWrap>::Ptr

Definition at line 80 of file octree.h.

PointCloud

template<typename PointT , typename LeafTWrap = pcl::octree::OctreeContainerPointIndices, typename BranchTWrap = pcl::octree::OctreeContainerEmpty, typename OctreeT = pcl::octree::OctreeBase<LeafTWrap, BranchTWrap >>
using pcl::search::Octree< PointT, LeafTWrap, BranchTWrap, OctreeT >::PointCloud = pcl::PointCloud<PointT>

Definition at line 75 of file octree.h.

PointCloudConstPtr

template<typename PointT , typename LeafTWrap = pcl::octree::OctreeContainerPointIndices, typename BranchTWrap = pcl::octree::OctreeContainerEmpty, typename OctreeT = pcl::octree::OctreeBase<LeafTWrap, BranchTWrap >>
using pcl::search::Octree< PointT, LeafTWrap, BranchTWrap, OctreeT >::PointCloudConstPtr = typename PointCloud::ConstPtr

Definition at line 77 of file octree.h.

PointCloudPtr

template<typename PointT , typename LeafTWrap = pcl::octree::OctreeContainerPointIndices, typename BranchTWrap = pcl::octree::OctreeContainerEmpty, typename OctreeT = pcl::octree::OctreeBase<LeafTWrap, BranchTWrap >>
using pcl::search::Octree< PointT, LeafTWrap, BranchTWrap, OctreeT >::PointCloudPtr = typename PointCloud::Ptr

Definition at line 76 of file octree.h.

Ptr

template<typename PointT , typename LeafTWrap = pcl::octree::OctreeContainerPointIndices, typename BranchTWrap = pcl::octree::OctreeContainerEmpty, typename OctreeT = pcl::octree::OctreeBase<LeafTWrap, BranchTWrap >>
using pcl::search::Octree< PointT, LeafTWrap, BranchTWrap, OctreeT >::Ptr = shared_ptr<pcl::search::Octree<PointT,LeafTWrap,BranchTWrap,OctreeT> >

Definition at line 72 of file octree.h.

Constructor & Destructor Documentation

Octree()

template<typename PointT , typename LeafTWrap = pcl::octree::OctreeContainerPointIndices, typename BranchTWrap = pcl::octree::OctreeContainerEmpty, typename OctreeT = pcl::octree::OctreeBase<LeafTWrap, BranchTWrap >>
pcl::search::Octree< PointT, LeafTWrap, BranchTWrap, OctreeT >::Octree ( const double resolution )
inline

Octree constructor.

Parameters
[in] resolution octree resolution at lowest octree level

Definition at line 91 of file octree.h.

~Octree()

template<typename PointT , typename LeafTWrap = pcl::octree::OctreeContainerPointIndices, typename BranchTWrap = pcl::octree::OctreeContainerEmpty, typename OctreeT = pcl::octree::OctreeBase<LeafTWrap, BranchTWrap >>
pcl::search::Octree< PointT, LeafTWrap, BranchTWrap, OctreeT >::~Octree ( )
inline

Empty Destructor.

Definition at line 99 of file octree.h.

Member Function Documentation

approxNearestSearch() [1/3]

template<typename PointT , typename LeafTWrap = pcl::octree::OctreeContainerPointIndices, typename BranchTWrap = pcl::octree::OctreeContainerEmpty, typename OctreeT = pcl::octree::OctreeBase<LeafTWrap, BranchTWrap >>
void pcl::search::Octree< PointT, LeafTWrap, BranchTWrap, OctreeT >::approxNearestSearch ( const PointCloudConstPtr & cloud,
index_t query_index,
index_t & result_index,
float & sqr_distance
)
inline

Search for approximate nearest neighbor at the query point.

Parameters
[in] cloud the point cloud data
[in] query_index the index in cloud representing the query point
[out] result_index the resultant index of the neighbor point
[out] sqr_distance the resultant squared distance to the neighboring point
Returns
number of neighbors found

Definition at line 249 of file octree.h.

approxNearestSearch() [2/3]

template<typename PointT , typename LeafTWrap = pcl::octree::OctreeContainerPointIndices, typename BranchTWrap = pcl::octree::OctreeContainerEmpty, typename OctreeT = pcl::octree::OctreeBase<LeafTWrap, BranchTWrap >>
void pcl::search::Octree< PointT, LeafTWrap, BranchTWrap, OctreeT >::approxNearestSearch ( const PointT & p_q,
index_t & result_index,
float & sqr_distance
)
inline

Search for approximate nearest neighbor at the query point.

Parameters
[in] p_q the given query point
[out] result_index the resultant index of the neighbor point
[out] sqr_distance the resultant squared distance to the neighboring point

Definition at line 261 of file octree.h.

approxNearestSearch() [3/3]

template<typename PointT , typename LeafTWrap = pcl::octree::OctreeContainerPointIndices, typename BranchTWrap = pcl::octree::OctreeContainerEmpty, typename OctreeT = pcl::octree::OctreeBase<LeafTWrap, BranchTWrap >>
void pcl::search::Octree< PointT, LeafTWrap, BranchTWrap, OctreeT >::approxNearestSearch ( index_t query_index,
index_t & result_index,
float & sqr_distance
)
inline

Search for approximate nearest neighbor at the query point.

Parameters
query_index 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.
result_index the resultant index of the neighbor point
sqr_distance the resultant squared distance to the neighboring point
Returns
number of neighbors found

Definition at line 274 of file octree.h.

boxSearch()

template<typename PointT , typename LeafTWrap = pcl::octree::OctreeContainerPointIndices, typename BranchTWrap = pcl::octree::OctreeContainerEmpty, typename OctreeT = pcl::octree::OctreeBase<LeafTWrap, BranchTWrap >>
uindex_t pcl::search::Octree< PointT, LeafTWrap, BranchTWrap, OctreeT >::boxSearch ( const Eigen::Vector3f & min_pt,
const Eigen::Vector3f & max_pt,
Indices & k_indices
) const
inline

Search for points within rectangular search area.

Parameters
[in] min_pt lower corner of search area
[in] max_pt upper corner of search area
[out] k_indices the resultant point indices
Returns
number of points found within search area

Definition at line 285 of file octree.h.

nearestKSearch() [1/3]

template<typename PointT , typename LeafTWrap = pcl::octree::OctreeContainerPointIndices, typename BranchTWrap = pcl::octree::OctreeContainerEmpty, typename OctreeT = pcl::octree::OctreeBase<LeafTWrap, BranchTWrap >>
int pcl::search::Octree< PointT, LeafTWrap, BranchTWrap, OctreeT >::nearestKSearch ( const PointCloud & cloud,
index_t index,
int k,
Indices & k_indices,
std::vector< float > & k_sqr_distances
) const
inlineoverridevirtual

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

Parameters
[in] cloud the point cloud data
[in] index the index in cloud representing the query point
[in] k the number of neighbors to search for
[out] k_indices the resultant indices of the neighboring points (must be resized to k a priori!)
[out] k_sqr_distances the resultant squared distances to the neighboring points (must be resized to k a priori!)
Returns
number of neighbors found

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

Definition at line 139 of file octree.h.

nearestKSearch() [2/3]

template<typename PointT , typename LeafTWrap = pcl::octree::OctreeContainerPointIndices, typename BranchTWrap = pcl::octree::OctreeContainerEmpty, typename OctreeT = pcl::octree::OctreeBase<LeafTWrap, BranchTWrap >>
int pcl::search::Octree< PointT, LeafTWrap, BranchTWrap, OctreeT >::nearestKSearch ( const PointT & point,
int k,
Indices & k_indices,
std::vector< float > & k_sqr_distances
) const
inlineoverridevirtual

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

Parameters
[in] point the given query point
[in] k the number of neighbors to search for
[out] k_indices the resultant indices of the neighboring points (must be resized to k a priori!)
[out] k_sqr_distances the 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 154 of file octree.h.

nearestKSearch() [3/3]

template<typename PointT , typename LeafTWrap = pcl::octree::OctreeContainerPointIndices, typename BranchTWrap = pcl::octree::OctreeContainerEmpty, typename OctreeT = pcl::octree::OctreeBase<LeafTWrap, BranchTWrap >>
int pcl::search::Octree< PointT, LeafTWrap, BranchTWrap, OctreeT >::nearestKSearch ( index_t index,
int k,
Indices & k_indices,
std::vector< float > & k_sqr_distances
) const
inlineoverridevirtual

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

Parameters
[in] 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
[in] k the number of neighbors to search for
[out] k_indices the resultant indices of the neighboring points (must be resized to k a priori!)
[out] k_sqr_distances the resultant squared distances to the neighboring points (must be resized to k a priori!)
Returns
number of neighbors found

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

Definition at line 172 of file octree.h.

radiusSearch() [1/3]

template<typename PointT , typename LeafTWrap = pcl::octree::OctreeContainerPointIndices, typename BranchTWrap = pcl::octree::OctreeContainerEmpty, typename OctreeT = pcl::octree::OctreeBase<LeafTWrap, BranchTWrap >>
int pcl::search::Octree< PointT, LeafTWrap, BranchTWrap, OctreeT >::radiusSearch ( const PointCloud & cloud,
index_t index,
double radius,
Indices & k_indices,
std::vector< float > & k_sqr_distances,
unsigned int max_nn = 0
) const
inlineoverridevirtual

search for all neighbors of query point that are within 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_sqr_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

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

Definition at line 187 of file octree.h.

radiusSearch() [2/3]

template<typename PointT , typename LeafTWrap = pcl::octree::OctreeContainerPointIndices, typename BranchTWrap = pcl::octree::OctreeContainerEmpty, typename OctreeT = pcl::octree::OctreeBase<LeafTWrap, BranchTWrap >>
int pcl::search::Octree< PointT, LeafTWrap, BranchTWrap, OctreeT >::radiusSearch ( const PointT & p_q,
double radius,
Indices & k_indices,
std::vector< float > & k_sqr_distances,
unsigned int max_nn = 0
) const
inlineoverridevirtual

search for all neighbors of query point that are within a given radius.

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

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

Definition at line 209 of file octree.h.

radiusSearch() [3/3]

template<typename PointT , typename LeafTWrap = pcl::octree::OctreeContainerPointIndices, typename BranchTWrap = pcl::octree::OctreeContainerEmpty, typename OctreeT = pcl::octree::OctreeBase<LeafTWrap, BranchTWrap >>
int pcl::search::Octree< PointT, LeafTWrap, BranchTWrap, OctreeT >::radiusSearch ( index_t index,
double radius,
Indices & k_indices,
std::vector< float > & k_sqr_distances,
unsigned int max_nn = 0
) const
inlineoverridevirtual

search for all neighbors of query point that are within a given radius.

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

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

Definition at line 231 of file octree.h.

setInputCloud() [1/2]

template<typename PointT , typename LeafTWrap = pcl::octree::OctreeContainerPointIndices, typename BranchTWrap = pcl::octree::OctreeContainerEmpty, typename OctreeT = pcl::octree::OctreeBase<LeafTWrap, BranchTWrap >>
void pcl::search::Octree< PointT, LeafTWrap, BranchTWrap, OctreeT >::setInputCloud ( const PointCloudConstPtr & cloud )
inline

Provide a pointer to the input dataset.

Parameters
[in] cloud the const boost shared pointer to a PointCloud message

Definition at line 107 of file octree.h.

setInputCloud() [2/2]

template<typename PointT , typename LeafTWrap = pcl::octree::OctreeContainerPointIndices, typename BranchTWrap = pcl::octree::OctreeContainerEmpty, typename OctreeT = pcl::octree::OctreeBase<LeafTWrap, BranchTWrap >>
void pcl::search::Octree< PointT, LeafTWrap, BranchTWrap, OctreeT >::setInputCloud ( const PointCloudConstPtr & cloud,
const IndicesConstPtr & indices
)
inlineoverridevirtual

Provide a pointer to the input dataset.

Parameters
[in] cloud the const boost shared pointer to a PointCloud message
[in] indices the point indices subset that is to be used from cloud

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

Definition at line 120 of file octree.h.

Member Data Documentation

tree_

template<typename PointT , typename LeafTWrap = pcl::octree::OctreeContainerPointIndices, typename BranchTWrap = pcl::octree::OctreeContainerEmpty, typename OctreeT = pcl::octree::OctreeBase<LeafTWrap, BranchTWrap >>
OctreePointCloudSearchPtr pcl::search::Octree< PointT, LeafTWrap, BranchTWrap, OctreeT >::tree_

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

© 2009–2012, Willow Garage, Inc.
© 2012–, Open Perception, Inc.
Licensed under the BSD License.
https://pointclouds.org/documentation/classpcl_1_1search_1_1_octree.html