search::Octree is a wrapper class which implements nearest neighbor search operations based on the pcl::octree::Octree structure. More...
#include <octree.h>
Public Types | |
typedef boost::shared_ptr < const pcl::octree::OctreePointCloudSearch < PointT, LeafTWrap, BranchTWrap > > | ConstPtr |
typedef boost::shared_ptr < const std::vector< int > > | IndicesConstPtr |
typedef boost::shared_ptr < std::vector< int > > | IndicesPtr |
typedef pcl::PointCloud< PointT > | PointCloud |
typedef boost::shared_ptr < const PointCloud > | PointCloudConstPtr |
typedef boost::shared_ptr < PointCloud > | PointCloudPtr |
typedef boost::shared_ptr < pcl::octree::OctreePointCloudSearch < PointT, LeafTWrap, BranchTWrap > > | Ptr |
Public Member Functions | |
void | approxNearestSearch (const PointCloudConstPtr &cloud, int query_index, int &result_index, float &sqr_distance) |
Search for approximate nearest neighbor at the query point. | |
void | approxNearestSearch (const PointT &p_q, int &result_index, float &sqr_distance) |
Search for approximate nearest neighbor at the query point. | |
void | approxNearestSearch (int query_index, int &result_index, float &sqr_distance) |
Search for approximate nearest neighbor at the query point. | |
int | nearestKSearch (const PointCloud &cloud, int index, 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 | 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 | nearestKSearch (int index, 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 (zero-copy). | |
Octree (const double resolution) | |
Octree constructor. | |
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 neighbors of query point that are within a given radius. | |
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 |
search for all neighbors of query point that are within a given radius. | |
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 neighbors of query point that are within a given radius. | |
void | setInputCloud (const PointCloudConstPtr &cloud) |
Provide a pointer to the input dataset. | |
void | setInputCloud (const PointCloudConstPtr &cloud, const IndicesConstPtr &indices) |
Provide a pointer to the input dataset. | |
virtual | ~Octree () |
Empty Destructor. | |
Public Attributes | |
Ptr | tree_ |
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.
Definition at line 67 of file search/include/pcl/search/octree.h.
typedef boost::shared_ptr<const pcl::octree::OctreePointCloudSearch<PointT, LeafTWrap, BranchTWrap> > pcl::search::Octree< PointT, LeafTWrap, BranchTWrap, OctreeT >::ConstPtr |
Reimplemented from pcl::search::Search< PointT >.
Definition at line 80 of file search/include/pcl/search/octree.h.
typedef boost::shared_ptr<const std::vector<int> > pcl::search::Octree< PointT, LeafTWrap, BranchTWrap, OctreeT >::IndicesConstPtr |
Reimplemented from pcl::search::Search< PointT >.
Definition at line 72 of file search/include/pcl/search/octree.h.
typedef boost::shared_ptr<std::vector<int> > pcl::search::Octree< PointT, LeafTWrap, BranchTWrap, OctreeT >::IndicesPtr |
Reimplemented from pcl::search::Search< PointT >.
Definition at line 71 of file search/include/pcl/search/octree.h.
typedef pcl::PointCloud<PointT> pcl::search::Octree< PointT, LeafTWrap, BranchTWrap, OctreeT >::PointCloud |
Reimplemented from pcl::search::Search< PointT >.
Definition at line 74 of file search/include/pcl/search/octree.h.
typedef boost::shared_ptr<const PointCloud> pcl::search::Octree< PointT, LeafTWrap, BranchTWrap, OctreeT >::PointCloudConstPtr |
Reimplemented from pcl::search::Search< PointT >.
Definition at line 76 of file search/include/pcl/search/octree.h.
typedef boost::shared_ptr<PointCloud> pcl::search::Octree< PointT, LeafTWrap, BranchTWrap, OctreeT >::PointCloudPtr |
Reimplemented from pcl::search::Search< PointT >.
Definition at line 75 of file search/include/pcl/search/octree.h.
typedef boost::shared_ptr<pcl::octree::OctreePointCloudSearch<PointT, LeafTWrap, BranchTWrap> > pcl::search::Octree< PointT, LeafTWrap, BranchTWrap, OctreeT >::Ptr |
Reimplemented from pcl::search::Search< PointT >.
Definition at line 79 of file search/include/pcl/search/octree.h.
pcl::search::Octree< PointT, LeafTWrap, BranchTWrap, OctreeT >::Octree | ( | const double | resolution | ) | [inline] |
Octree constructor.
[in] | resolution | octree resolution at lowest octree level |
Definition at line 90 of file search/include/pcl/search/octree.h.
virtual pcl::search::Octree< PointT, LeafTWrap, BranchTWrap, OctreeT >::~Octree | ( | ) | [inline, virtual] |
Empty Destructor.
Definition at line 98 of file search/include/pcl/search/octree.h.
void pcl::search::Octree< PointT, LeafTWrap, BranchTWrap, OctreeT >::approxNearestSearch | ( | const PointCloudConstPtr & | cloud, |
int | query_index, | ||
int & | result_index, | ||
float & | sqr_distance | ||
) | [inline] |
Search for approximate nearest neighbor at the query point.
[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 |
Definition at line 248 of file search/include/pcl/search/octree.h.
void pcl::search::Octree< PointT, LeafTWrap, BranchTWrap, OctreeT >::approxNearestSearch | ( | const PointT & | p_q, |
int & | result_index, | ||
float & | sqr_distance | ||
) | [inline] |
Search for approximate nearest neighbor at the query point.
[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 260 of file search/include/pcl/search/octree.h.
void pcl::search::Octree< PointT, LeafTWrap, BranchTWrap, OctreeT >::approxNearestSearch | ( | int | query_index, |
int & | result_index, | ||
float & | sqr_distance | ||
) | [inline] |
Search for approximate nearest neighbor at the query point.
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 |
Definition at line 273 of file search/include/pcl/search/octree.h.
int pcl::search::Octree< PointT, LeafTWrap, BranchTWrap, OctreeT >::nearestKSearch | ( | const PointCloud & | cloud, |
int | index, | ||
int | k, | ||
std::vector< int > & | k_indices, | ||
std::vector< float > & | k_sqr_distances | ||
) | const [inline, virtual] |
Search for the k-nearest neighbors for the given query point.
[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!) |
Reimplemented from pcl::search::Search< PointT >.
Definition at line 138 of file search/include/pcl/search/octree.h.
int pcl::search::Octree< PointT, LeafTWrap, BranchTWrap, OctreeT >::nearestKSearch | ( | const PointT & | point, |
int | k, | ||
std::vector< int > & | k_indices, | ||
std::vector< float > & | k_sqr_distances | ||
) | const [inline, virtual] |
Search for the k-nearest neighbors for the given query point.
[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!) |
Implements pcl::search::Search< PointT >.
Definition at line 153 of file search/include/pcl/search/octree.h.
int pcl::search::Octree< PointT, LeafTWrap, BranchTWrap, OctreeT >::nearestKSearch | ( | int | index, |
int | k, | ||
std::vector< int > & | k_indices, | ||
std::vector< float > & | k_sqr_distances | ||
) | const [inline, virtual] |
Search for the k-nearest neighbors for the given query point (zero-copy).
[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!) |
Reimplemented from pcl::search::Search< PointT >.
Definition at line 171 of file search/include/pcl/search/octree.h.
int pcl::search::Octree< PointT, LeafTWrap, BranchTWrap, OctreeT >::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 neighbors of query point that are within 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 |
Reimplemented from pcl::search::Search< PointT >.
Definition at line 186 of file search/include/pcl/search/octree.h.
int pcl::search::Octree< PointT, LeafTWrap, BranchTWrap, OctreeT >::radiusSearch | ( | const PointT & | p_q, |
double | radius, | ||
std::vector< int > & | k_indices, | ||
std::vector< float > & | k_sqr_distances, | ||
unsigned int | max_nn = 0 |
||
) | const [inline, virtual] |
search for all neighbors of query point that are within a given radius.
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 |
Implements pcl::search::Search< PointT >.
Definition at line 208 of file search/include/pcl/search/octree.h.
int pcl::search::Octree< PointT, LeafTWrap, BranchTWrap, OctreeT >::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 neighbors of query point that are within a given radius.
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 |
Reimplemented from pcl::search::Search< PointT >.
Definition at line 230 of file search/include/pcl/search/octree.h.
void pcl::search::Octree< PointT, LeafTWrap, BranchTWrap, OctreeT >::setInputCloud | ( | const PointCloudConstPtr & | cloud | ) | [inline] |
Provide a pointer to the input dataset.
[in] | cloud | the const boost shared pointer to a PointCloud message |
Definition at line 106 of file search/include/pcl/search/octree.h.
void pcl::search::Octree< PointT, LeafTWrap, BranchTWrap, OctreeT >::setInputCloud | ( | const PointCloudConstPtr & | cloud, |
const IndicesConstPtr & | indices | ||
) | [inline] |
Provide a pointer to the input dataset.
[in] | cloud | the const boost shared pointer to a PointCloud message |
[in] | indices | the point indices subset that is to be used from cloud |
Definition at line 119 of file search/include/pcl/search/octree.h.
Ptr pcl::search::Octree< PointT, LeafTWrap, BranchTWrap, OctreeT >::tree_ |
Definition at line 81 of file search/include/pcl/search/octree.h.