Generic search class. All search wrappers must inherit from this. More...
#include <search.h>

Classes | |
| struct | Compare |
Public Types | |
| typedef boost::shared_ptr < const pcl::search::Search < PointT > > | ConstPtr |
| typedef boost::shared_ptr < const std::vector< int > > | IndicesConstPtr |
| typedef boost::shared_ptr < std::vector< int > > | IndicesPtr |
| typedef pcl::PointCloud< PointT > | PointCloud |
| typedef PointCloud::ConstPtr | PointCloudConstPtr |
| typedef PointCloud::Ptr | PointCloudPtr |
| typedef boost::shared_ptr < pcl::search::Search< PointT > > | Ptr |
Public Member Functions | |
| virtual IndicesConstPtr | getIndices () const |
| Get a pointer to the vector of indices used. | |
| virtual PointCloudConstPtr | getInputCloud () const |
| Get a pointer to the input point cloud dataset. | |
| virtual const std::string & | getName () const |
| Returns the search method name. | |
| virtual bool | getSortedResults () |
| Gets whether the results should be sorted (ascending in the distance) or not Otherwise the results may be returned in any order. | |
| virtual int | nearestKSearch (const PointT &point, int k, std::vector< int > &k_indices, std::vector< float > &k_sqr_distances) const =0 |
| Search for the 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). | |
| virtual void | nearestKSearch (const PointCloud &cloud, const std::vector< int > &indices, int k, std::vector< std::vector< int > > &k_indices, std::vector< std::vector< float > > &k_sqr_distances) const |
| Search for the k-nearest neighbors for the given query point. | |
| 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. | |
| template<typename PointTDiff > | |
| void | nearestKSearchT (const pcl::PointCloud< PointTDiff > &cloud, const std::vector< int > &indices, int k, std::vector< std::vector< int > > &k_indices, std::vector< std::vector< float > > &k_sqr_distances) const |
| Search for the k-nearest neighbors for the given query point. Use this method if the query points are of a different type than the points in the data set (e.g. PointXYZRGBA instead of PointXYZ). | |
| virtual int | radiusSearch (const PointT &point, 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). | |
| virtual void | radiusSearch (const PointCloud &cloud, const std::vector< int > &indices, double radius, std::vector< std::vector< int > > &k_indices, std::vector< 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. | |
| 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. | |
| template<typename PointTDiff > | |
| void | radiusSearchT (const pcl::PointCloud< PointTDiff > &cloud, const std::vector< int > &indices, double radius, std::vector< std::vector< int > > &k_indices, std::vector< std::vector< float > > &k_sqr_distances, unsigned int max_nn=0) const |
| Search for all the nearest neighbors of the query points in a given radius. | |
| Search (const std::string &name="", bool sorted=false) | |
| virtual void | setInputCloud (const PointCloudConstPtr &cloud, const IndicesConstPtr &indices=IndicesConstPtr()) |
| Pass the input dataset that the search will be performed on. | |
| virtual void | setSortedResults (bool sorted) |
| sets whether the results should be sorted (ascending in the distance) or not | |
| virtual | ~Search () |
Protected Member Functions | |
| void | sortResults (std::vector< int > &indices, std::vector< float > &distances) const |
Protected Attributes | |
| IndicesConstPtr | indices_ |
| PointCloudConstPtr | input_ |
| std::string | name_ |
| bool | sorted_results_ |
Generic search class. All search wrappers must inherit from this.
Each search method must implement 2 different types of search:
The input to each search method can be given in 3 different ways:
For the latter option, it is assumed that the user specified the input via a setInputCloud () method first.
| typedef boost::shared_ptr<const pcl::search::Search<PointT> > pcl::search::Search< PointT >::ConstPtr |
Reimplemented in pcl::search::FlannSearch< PointT, FlannDistance >, pcl::search::KdTree< PointT >, pcl::search::KdTree< SceneT >, pcl::search::KdTree< PointTarget >, pcl::search::KdTree< pcl::PointXYZ >, pcl::search::Octree< PointT, LeafTWrap, BranchTWrap, OctreeT >, and pcl::search::OrganizedNeighbor< PointT >.
| typedef boost::shared_ptr<const std::vector<int> > pcl::search::Search< PointT >::IndicesConstPtr |
Reimplemented in pcl::search::Octree< PointT, LeafTWrap, BranchTWrap, OctreeT >, pcl::search::FlannSearch< PointT, FlannDistance >, pcl::search::OrganizedNeighbor< PointT >, pcl::search::KdTree< PointT >, pcl::search::KdTree< SceneT >, pcl::search::KdTree< PointTarget >, pcl::search::KdTree< pcl::PointXYZ >, and pcl::search::BruteForce< PointT >.
| typedef boost::shared_ptr<std::vector<int> > pcl::search::Search< PointT >::IndicesPtr |
Reimplemented in pcl::search::Octree< PointT, LeafTWrap, BranchTWrap, OctreeT >, pcl::search::FlannSearch< PointT, FlannDistance >, pcl::search::KdTree< PointT >, pcl::search::KdTree< SceneT >, pcl::search::KdTree< PointTarget >, pcl::search::KdTree< pcl::PointXYZ >, and pcl::search::BruteForce< PointT >.
| typedef pcl::PointCloud<PointT> pcl::search::Search< PointT >::PointCloud |
Reimplemented in pcl::search::Octree< PointT, LeafTWrap, BranchTWrap, OctreeT >, pcl::search::FlannSearch< PointT, FlannDistance >, pcl::search::OrganizedNeighbor< PointT >, pcl::search::KdTree< PointT >, pcl::search::KdTree< SceneT >, pcl::search::KdTree< PointTarget >, pcl::search::KdTree< pcl::PointXYZ >, and pcl::search::BruteForce< PointT >.
| typedef PointCloud::ConstPtr pcl::search::Search< PointT >::PointCloudConstPtr |
Reimplemented in pcl::search::Octree< PointT, LeafTWrap, BranchTWrap, OctreeT >, pcl::search::FlannSearch< PointT, FlannDistance >, pcl::search::OrganizedNeighbor< PointT >, pcl::search::KdTree< PointT >, pcl::search::KdTree< SceneT >, pcl::search::KdTree< PointTarget >, pcl::search::KdTree< pcl::PointXYZ >, and pcl::search::BruteForce< PointT >.
| typedef PointCloud::Ptr pcl::search::Search< PointT >::PointCloudPtr |
| typedef boost::shared_ptr<pcl::search::Search<PointT> > pcl::search::Search< PointT >::Ptr |
Reimplemented in pcl::search::FlannSearch< PointT, FlannDistance >, pcl::search::KdTree< PointT >, pcl::search::KdTree< SceneT >, pcl::search::KdTree< PointTarget >, pcl::search::KdTree< pcl::PointXYZ >, pcl::search::Octree< PointT, LeafTWrap, BranchTWrap, OctreeT >, and pcl::search::OrganizedNeighbor< PointT >.
| pcl::search::Search< PointT >::Search | ( | const std::string & | name = "", |
| bool | sorted = false |
||
| ) |
Constructor.
Definition at line 45 of file search.hpp.
| virtual pcl::search::Search< PointT >::~Search | ( | ) | [inline, virtual] |
| virtual IndicesConstPtr pcl::search::Search< PointT >::getIndices | ( | ) | const [inline, virtual] |
| virtual PointCloudConstPtr pcl::search::Search< PointT >::getInputCloud | ( | ) | const [inline, virtual] |
| const std::string & pcl::search::Search< PointT >::getName | ( | ) | const [virtual] |
Returns the search method name.
Definition at line 55 of file search.hpp.
| bool pcl::search::Search< PointT >::getSortedResults | ( | ) | [virtual] |
Gets whether the results should be sorted (ascending in the distance) or not Otherwise the results may be returned in any order.
Definition at line 69 of file search.hpp.
| virtual int pcl::search::Search< PointT >::nearestKSearch | ( | const PointT & | point, |
| int | k, | ||
| std::vector< int > & | k_indices, | ||
| std::vector< float > & | k_sqr_distances | ||
| ) | const [pure 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!) |
Implemented in pcl::search::FlannSearch< PointT, FlannDistance >, pcl::search::OrganizedNeighbor< PointT >, pcl::search::Octree< PointT, LeafTWrap, BranchTWrap, OctreeT >, pcl::search::KdTree< PointT >, pcl::search::KdTree< SceneT >, pcl::search::KdTree< PointTarget >, pcl::search::KdTree< pcl::PointXYZ >, and pcl::search::BruteForce< PointT >.
| int pcl::search::Search< PointT >::nearestKSearch | ( | const PointCloud & | cloud, |
| int | index, | ||
| int | k, | ||
| std::vector< int > & | k_indices, | ||
| std::vector< float > & | k_sqr_distances | ||
| ) | const [virtual] |
Search for k-nearest neighbors for the given query point.
| [in] | cloud | the point cloud data |
| [in] | index | a valid index in cloud representing a valid (i.e., finite) 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!) |
| asserts | in debug mode if the index is not between 0 and the maximum number of points |
Reimplemented in pcl::search::Octree< PointT, LeafTWrap, BranchTWrap, OctreeT >.
Definition at line 86 of file search.hpp.
| int pcl::search::Search< PointT >::nearestKSearch | ( | int | index, |
| int | k, | ||
| std::vector< int > & | k_indices, | ||
| std::vector< float > & | k_sqr_distances | ||
| ) | const [virtual] |
Search for k-nearest neighbors for the given query point (zero-copy).
| [in] | index | a 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] | 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!) |
| asserts | in debug mode if the index is not between 0 and the maximum number of points |
Reimplemented in pcl::search::Octree< PointT, LeafTWrap, BranchTWrap, OctreeT >.
Definition at line 96 of file search.hpp.
| void pcl::search::Search< PointT >::nearestKSearch | ( | const PointCloud & | cloud, |
| const std::vector< int > & | indices, | ||
| int | k, | ||
| std::vector< std::vector< int > > & | k_indices, | ||
| std::vector< std::vector< float > > & | k_sqr_distances | ||
| ) | const [virtual] |
Search for the k-nearest neighbors for the given query point.
| [in] | cloud | the point cloud data |
| [in] | indices | a vector of point cloud indices to query for nearest neighbors |
| [in] | k | the number of neighbors to search for |
| [out] | k_indices | the resultant indices of the neighboring points, k_indices[i] corresponds to the neighbors of the query point i |
| [out] | k_sqr_distances | the resultant squared distances to the neighboring points, k_sqr_distances[i] corresponds to the neighbors of the query point i |
Definition at line 117 of file search.hpp.
| int pcl::search::Search< 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.
| [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!) |
| void pcl::search::Search< PointT >::nearestKSearchT | ( | const pcl::PointCloud< PointTDiff > & | cloud, |
| const std::vector< int > & | indices, | ||
| int | k, | ||
| std::vector< std::vector< int > > & | k_indices, | ||
| std::vector< std::vector< float > > & | k_sqr_distances | ||
| ) | const [inline] |
Search for the k-nearest neighbors for the given query point. Use this method if the query points are of a different type than the points in the data set (e.g. PointXYZRGBA instead of PointXYZ).
| [in] | cloud | the point cloud data |
| [in] | indices | a vector of point cloud indices to query for nearest neighbors |
| [in] | k | the number of neighbors to search for |
| [out] | k_indices | the resultant indices of the neighboring points, k_indices[i] corresponds to the neighbors of the query point i |
| [out] | k_sqr_distances | the resultant squared distances to the neighboring points, k_sqr_distances[i] corresponds to the neighbors of the query point i |
| virtual int pcl::search::Search< PointT >::radiusSearch | ( | const PointT & | point, |
| 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.
| [in] | point | 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. 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. |
Implemented in pcl::search::FlannSearch< PointT, FlannDistance >, pcl::search::Octree< PointT, LeafTWrap, BranchTWrap, OctreeT >, pcl::search::KdTree< PointT >, pcl::search::KdTree< SceneT >, pcl::search::KdTree< PointTarget >, pcl::search::KdTree< pcl::PointXYZ >, pcl::search::OrganizedNeighbor< PointT >, and pcl::search::BruteForce< PointT >.
| int pcl::search::Search< 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 [virtual] |
Search for all the nearest neighbors of the query point in a given radius.
| [in] | cloud | the point cloud data |
| [in] | index | a valid index in cloud representing a valid (i.e., finite) 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. 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. |
| asserts | in debug mode if the index is not between 0 and the maximum number of points |
Reimplemented in pcl::search::Octree< PointT, LeafTWrap, BranchTWrap, OctreeT >.
Definition at line 140 of file search.hpp.
| int pcl::search::Search< PointT >::radiusSearch | ( | int | index, |
| double | radius, | ||
| std::vector< int > & | k_indices, | ||
| std::vector< float > & | k_sqr_distances, | ||
| unsigned int | max_nn = 0 |
||
| ) | const [virtual] |
Search for all the nearest neighbors of the query point in a given radius (zero-copy).
| [in] | index | a 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] | 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. 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. |
| asserts | in debug mode if the index is not between 0 and the maximum number of points |
Reimplemented in pcl::search::Octree< PointT, LeafTWrap, BranchTWrap, OctreeT >.
Definition at line 151 of file search.hpp.
| void pcl::search::Search< PointT >::radiusSearch | ( | const PointCloud & | cloud, |
| const std::vector< int > & | indices, | ||
| double | radius, | ||
| std::vector< std::vector< int > > & | k_indices, | ||
| std::vector< std::vector< float > > & | k_sqr_distances, | ||
| unsigned int | max_nn = 0 |
||
| ) | const [virtual] |
Search for all the nearest neighbors of the query point in a given radius.
| [in] | cloud | the point cloud data |
| [in] | indices | the indices in cloud. If indices is empty, neighbors will be searched for all points. |
| [in] | radius | the radius of the sphere bounding all of p_q's neighbors |
| [out] | k_indices | the resultant indices of the neighboring points, k_indices[i] corresponds to the neighbors of the query point i |
| [out] | k_sqr_distances | the resultant squared distances to the neighboring points, k_sqr_distances[i] corresponds to the neighbors of the query point i |
| [in] | max_nn | if 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. |
Definition at line 169 of file search.hpp.
| int pcl::search::Search< 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.
| [in] | point | 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. 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. |
| void pcl::search::Search< PointT >::radiusSearchT | ( | const pcl::PointCloud< PointTDiff > & | cloud, |
| const std::vector< int > & | indices, | ||
| double | radius, | ||
| std::vector< std::vector< int > > & | k_indices, | ||
| std::vector< std::vector< float > > & | k_sqr_distances, | ||
| unsigned int | max_nn = 0 |
||
| ) | const [inline] |
Search for all the nearest neighbors of the query points in a given radius.
| [in] | cloud | the point cloud data |
| [in] | indices | a vector of point cloud indices to query for nearest neighbors |
| [in] | radius | the radius of the sphere bounding all of p_q's neighbors |
| [out] | k_indices | the resultant indices of the neighboring points, k_indices[i] corresponds to the neighbors of the query point i |
| [out] | k_sqr_distances | the resultant squared distances to the neighboring points, k_sqr_distances[i] corresponds to the neighbors of the query point i |
| [in] | max_nn | if 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. |
| void pcl::search::Search< PointT >::setInputCloud | ( | const PointCloudConstPtr & | cloud, |
| const IndicesConstPtr & | indices = IndicesConstPtr () |
||
| ) | [virtual] |
Pass the input dataset that the search will be performed on.
| [in] | cloud | a const pointer to the PointCloud data |
| [in] | indices | the point indices subset that is to be used from the cloud |
Reimplemented in pcl::search::FlannSearch< PointT, FlannDistance >, and pcl::search::KdTree< PointT >.
Definition at line 76 of file search.hpp.
| void pcl::search::Search< PointT >::setSortedResults | ( | bool | sorted | ) | [virtual] |
sets whether the results should be sorted (ascending in the distance) or not
| [in] | sorted | should be true if the results should be sorted by the distance in ascending order. Otherwise the results may be returned in any order. |
Reimplemented in pcl::search::KdTree< PointT >, pcl::search::KdTree< SceneT >, pcl::search::KdTree< PointTarget >, and pcl::search::KdTree< pcl::PointXYZ >.
Definition at line 62 of file search.hpp.
| void pcl::search::Search< PointT >::sortResults | ( | std::vector< int > & | indices, |
| std::vector< float > & | distances | ||
| ) | const [protected] |
Definition at line 195 of file search.hpp.
IndicesConstPtr pcl::search::Search< PointT >::indices_ [protected] |
PointCloudConstPtr pcl::search::Search< PointT >::input_ [protected] |
std::string pcl::search::Search< PointT >::name_ [protected] |
bool pcl::search::Search< PointT >::sorted_results_ [protected] |