Classes | Public Types | Public Member Functions | Protected Member Functions | Protected Attributes
pcl::search::Search< PointT > Class Template Reference

Generic search class. All search wrappers must inherit from this. More...

#include <search.h>

Inheritance diagram for pcl::search::Search< PointT >:
Inheritance graph
[legend]

List of all members.

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< PointTPointCloud
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 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_

Detailed Description

template<typename PointT>
class pcl::search::Search< PointT >

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.

Note:
In case of an error, all methods are supposed to return 0 as the number of neighbors found.
libpcl_search deals with three-dimensional search problems. For higher level dimensional search, please refer to the libpcl_kdtree module.
Author:
Radu B. Rusu

Definition at line 73 of file search.h.


Member Typedef Documentation

template<typename PointT>
typedef boost::shared_ptr<const pcl::search::Search<PointT> > pcl::search::Search< PointT >::ConstPtr
template<typename PointT>
typedef boost::shared_ptr<const std::vector<int> > pcl::search::Search< PointT >::IndicesConstPtr
template<typename PointT>
typedef boost::shared_ptr<std::vector<int> > pcl::search::Search< PointT >::IndicesPtr
template<typename PointT>
typedef pcl::PointCloud<PointT> pcl::search::Search< PointT >::PointCloud
template<typename PointT>
typedef PointCloud::ConstPtr pcl::search::Search< PointT >::PointCloudConstPtr
template<typename PointT>
typedef PointCloud::Ptr pcl::search::Search< PointT >::PointCloudPtr
template<typename PointT>
typedef boost::shared_ptr<pcl::search::Search<PointT> > pcl::search::Search< PointT >::Ptr

Constructor & Destructor Documentation

template<typename PointT>
pcl::search::Search< PointT >::Search ( const std::string &  name = "",
bool  sorted = false 
) [inline]

Constructor.

Definition at line 87 of file search.h.

template<typename PointT>
virtual pcl::search::Search< PointT >::~Search ( ) [inline, virtual]

Destructor.

Definition at line 97 of file search.h.


Member Function Documentation

template<typename PointT>
virtual IndicesConstPtr pcl::search::Search< PointT >::getIndices ( ) const [inline, virtual]

Get a pointer to the vector of indices used.

Definition at line 139 of file search.h.

template<typename PointT>
virtual PointCloudConstPtr pcl::search::Search< PointT >::getInputCloud ( ) const [inline, virtual]

Get a pointer to the input point cloud dataset.

Definition at line 132 of file search.h.

template<typename PointT>
virtual const std::string& pcl::search::Search< PointT >::getName ( ) const [inline, virtual]

returns the search method name

Definition at line 104 of file search.h.

template<typename PointT>
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.

Parameters:
[in]pointthe given query point
[in]kthe number of neighbors to search for
[out]k_indicesthe resultant indices of the neighboring points (must be resized to k a priori!)
[out]k_sqr_distancesthe resultant squared distances to the neighboring points (must be resized to k a priori!)
Returns:
number of neighbors found

Implemented in pcl::search::OrganizedNeighbor< PointT >, pcl::search::FlannSearch< PointT, FlannDistance >, pcl::search::Octree< PointT, LeafTWrap, BranchTWrap, OctreeT >, pcl::search::KdTree< PointT >, and pcl::search::BruteForce< PointT >.

template<typename PointT>
virtual 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 [inline, virtual]

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

Attention:
This method does not do any bounds checking for the input index (i.e., index >= cloud.points.size () || index < 0), and assumes valid (i.e., finite) data.
Parameters:
[in]cloudthe point cloud data
[in]indexa valid index in cloud representing a valid (i.e., finite) query point
[in]kthe number of neighbors to search for
[out]k_indicesthe resultant indices of the neighboring points (must be resized to k a priori!)
[out]k_sqr_distancesthe resultant squared distances to the neighboring points (must be resized to k a priori!)
Returns:
number of neighbors found
Exceptions:
assertsin 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 195 of file search.h.

template<typename PointT>
virtual int pcl::search::Search< PointT >::nearestKSearch ( int  index,
int  k,
std::vector< int > &  k_indices,
std::vector< float > &  k_sqr_distances 
) const [inline, virtual]

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

Attention:
This method does not do any bounds checking for the input index (i.e., index >= cloud.points.size () || index < 0), and assumes valid (i.e., finite) data.
Parameters:
[in]indexa 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]kthe number of neighbors to search for
[out]k_indicesthe resultant indices of the neighboring points (must be resized to k a priori!)
[out]k_sqr_distancesthe resultant squared distances to the neighboring points (must be resized to k a priori!)
Returns:
number of neighbors found
Exceptions:
assertsin 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 220 of file search.h.

template<typename PointT>
virtual 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 [inline, virtual]

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

Parameters:
[in]cloudthe point cloud data
[in]indicesa vector of point cloud indices to query for nearest neighbors
[in]kthe number of neighbors to search for
[out]k_indicesthe resultant indices of the neighboring points, k_indices[i] corresponds to the neighbors of the query point i
[out]k_sqr_distancesthe resultant squared distances to the neighboring points, k_sqr_distances[i] corresponds to the neighbors of the query point i

Definition at line 245 of file search.h.

template<typename PointT>
template<typename PointTDiff >
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.

Parameters:
[in]pointthe given query point
[in]kthe number of neighbors to search for
[out]k_indicesthe resultant indices of the neighboring points (must be resized to k a priori!)
[out]k_sqr_distancesthe resultant squared distances to the neighboring points (must be resized to k a priori!)
Returns:
number of neighbors found

Definition at line 166 of file search.h.

template<typename PointT>
template<typename PointTDiff >
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).

Parameters:
[in]cloudthe point cloud data
[in]indicesa vector of point cloud indices to query for nearest neighbors
[in]kthe number of neighbors to search for
[out]k_indicesthe resultant indices of the neighboring points, k_indices[i] corresponds to the neighbors of the query point i
[out]k_sqr_distancesthe resultant squared distances to the neighboring points, k_sqr_distances[i] corresponds to the neighbors of the query point i
Note:
This method copies the input point cloud of type PointTDiff to a temporary cloud of type PointT and performs the batch search on the new cloud. You should prefer the single-point search if you don't use a search algorithm that accelerates batch NN search.

Definition at line 273 of file search.h.

template<typename PointT>
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.

Parameters:
[in]pointthe given query point
[in]radiusthe radius of the sphere bounding all of p_q's neighbors
[out]k_indicesthe resultant indices of the neighboring points
[out]k_sqr_distancesthe resultant squared distances to the neighboring points
[in]max_nnif 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.
Returns:
number of neighbors found in radius

Implemented in pcl::search::Octree< PointT, LeafTWrap, BranchTWrap, OctreeT >, pcl::search::FlannSearch< PointT, FlannDistance >, pcl::search::KdTree< PointT >, pcl::search::OrganizedNeighbor< PointT >, and pcl::search::BruteForce< PointT >.

template<typename PointT>
virtual 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 [inline, virtual]

Search for all the nearest neighbors of the query point in a given radius.

Attention:
This method does not do any bounds checking for the input index (i.e., index >= cloud.points.size () || index < 0), and assumes valid (i.e., finite) data.
Parameters:
[in]cloudthe point cloud data
[in]indexa valid index in cloud representing a valid (i.e., finite) query point
[in]radiusthe radius of the sphere bounding all of p_q's neighbors
[out]k_indicesthe resultant indices of the neighboring points
[out]k_sqr_distancesthe resultant squared distances to the neighboring points
[in]max_nnif 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.
Returns:
number of neighbors found in radius
Exceptions:
assertsin 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 359 of file search.h.

template<typename PointT>
virtual 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 [inline, virtual]

Search for all the nearest neighbors of the query point in a given radius (zero-copy).

Attention:
This method does not do any bounds checking for the input index (i.e., index >= cloud.points.size () || index < 0), and assumes valid (i.e., finite) data.
Parameters:
[in]indexa 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]radiusthe radius of the sphere bounding all of p_q's neighbors
[out]k_indicesthe resultant indices of the neighboring points
[out]k_sqr_distancesthe resultant squared distances to the neighboring points
[in]max_nnif 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.
Returns:
number of neighbors found in radius
Exceptions:
assertsin 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 387 of file search.h.

template<typename PointT>
virtual 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 [inline, virtual]

Search for all the nearest neighbors of the query point in a given radius.

Parameters:
[in]cloudthe point cloud data
[in]indicesthe indices in cloud. If indices is empty, neighbors will be searched for all points.
[in]radiusthe radius of the sphere bounding all of p_q's neighbors
[out]k_indicesthe resultant indices of the neighboring points, k_indices[i] corresponds to the neighbors of the query point i
[out]k_sqr_distancesthe resultant squared distances to the neighboring points, k_sqr_distances[i] corresponds to the neighbors of the query point i
[in]max_nnif 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 413 of file search.h.

template<typename PointT>
template<typename PointTDiff >
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.

Parameters:
[in]pointthe given query point
[in]radiusthe radius of the sphere bounding all of p_q's neighbors
[out]k_indicesthe resultant indices of the neighboring points
[out]k_sqr_distancesthe resultant squared distances to the neighboring points
[in]max_nnif 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.
Returns:
number of neighbors found in radius

Definition at line 329 of file search.h.

template<typename PointT>
template<typename PointTDiff >
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.

Parameters:
[in]cloudthe point cloud data
[in]indicesa vector of point cloud indices to query for nearest neighbors
[in]radiusthe radius of the sphere bounding all of p_q's neighbors
[out]k_indicesthe resultant indices of the neighboring points, k_indices[i] corresponds to the neighbors of the query point i
[out]k_sqr_distancesthe resultant squared distances to the neighboring points, k_sqr_distances[i] corresponds to the neighbors of the query point i
[in]max_nnif 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.
Note:
This method copies the input point cloud of type PointTDiff to a temporary cloud of type PointT and performs the batch search on the new cloud. You should prefer the single-point search if you don't use a search algorithm that accelerates batch NN search.

Definition at line 449 of file search.h.

template<typename PointT>
virtual void pcl::search::Search< PointT >::setInputCloud ( const PointCloudConstPtr cloud,
const IndicesConstPtr indices = IndicesConstPtr () 
) [inline, virtual]

Pass the input dataset that the search will be performed on.

Parameters:
[in]clouda const pointer to the PointCloud data
[in]indicesthe 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 124 of file search.h.

template<typename PointT>
virtual void pcl::search::Search< PointT >::setSortedResults ( bool  sorted) [inline, virtual]

sets whether the results should be sorted (ascending in the distance) or not

Parameters:
[in]sortedshould 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 >.

Definition at line 114 of file search.h.

template<typename PointT >
void pcl::search::Search< PointT >::sortResults ( std::vector< int > &  indices,
std::vector< float > &  distances 
) const [protected]

Definition at line 504 of file search.h.


Member Data Documentation

template<typename PointT>
IndicesConstPtr pcl::search::Search< PointT >::indices_ [protected]

Definition at line 481 of file search.h.

template<typename PointT>
PointCloudConstPtr pcl::search::Search< PointT >::input_ [protected]

Definition at line 480 of file search.h.

template<typename PointT>
std::string pcl::search::Search< PointT >::name_ [protected]

Definition at line 483 of file search.h.

template<typename PointT>
bool pcl::search::Search< PointT >::sorted_results_ [protected]

Definition at line 482 of file search.h.


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


pcl
Author(s): Open Perception
autogenerated on Mon Oct 6 2014 03:20:27