Classes | Public Types | Public Member Functions | Protected Member Functions | Protected Attributes | Private Types
pcl::search::FlannSearch< PointT, FlannDistance > Class Template Reference

search::FlannSearch is a generic FLANN wrapper class for the new search interface. It is able to wrap any FLANN index type, e.g. the kd tree as well as indices for high-dimensional searches and intended as a more powerful and cleaner successor to KdTreeFlann. More...

#include <flann_search.h>

Inheritance diagram for pcl::search::FlannSearch< PointT, FlannDistance >:
Inheritance graph
[legend]

List of all members.

Classes

class  FlannIndexCreator
 Helper class that creates a FLANN index from a given FLANN matrix. To use a FLANN index type with FlannSearch, implement this interface and pass an object of the new type to the FlannSearch constructor. See the implementation of KdTreeIndexCreator for an example. More...
class  KdTreeIndexCreator
 Creates a FLANN KdTreeSingleIndex from the given input data. More...
class  KMeansIndexCreator
 Creates a FLANN KdTreeSingleIndex from the given input data. More...

Public Types

typedef boost::shared_ptr
< const FlannSearch< PointT,
FlannDistance > > 
ConstPtr
typedef boost::shared_ptr
< FlannIndexCreator
FlannIndexCreatorPtr
typedef boost::shared_ptr
< FlannSearch< PointT,
FlannDistance > > 
Ptr

Public Member Functions

 FlannSearch (bool sorted=true, FlannIndexCreatorPtr creator=FlannIndexCreatorPtr(new KdTreeIndexCreator()))
double getEpsilon ()
 Get the search epsilon precision (error bound) for nearest neighbors searches.
PointRepresentationConstPtr const getPointRepresentation ()
 Get a pointer to the point representation used when converting points into k-D vectors.
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.
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.
int radiusSearch (const PointT &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.
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 the k-nearest neighbors for the given query point.
void setEpsilon (double eps)
 Set the search epsilon precision (error bound) for nearest neighbors searches.
virtual void setInputCloud (const PointCloudConstPtr &cloud, const IndicesConstPtr &indices=IndicesConstPtr())
 Provide a pointer to the input dataset.
void setPointRepresentation (const PointRepresentationConstPtr &point_representation)
 Provide a pointer to the point representation to use to convert points into k-D vectors.
virtual ~FlannSearch ()
 Destructor for FlannSearch.

Protected Member Functions

void convertInputToFlannMatrix ()
 converts the input data to a format usable by FLANN

Protected Attributes

FlannIndexCreatorPtr creator_
int dim_
float eps_
bool identity_mapping_
IndexPtr index_
std::vector< int > index_mapping_
bool input_copied_for_flann_
MatrixPtr input_flann_
PointRepresentationConstPtr point_representation_

Private Types

typedef flann::NNIndex
< FlannDistance > 
Index
typedef boost::shared_ptr
< flann::NNIndex
< FlannDistance > > 
IndexPtr
typedef boost::shared_ptr
< const std::vector< int > > 
IndicesConstPtr
typedef boost::shared_ptr
< std::vector< int > > 
IndicesPtr
typedef boost::shared_ptr
< const flann::Matrix< float > > 
MatrixConstPtr
typedef boost::shared_ptr
< flann::Matrix< float > > 
MatrixPtr
typedef Search< PointT >
::PointCloud 
PointCloud
typedef Search< PointT >
::PointCloudConstPtr 
PointCloudConstPtr
typedef
pcl::PointRepresentation
< PointT
PointRepresentation
typedef boost::shared_ptr
< const PointRepresentation
PointRepresentationConstPtr

Detailed Description

template<typename PointT, typename FlannDistance = flann::L2_Simple <float>>
class pcl::search::FlannSearch< PointT, FlannDistance >

search::FlannSearch is a generic FLANN wrapper class for the new search interface. It is able to wrap any FLANN index type, e.g. the kd tree as well as indices for high-dimensional searches and intended as a more powerful and cleaner successor to KdTreeFlann.

Author:
Andreas Muetzel

Definition at line 67 of file flann_search.h.


Member Typedef Documentation

template<typename PointT, typename FlannDistance = flann::L2_Simple <float>>
typedef boost::shared_ptr<const FlannSearch<PointT, FlannDistance> > pcl::search::FlannSearch< PointT, FlannDistance >::ConstPtr

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

Definition at line 89 of file flann_search.h.

template<typename PointT, typename FlannDistance = flann::L2_Simple <float>>
typedef boost::shared_ptr<FlannIndexCreator> pcl::search::FlannSearch< PointT, FlannDistance >::FlannIndexCreatorPtr

Definition at line 109 of file flann_search.h.

template<typename PointT, typename FlannDistance = flann::L2_Simple <float>>
typedef flann::NNIndex< FlannDistance > pcl::search::FlannSearch< PointT, FlannDistance >::Index [private]

Definition at line 74 of file flann_search.h.

template<typename PointT, typename FlannDistance = flann::L2_Simple <float>>
typedef boost::shared_ptr<flann::NNIndex <FlannDistance > > pcl::search::FlannSearch< PointT, FlannDistance >::IndexPtr [private]

Definition at line 75 of file flann_search.h.

template<typename PointT, typename FlannDistance = flann::L2_Simple <float>>
typedef boost::shared_ptr<const std::vector<int> > pcl::search::FlannSearch< PointT, FlannDistance >::IndicesConstPtr [private]

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

Definition at line 73 of file flann_search.h.

template<typename PointT, typename FlannDistance = flann::L2_Simple <float>>
typedef boost::shared_ptr<std::vector<int> > pcl::search::FlannSearch< PointT, FlannDistance >::IndicesPtr [private]

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

Definition at line 72 of file flann_search.h.

template<typename PointT, typename FlannDistance = flann::L2_Simple <float>>
typedef boost::shared_ptr<const flann::Matrix <float> > pcl::search::FlannSearch< PointT, FlannDistance >::MatrixConstPtr [private]

Definition at line 77 of file flann_search.h.

template<typename PointT, typename FlannDistance = flann::L2_Simple <float>>
typedef boost::shared_ptr<flann::Matrix <float> > pcl::search::FlannSearch< PointT, FlannDistance >::MatrixPtr [private]

Definition at line 76 of file flann_search.h.

template<typename PointT, typename FlannDistance = flann::L2_Simple <float>>
typedef Search<PointT>::PointCloud pcl::search::FlannSearch< PointT, FlannDistance >::PointCloud [private]

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

Definition at line 69 of file flann_search.h.

template<typename PointT, typename FlannDistance = flann::L2_Simple <float>>
typedef Search<PointT>::PointCloudConstPtr pcl::search::FlannSearch< PointT, FlannDistance >::PointCloudConstPtr [private]

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

Definition at line 70 of file flann_search.h.

template<typename PointT, typename FlannDistance = flann::L2_Simple <float>>
typedef pcl::PointRepresentation<PointT> pcl::search::FlannSearch< PointT, FlannDistance >::PointRepresentation [private]

Definition at line 79 of file flann_search.h.

template<typename PointT, typename FlannDistance = flann::L2_Simple <float>>
typedef boost::shared_ptr<const PointRepresentation> pcl::search::FlannSearch< PointT, FlannDistance >::PointRepresentationConstPtr [private]

Definition at line 81 of file flann_search.h.

template<typename PointT, typename FlannDistance = flann::L2_Simple <float>>
typedef boost::shared_ptr<FlannSearch<PointT, FlannDistance> > pcl::search::FlannSearch< PointT, FlannDistance >::Ptr

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

Definition at line 88 of file flann_search.h.


Constructor & Destructor Documentation

template<typename PointT , typename FlannDistance >
pcl::search::FlannSearch< PointT, FlannDistance >::FlannSearch ( bool  sorted = true,
FlannIndexCreatorPtr  creator = FlannIndexCreatorPtr (new KdTreeIndexCreator ()) 
)

Definition at line 64 of file flann_search.hpp.

template<typename PointT , typename FlannDistance >
pcl::search::FlannSearch< PointT, FlannDistance >::~FlannSearch ( ) [virtual]

Destructor for FlannSearch.

Definition at line 73 of file flann_search.hpp.


Member Function Documentation

template<typename PointT , typename FlannDistance >
void pcl::search::FlannSearch< PointT, FlannDistance >::convertInputToFlannMatrix ( ) [protected]

converts the input data to a format usable by FLANN

Definition at line 348 of file flann_search.hpp.

template<typename PointT, typename FlannDistance = flann::L2_Simple <float>>
double pcl::search::FlannSearch< PointT, FlannDistance >::getEpsilon ( ) [inline]

Get the search epsilon precision (error bound) for nearest neighbors searches.

Definition at line 177 of file flann_search.h.

template<typename PointT, typename FlannDistance = flann::L2_Simple <float>>
PointRepresentationConstPtr const pcl::search::FlannSearch< PointT, FlannDistance >::getPointRepresentation ( ) [inline]

Get a pointer to the point representation used when converting points into k-D vectors.

Definition at line 253 of file flann_search.h.

template<typename PointT, typename FlannDistance >
int pcl::search::FlannSearch< PointT, FlannDistance >::nearestKSearch ( const PointT point,
int  k,
std::vector< int > &  k_indices,
std::vector< float > &  k_sqr_distances 
) const [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

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

Definition at line 92 of file flann_search.hpp.

template<typename PointT, typename FlannDistance >
void pcl::search::FlannSearch< PointT, FlannDistance >::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.

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 133 of file flann_search.hpp.

template<typename PointT, typename FlannDistance >
int pcl::search::FlannSearch< PointT, FlannDistance >::radiusSearch ( const PointT point,
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.

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

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

Definition at line 219 of file flann_search.hpp.

template<typename PointT, typename FlannDistance >
void pcl::search::FlannSearch< PointT, FlannDistance >::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 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]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

Definition at line 261 of file flann_search.hpp.

template<typename PointT, typename FlannDistance = flann::L2_Simple <float>>
void pcl::search::FlannSearch< PointT, FlannDistance >::setEpsilon ( double  eps) [inline]

Set the search epsilon precision (error bound) for nearest neighbors searches.

Parameters:
[in]epsprecision (error bound) for nearest neighbors searches

Definition at line 170 of file flann_search.h.

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

Provide a pointer to the input dataset.

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

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

Definition at line 81 of file flann_search.hpp.

template<typename PointT, typename FlannDistance = flann::L2_Simple <float>>
void pcl::search::FlannSearch< PointT, FlannDistance >::setPointRepresentation ( const PointRepresentationConstPtr point_representation) [inline]

Provide a pointer to the point representation to use to convert points into k-D vectors.

Parameters:
[in]point_representationthe const boost shared pointer to a PointRepresentation

Definition at line 243 of file flann_search.h.


Member Data Documentation

template<typename PointT, typename FlannDistance = flann::L2_Simple <float>>
FlannIndexCreatorPtr pcl::search::FlannSearch< PointT, FlannDistance >::creator_ [protected]

The index creator, used to (re-) create the index when the search data is passed.

Definition at line 270 of file flann_search.h.

template<typename PointT, typename FlannDistance = flann::L2_Simple <float>>
int pcl::search::FlannSearch< PointT, FlannDistance >::dim_ [protected]

Definition at line 283 of file flann_search.h.

template<typename PointT, typename FlannDistance = flann::L2_Simple <float>>
float pcl::search::FlannSearch< PointT, FlannDistance >::eps_ [protected]

Epsilon for approximate NN search.

Definition at line 278 of file flann_search.h.

template<typename PointT, typename FlannDistance = flann::L2_Simple <float>>
bool pcl::search::FlannSearch< PointT, FlannDistance >::identity_mapping_ [protected]

Definition at line 286 of file flann_search.h.

template<typename PointT, typename FlannDistance = flann::L2_Simple <float>>
IndexPtr pcl::search::FlannSearch< PointT, FlannDistance >::index_ [protected]

The FLANN index.

Definition at line 266 of file flann_search.h.

template<typename PointT, typename FlannDistance = flann::L2_Simple <float>>
std::vector<int> pcl::search::FlannSearch< PointT, FlannDistance >::index_mapping_ [protected]

Definition at line 285 of file flann_search.h.

template<typename PointT, typename FlannDistance = flann::L2_Simple <float>>
bool pcl::search::FlannSearch< PointT, FlannDistance >::input_copied_for_flann_ [protected]

Definition at line 279 of file flann_search.h.

template<typename PointT, typename FlannDistance = flann::L2_Simple <float>>
MatrixPtr pcl::search::FlannSearch< PointT, FlannDistance >::input_flann_ [protected]

Input data in FLANN format.

Definition at line 274 of file flann_search.h.

template<typename PointT, typename FlannDistance = flann::L2_Simple <float>>
PointRepresentationConstPtr pcl::search::FlannSearch< PointT, FlannDistance >::point_representation_ [protected]

Definition at line 281 of file flann_search.h.


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


pcl
Author(s): Open Perception
autogenerated on Wed Aug 26 2015 15:46:56