Octree pointcloud search class More...
#include <octree_search.h>
Classes | |
class | prioBranchQueueEntry |
Priority queue entry for branch nodes More... | |
class | prioPointQueueEntry |
Priority queue entry for point candidates More... | |
Public Types | |
typedef std::vector< PointT, Eigen::aligned_allocator < PointT > > | AlignedPointTVector |
typedef OctreeT::BranchNode | BranchNode |
typedef boost::shared_ptr < const OctreePointCloudSearch < PointT, LeafT, BranchT > > | ConstPtr |
typedef boost::shared_ptr < const std::vector< int > > | IndicesConstPtr |
typedef boost::shared_ptr < std::vector< int > > | IndicesPtr |
typedef OctreeT::LeafNode | LeafNode |
typedef OctreePointCloud < PointT, LeafT, BranchT > | OctreeT |
typedef pcl::PointCloud< PointT > | PointCloud |
typedef boost::shared_ptr < const PointCloud > | PointCloudConstPtr |
typedef boost::shared_ptr < PointCloud > | PointCloudPtr |
typedef boost::shared_ptr < OctreePointCloudSearch < PointT, LeafT, BranchT > > | Ptr |
Public Member Functions | |
void | approxNearestSearch (const PointCloud &cloud, int query_index, int &result_index, float &sqr_distance) |
Search for approx. nearest neighbor at the query point. | |
void | approxNearestSearch (const PointT &p_q, int &result_index, float &sqr_distance) |
Search for approx. nearest neighbor at the query point. | |
void | approxNearestSearch (int query_index, int &result_index, float &sqr_distance) |
Search for approx. nearest neighbor at the query point. | |
int | boxSearch (const Eigen::Vector3f &min_pt, const Eigen::Vector3f &max_pt, std::vector< int > &k_indices) const |
Search for points within rectangular search area. | |
int | getIntersectedVoxelCenters (Eigen::Vector3f origin, Eigen::Vector3f direction, AlignedPointTVector &voxelCenterList, int maxVoxelCount=0) const |
Get a PointT vector of centers of all voxels that intersected by a ray (origin, direction). | |
int | getIntersectedVoxelIndices (Eigen::Vector3f origin, Eigen::Vector3f direction, std::vector< int > &k_indices, int maxVoxelCount=0) const |
Get indices of all voxels that are intersected by a ray (origin, direction). | |
int | nearestKSearch (const PointCloud &cloud, int index, int k, std::vector< int > &k_indices, std::vector< float > &k_sqr_distances) |
Search for k-nearest neighbors at the query point. | |
int | nearestKSearch (const PointT &p_q, int k, std::vector< int > &k_indices, std::vector< float > &k_sqr_distances) |
Search for k-nearest neighbors at given query point. | |
int | nearestKSearch (int index, int k, std::vector< int > &k_indices, std::vector< float > &k_sqr_distances) |
Search for k-nearest neighbors at query point. | |
OctreePointCloudSearch (const double resolution) | |
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) |
Search for all neighbors of query point that are within a given radius. | |
int | radiusSearch (const PointT &p_q, const 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, const 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. | |
bool | voxelSearch (const PointT &point, std::vector< int > &pointIdx_data) |
Search for neighbors within a voxel at given point. | |
bool | voxelSearch (const int index, std::vector< int > &pointIdx_data) |
Search for neighbors within a voxel at given point referenced by a point index. | |
virtual | ~OctreePointCloudSearch () |
Empty class constructor. | |
Protected Member Functions | |
void | approxNearestSearchRecursive (const PointT &point, const BranchNode *node, const OctreeKey &key, unsigned int treeDepth, int &result_index, float &sqr_distance) |
Recursive search method that explores the octree and finds the approximate nearest neighbor. | |
void | boxSearchRecursive (const Eigen::Vector3f &min_pt, const Eigen::Vector3f &max_pt, const BranchNode *node, const OctreeKey &key, unsigned int treeDepth, std::vector< int > &k_indices) const |
Recursive search method that explores the octree and finds points within a rectangular search area. | |
int | getFirstIntersectedNode (double minX, double minY, double minZ, double midX, double midY, double midZ) const |
Find first child node ray will enter. | |
int | getIntersectedVoxelCentersRecursive (double minX, double minY, double minZ, double maxX, double maxY, double maxZ, unsigned char a, const OctreeNode *node, const OctreeKey &key, AlignedPointTVector &voxelCenterList, int maxVoxelCount) const |
Recursively search the tree for all intersected leaf nodes and return a vector of voxel centers. This algorithm is based off the paper An Efficient Parametric Algorithm for Octree Traversal: http://wscg.zcu.cz/wscg2000/Papers_2000/X31.pdf. | |
int | getIntersectedVoxelIndicesRecursive (double minX, double minY, double minZ, double maxX, double maxY, double maxZ, unsigned char a, const OctreeNode *node, const OctreeKey &key, std::vector< int > &k_indices, int maxVoxelCount) const |
Recursively search the tree for all intersected leaf nodes and return a vector of indices. This algorithm is based off the paper An Efficient Parametric Algorithm for Octree Traversal: http://wscg.zcu.cz/wscg2000/Papers_2000/X31.pdf. | |
double | getKNearestNeighborRecursive (const PointT &point, unsigned int K, const BranchNode *node, const OctreeKey &key, unsigned int treeDepth, const double squaredSearchRadius, std::vector< prioPointQueueEntry > &pointCandidates) const |
Recursive search method that explores the octree and finds the K nearest neighbors. | |
void | getNeighborsWithinRadiusRecursive (const PointT &point, const double radiusSquared, const BranchNode *node, const OctreeKey &key, unsigned int treeDepth, std::vector< int > &k_indices, std::vector< float > &k_sqr_distances, unsigned int max_nn) const |
Recursive search method that explores the octree and finds neighbors within a given radius. | |
int | getNextIntersectedNode (double x, double y, double z, int a, int b, int c) const |
Get the next visited node given the current node upper bounding box corner. This function accepts three float values, and three int values. The function returns the ith integer where the ith float value is the minimum of the three float values. | |
void | initIntersectedVoxel (Eigen::Vector3f &origin, Eigen::Vector3f &direction, double &minX, double &minY, double &minZ, double &maxX, double &maxY, double &maxZ, unsigned char &a) const |
Initialize raytracing algorithm. | |
float | pointSquaredDist (const PointT &pointA, const PointT &pointB) const |
Helper function to calculate the squared distance between two points. |
Octree pointcloud search class
Definition at line 62 of file octree_search.h.
typedef std::vector<PointT, Eigen::aligned_allocator<PointT> > pcl::octree::OctreePointCloudSearch< PointT, LeafT, BranchT >::AlignedPointTVector |
Reimplemented from pcl::octree::OctreePointCloud< PointT, LeafT, BranchT >.
Definition at line 78 of file octree_search.h.
typedef OctreeT::BranchNode pcl::octree::OctreePointCloudSearch< PointT, LeafT, BranchT >::BranchNode |
Reimplemented from pcl::octree::OctreePointCloud< PointT, LeafT, BranchT >.
Definition at line 82 of file octree_search.h.
typedef boost::shared_ptr<const OctreePointCloudSearch<PointT, LeafT, BranchT> > pcl::octree::OctreePointCloudSearch< PointT, LeafT, BranchT >::ConstPtr |
Reimplemented from pcl::octree::OctreePointCloud< PointT, LeafT, BranchT >.
Definition at line 75 of file octree_search.h.
typedef boost::shared_ptr<const std::vector<int> > pcl::octree::OctreePointCloudSearch< PointT, LeafT, BranchT >::IndicesConstPtr |
Reimplemented from pcl::octree::OctreePointCloud< PointT, LeafT, BranchT >.
Definition at line 67 of file octree_search.h.
typedef boost::shared_ptr<std::vector<int> > pcl::octree::OctreePointCloudSearch< PointT, LeafT, BranchT >::IndicesPtr |
Reimplemented from pcl::octree::OctreePointCloud< PointT, LeafT, BranchT >.
Definition at line 66 of file octree_search.h.
typedef OctreeT::LeafNode pcl::octree::OctreePointCloudSearch< PointT, LeafT, BranchT >::LeafNode |
Reimplemented from pcl::octree::OctreePointCloud< PointT, LeafT, BranchT >.
Definition at line 81 of file octree_search.h.
typedef OctreePointCloud<PointT, LeafT, BranchT> pcl::octree::OctreePointCloudSearch< PointT, LeafT, BranchT >::OctreeT |
Reimplemented from pcl::octree::OctreeBase< int, LeafT, BranchT >.
Definition at line 80 of file octree_search.h.
typedef pcl::PointCloud<PointT> pcl::octree::OctreePointCloudSearch< PointT, LeafT, BranchT >::PointCloud |
Reimplemented from pcl::octree::OctreePointCloud< PointT, LeafT, BranchT >.
Definition at line 69 of file octree_search.h.
typedef boost::shared_ptr<const PointCloud> pcl::octree::OctreePointCloudSearch< PointT, LeafT, BranchT >::PointCloudConstPtr |
Reimplemented from pcl::octree::OctreePointCloud< PointT, LeafT, BranchT >.
Definition at line 71 of file octree_search.h.
typedef boost::shared_ptr<PointCloud> pcl::octree::OctreePointCloudSearch< PointT, LeafT, BranchT >::PointCloudPtr |
Reimplemented from pcl::octree::OctreePointCloud< PointT, LeafT, BranchT >.
Definition at line 70 of file octree_search.h.
typedef boost::shared_ptr<OctreePointCloudSearch<PointT, LeafT, BranchT> > pcl::octree::OctreePointCloudSearch< PointT, LeafT, BranchT >::Ptr |
Reimplemented from pcl::octree::OctreePointCloud< PointT, LeafT, BranchT >.
Definition at line 74 of file octree_search.h.
pcl::octree::OctreePointCloudSearch< PointT, LeafT, BranchT >::OctreePointCloudSearch | ( | const double | resolution | ) | [inline] |
Constructor.
[in] | resolution | octree resolution at lowest octree level |
Definition at line 87 of file octree_search.h.
virtual pcl::octree::OctreePointCloudSearch< PointT, LeafT, BranchT >::~OctreePointCloudSearch | ( | ) | [inline, virtual] |
Empty class constructor.
Definition at line 94 of file octree_search.h.
void pcl::octree::OctreePointCloudSearch< PointT, LeafT, BranchT >::approxNearestSearch | ( | const PointCloud & | cloud, |
int | query_index, | ||
int & | result_index, | ||
float & | sqr_distance | ||
) | [inline] |
Search for approx. 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 162 of file octree_search.h.
void pcl::octree::OctreePointCloudSearch< PointT, LeafT, BranchT >::approxNearestSearch | ( | const PointT & | p_q, |
int & | result_index, | ||
float & | sqr_distance | ||
) |
Search for approx. 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 135 of file octree_search.hpp.
void pcl::octree::OctreePointCloudSearch< PointT, LeafT, BranchT >::approxNearestSearch | ( | int | query_index, |
int & | result_index, | ||
float & | sqr_distance | ||
) |
Search for approx. nearest neighbor at the query point.
[in] | 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. |
[out] | result_index | the resultant index of the neighbor point |
[out] | sqr_distance | the resultant squared distance to the neighboring point |
Definition at line 152 of file octree_search.hpp.
void pcl::octree::OctreePointCloudSearch< PointT, LeafT, BranchT >::approxNearestSearchRecursive | ( | const PointT & | point, |
const BranchNode * | node, | ||
const OctreeKey & | key, | ||
unsigned int | treeDepth, | ||
int & | result_index, | ||
float & | sqr_distance | ||
) | [protected] |
Recursive search method that explores the octree and finds the approximate nearest neighbor.
[in] | point | query point |
[in] | node | current octree node to be explored |
[in] | key | octree key addressing a leaf node. |
[in] | treeDepth | current depth/level in the octree |
[out] | result_index | result index is written to this reference |
[out] | sqr_distance | squared distance to search |
Definition at line 408 of file octree_search.hpp.
int pcl::octree::OctreePointCloudSearch< PointT, LeafT, BranchT >::boxSearch | ( | const Eigen::Vector3f & | min_pt, |
const Eigen::Vector3f & | max_pt, | ||
std::vector< int > & | k_indices | ||
) | const |
Search for points within rectangular search area.
[in] | min_pt | lower corner of search area |
[in] | max_pt | upper corner of search area |
[out] | k_indices | the resultant point indices |
Definition at line 194 of file octree_search.hpp.
void pcl::octree::OctreePointCloudSearch< PointT, LeafT, BranchT >::boxSearchRecursive | ( | const Eigen::Vector3f & | min_pt, |
const Eigen::Vector3f & | max_pt, | ||
const BranchNode * | node, | ||
const OctreeKey & | key, | ||
unsigned int | treeDepth, | ||
std::vector< int > & | k_indices | ||
) | const [protected] |
Recursive search method that explores the octree and finds points within a rectangular search area.
[in] | min_pt | lower corner of search area |
[in] | max_pt | upper corner of search area |
[in] | node | current octree node to be explored |
[in] | key | octree key addressing a leaf node. |
[in] | treeDepth | current depth/level in the octree |
[out] | k_indices | the resultant point indices |
Definition at line 512 of file octree_search.hpp.
int pcl::octree::OctreePointCloudSearch< PointT, LeafT, BranchT >::getFirstIntersectedNode | ( | double | minX, |
double | minY, | ||
double | minZ, | ||
double | midX, | ||
double | midY, | ||
double | midZ | ||
) | const [inline, protected] |
Find first child node ray will enter.
[in] | minX | octree nodes X coordinate of lower bounding box corner |
[in] | minY | octree nodes Y coordinate of lower bounding box corner |
[in] | minZ | octree nodes Z coordinate of lower bounding box corner |
[in] | midX | octree nodes X coordinate of bounding box mid line |
[in] | midY | octree nodes Y coordinate of bounding box mid line |
[in] | midZ | octree nodes Z coordinate of bounding box mid line |
Definition at line 527 of file octree_search.h.
int pcl::octree::OctreePointCloudSearch< PointT, LeafT, BranchT >::getIntersectedVoxelCenters | ( | Eigen::Vector3f | origin, |
Eigen::Vector3f | direction, | ||
AlignedPointTVector & | voxelCenterList, | ||
int | maxVoxelCount = 0 |
||
) | const |
Get a PointT vector of centers of all voxels that intersected by a ray (origin, direction).
[in] | origin | ray origin |
[in] | direction | ray direction vector |
[out] | voxelCenterList | results are written to this vector of PointT elements |
[in] | maxVoxelCount | stop raycasting when this many voxels intersected (0: disable) |
Definition at line 589 of file octree_search.hpp.
int pcl::octree::OctreePointCloudSearch< PointT, LeafT, BranchT >::getIntersectedVoxelCentersRecursive | ( | double | minX, |
double | minY, | ||
double | minZ, | ||
double | maxX, | ||
double | maxY, | ||
double | maxZ, | ||
unsigned char | a, | ||
const OctreeNode * | node, | ||
const OctreeKey & | key, | ||
AlignedPointTVector & | voxelCenterList, | ||
int | maxVoxelCount | ||
) | const [protected] |
Recursively search the tree for all intersected leaf nodes and return a vector of voxel centers. This algorithm is based off the paper An Efficient Parametric Algorithm for Octree Traversal: http://wscg.zcu.cz/wscg2000/Papers_2000/X31.pdf.
[in] | minX | octree nodes X coordinate of lower bounding box corner |
[in] | minY | octree nodes Y coordinate of lower bounding box corner |
[in] | minZ | octree nodes Z coordinate of lower bounding box corner |
[in] | maxX | octree nodes X coordinate of upper bounding box corner |
[in] | maxY | octree nodes Y coordinate of upper bounding box corner |
[in] | maxZ | octree nodes Z coordinate of upper bounding box corner |
[in] | a | |
[in] | node | current octree node to be explored |
[in] | key | octree key addressing a leaf node. |
[out] | voxelCenterList | results are written to this vector of PointT elements |
[in] | maxVoxelCount | stop raycasting when this many voxels intersected (0: disable) |
Definition at line 637 of file octree_search.hpp.
int pcl::octree::OctreePointCloudSearch< PointT, LeafT, BranchT >::getIntersectedVoxelIndices | ( | Eigen::Vector3f | origin, |
Eigen::Vector3f | direction, | ||
std::vector< int > & | k_indices, | ||
int | maxVoxelCount = 0 |
||
) | const |
Get indices of all voxels that are intersected by a ray (origin, direction).
[in] | origin | ray origin |
[in] | direction | ray direction vector |
[out] | k_indices | resulting point indices from intersected voxels |
[in] | maxVoxelCount | stop raycasting when this many voxels intersected (0: disable) |
Definition at line 614 of file octree_search.hpp.
int pcl::octree::OctreePointCloudSearch< PointT, LeafT, BranchT >::getIntersectedVoxelIndicesRecursive | ( | double | minX, |
double | minY, | ||
double | minZ, | ||
double | maxX, | ||
double | maxY, | ||
double | maxZ, | ||
unsigned char | a, | ||
const OctreeNode * | node, | ||
const OctreeKey & | key, | ||
std::vector< int > & | k_indices, | ||
int | maxVoxelCount | ||
) | const [protected] |
Recursively search the tree for all intersected leaf nodes and return a vector of indices. This algorithm is based off the paper An Efficient Parametric Algorithm for Octree Traversal: http://wscg.zcu.cz/wscg2000/Papers_2000/X31.pdf.
[in] | minX | octree nodes X coordinate of lower bounding box corner |
[in] | minY | octree nodes Y coordinate of lower bounding box corner |
[in] | minZ | octree nodes Z coordinate of lower bounding box corner |
[in] | maxX | octree nodes X coordinate of upper bounding box corner |
[in] | maxY | octree nodes Y coordinate of upper bounding box corner |
[in] | maxZ | octree nodes Z coordinate of upper bounding box corner |
[in] | a | |
[in] | node | current octree node to be explored |
[in] | key | octree key addressing a leaf node. |
[out] | k_indices | resulting indices |
[in] | maxVoxelCount | stop raycasting when this many voxels intersected (0: disable) |
Definition at line 755 of file octree_search.hpp.
double pcl::octree::OctreePointCloudSearch< PointT, LeafT, BranchT >::getKNearestNeighborRecursive | ( | const PointT & | point, |
unsigned int | K, | ||
const BranchNode * | node, | ||
const OctreeKey & | key, | ||
unsigned int | treeDepth, | ||
const double | squaredSearchRadius, | ||
std::vector< prioPointQueueEntry > & | pointCandidates | ||
) | const [protected] |
Recursive search method that explores the octree and finds the K nearest neighbors.
[in] | point | query point |
[in] | K | amount of nearest neighbors to be found |
[in] | node | current octree node to be explored |
[in] | key | octree key addressing a leaf node. |
[in] | treeDepth | current depth/level in the octree |
[in] | squaredSearchRadius | squared search radius distance |
[out] | pointCandidates | priority queue of nearest neigbor point candidates |
Definition at line 212 of file octree_search.hpp.
void pcl::octree::OctreePointCloudSearch< PointT, LeafT, BranchT >::getNeighborsWithinRadiusRecursive | ( | const PointT & | point, |
const double | radiusSquared, | ||
const BranchNode * | node, | ||
const OctreeKey & | key, | ||
unsigned int | treeDepth, | ||
std::vector< int > & | k_indices, | ||
std::vector< float > & | k_sqr_distances, | ||
unsigned int | max_nn | ||
) | const [protected] |
Recursive search method that explores the octree and finds neighbors within a given radius.
[in] | point | query point |
[in] | radiusSquared | squared search radius |
[in] | node | current octree node to be explored |
[in] | key | octree key addressing a leaf node. |
[in] | treeDepth | current depth/level in the octree |
[out] | k_indices | vector of indices found to be neighbors of query point |
[out] | k_sqr_distances | squared distances of neighbors to query point |
[in] | max_nn | maximum of neighbors to be found |
Definition at line 323 of file octree_search.hpp.
int pcl::octree::OctreePointCloudSearch< PointT, LeafT, BranchT >::getNextIntersectedNode | ( | double | x, |
double | y, | ||
double | z, | ||
int | a, | ||
int | b, | ||
int | c | ||
) | const [inline, protected] |
Get the next visited node given the current node upper bounding box corner. This function accepts three float values, and three int values. The function returns the ith integer where the ith float value is the minimum of the three float values.
[in] | x | current nodes X coordinate of upper bounding box corner |
[in] | y | current nodes Y coordinate of upper bounding box corner |
[in] | z | current nodes Z coordinate of upper bounding box corner |
[in] | a | next node if exit Plane YZ |
[in] | b | next node if exit Plane XZ |
[in] | c | next node if exit Plane XY |
Definition at line 586 of file octree_search.h.
void pcl::octree::OctreePointCloudSearch< PointT, LeafT, BranchT >::initIntersectedVoxel | ( | Eigen::Vector3f & | origin, |
Eigen::Vector3f & | direction, | ||
double & | minX, | ||
double & | minY, | ||
double & | minZ, | ||
double & | maxX, | ||
double & | maxY, | ||
double & | maxZ, | ||
unsigned char & | a | ||
) | const [inline, protected] |
Initialize raytracing algorithm.
origin | ||
direction | ||
[in] | minX | octree nodes X coordinate of lower bounding box corner |
[in] | minY | octree nodes Y coordinate of lower bounding box corner |
[in] | minZ | octree nodes Z coordinate of lower bounding box corner |
[in] | maxX | octree nodes X coordinate of upper bounding box corner |
[in] | maxY | octree nodes Y coordinate of upper bounding box corner |
[in] | maxZ | octree nodes Z coordinate of upper bounding box corner |
a |
Definition at line 473 of file octree_search.h.
int pcl::octree::OctreePointCloudSearch< PointT, LeafT, BranchT >::nearestKSearch | ( | const PointCloud & | cloud, |
int | index, | ||
int | k, | ||
std::vector< int > & | k_indices, | ||
std::vector< float > & | k_sqr_distances | ||
) | [inline] |
Search for k-nearest neighbors at the 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!) |
Definition at line 124 of file octree_search.h.
int pcl::octree::OctreePointCloudSearch< PointT, LeafT, BranchT >::nearestKSearch | ( | const PointT & | p_q, |
int | k, | ||
std::vector< int > & | k_indices, | ||
std::vector< float > & | k_sqr_distances | ||
) |
Search for k-nearest neighbors at given query point.
[in] | p_q | 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!) |
Definition at line 82 of file octree_search.hpp.
int pcl::octree::OctreePointCloudSearch< PointT, LeafT, BranchT >::nearestKSearch | ( | int | index, |
int | k, | ||
std::vector< int > & | k_indices, | ||
std::vector< float > & | k_sqr_distances | ||
) |
Search for k-nearest neighbors at query point.
[in] | 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. |
[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!) |
Definition at line 125 of file octree_search.hpp.
float pcl::octree::OctreePointCloudSearch< PointT, LeafT, BranchT >::pointSquaredDist | ( | const PointT & | pointA, |
const PointT & | pointB | ||
) | const [protected] |
Helper function to calculate the squared distance between two points.
[in] | pointA | point A |
[in] | pointB | point B |
Definition at line 504 of file octree_search.hpp.
int pcl::octree::OctreePointCloudSearch< PointT, LeafT, BranchT >::radiusSearch | ( | const PointCloud & | cloud, |
int | index, | ||
double | radius, | ||
std::vector< int > & | k_indices, | ||
std::vector< float > & | k_sqr_distances, | ||
unsigned int | max_nn = 0 |
||
) | [inline] |
Search for all neighbors of query point that are within a given radius.
[in] | cloud | the point cloud data |
[in] | index | the index in cloud representing the query point |
[in] | radius | the radius of the sphere bounding all of p_q's neighbors |
[out] | k_indices | the resultant indices of the neighboring points |
[out] | k_sqr_distances | the resultant squared distances to the neighboring points |
[in] | max_nn | if given, bounds the maximum returned neighbors to this value |
Definition at line 196 of file octree_search.h.
int pcl::octree::OctreePointCloudSearch< PointT, LeafT, BranchT >::radiusSearch | ( | const PointT & | p_q, |
const 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.
[in] | p_q | the given query point |
[in] | radius | the radius of the sphere bounding all of p_q's neighbors |
[out] | k_indices | the resultant indices of the neighboring points |
[out] | k_sqr_distances | the resultant squared distances to the neighboring points |
[in] | max_nn | if given, bounds the maximum returned neighbors to this value |
Definition at line 162 of file octree_search.hpp.
int pcl::octree::OctreePointCloudSearch< PointT, LeafT, BranchT >::radiusSearch | ( | int | index, |
const 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.
[in] | 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 |
[in] | radius | radius of the sphere bounding all of p_q's neighbors |
[out] | k_indices | the resultant indices of the neighboring points |
[out] | k_sqr_distances | the resultant squared distances to the neighboring points |
[in] | max_nn | if given, bounds the maximum returned neighbors to this value |
Definition at line 182 of file octree_search.hpp.
bool pcl::octree::OctreePointCloudSearch< PointT, LeafT, BranchT >::voxelSearch | ( | const PointT & | point, |
std::vector< int > & | pointIdx_data | ||
) |
Search for neighbors within a voxel at given point.
[in] | point | point addressing a leaf node voxel |
[out] | pointIdx_data | the resultant indices of the neighboring voxel points |
Definition at line 50 of file octree_search.hpp.
bool pcl::octree::OctreePointCloudSearch< PointT, LeafT, BranchT >::voxelSearch | ( | const int | index, |
std::vector< int > & | pointIdx_data | ||
) |
Search for neighbors within a voxel at given point referenced by a point index.
[in] | index | the index in input cloud defining the query point |
[out] | pointIdx_data | the resultant indices of the neighboring voxel points |
Definition at line 73 of file octree_search.hpp.