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>
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... | |
Public Types | |
typedef boost::shared_ptr < const FlannSearch< PointT > > | ConstPtr |
typedef boost::shared_ptr < FlannSearch< PointT > > | Ptr |
Public Member Functions | |
FlannSearch (bool sorted=true, FlannIndexCreator *creator=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 | |
FlannIndexCreator * | 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 |
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.
Definition at line 67 of file flann_search.h.
typedef boost::shared_ptr<const FlannSearch<PointT> > pcl::search::FlannSearch< PointT, FlannDistance >::ConstPtr |
Reimplemented from pcl::search::Search< PointT >.
Definition at line 89 of file flann_search.h.
typedef flann::NNIndex< FlannDistance > pcl::search::FlannSearch< PointT, FlannDistance >::Index [private] |
Definition at line 74 of file flann_search.h.
typedef boost::shared_ptr<flann::NNIndex <FlannDistance > > pcl::search::FlannSearch< PointT, FlannDistance >::IndexPtr [private] |
Definition at line 75 of file flann_search.h.
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.
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.
typedef boost::shared_ptr<const flann::Matrix <float> > pcl::search::FlannSearch< PointT, FlannDistance >::MatrixConstPtr [private] |
Definition at line 77 of file flann_search.h.
typedef boost::shared_ptr<flann::Matrix <float> > pcl::search::FlannSearch< PointT, FlannDistance >::MatrixPtr [private] |
Definition at line 76 of file flann_search.h.
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.
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.
typedef pcl::PointRepresentation<PointT> pcl::search::FlannSearch< PointT, FlannDistance >::PointRepresentation [private] |
Definition at line 79 of file flann_search.h.
typedef boost::shared_ptr<const PointRepresentation> pcl::search::FlannSearch< PointT, FlannDistance >::PointRepresentationConstPtr [private] |
Definition at line 81 of file flann_search.h.
typedef boost::shared_ptr<FlannSearch<PointT> > pcl::search::FlannSearch< PointT, FlannDistance >::Ptr |
Reimplemented from pcl::search::Search< PointT >.
Definition at line 88 of file flann_search.h.
pcl::search::FlannSearch< PointT, FlannDistance >::FlannSearch | ( | bool | sorted = true , |
FlannIndexCreator * | creator = new KdTreeIndexCreator() |
||
) |
Definition at line 57 of file flann_search.hpp.
pcl::search::FlannSearch< PointT, FlannDistance >::~FlannSearch | ( | ) | [virtual] |
Destructor for FlannSearch.
Definition at line 66 of file flann_search.hpp.
void pcl::search::FlannSearch< PointT, FlannDistance >::convertInputToFlannMatrix | ( | ) | [protected] |
converts the input data to a format usable by FLANN
Definition at line 342 of file flann_search.hpp.
double pcl::search::FlannSearch< PointT, FlannDistance >::getEpsilon | ( | ) | [inline] |
Get the search epsilon precision (error bound) for nearest neighbors searches.
Definition at line 146 of file flann_search.h.
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 220 of file flann_search.h.
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.
[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 86 of file flann_search.hpp.
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.
[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 127 of file flann_search.hpp.
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.
[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. |
Implements pcl::search::Search< PointT >.
Definition at line 213 of file flann_search.hpp.
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.
[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 |
Definition at line 255 of file flann_search.hpp.
void pcl::search::FlannSearch< PointT, FlannDistance >::setEpsilon | ( | double | eps | ) | [inline] |
Set the search epsilon precision (error bound) for nearest neighbors searches.
[in] | eps | precision (error bound) for nearest neighbors searches |
Definition at line 139 of file flann_search.h.
void pcl::search::FlannSearch< PointT, FlannDistance >::setInputCloud | ( | const PointCloudConstPtr & | cloud, |
const IndicesConstPtr & | indices = IndicesConstPtr () |
||
) | [inline, virtual] |
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 |
Reimplemented from pcl::search::Search< PointT >.
Definition at line 75 of file flann_search.hpp.
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.
[in] | point_representation | the const boost shared pointer to a PointRepresentation |
Definition at line 212 of file flann_search.h.
FlannIndexCreator* 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 237 of file flann_search.h.
int pcl::search::FlannSearch< PointT, FlannDistance >::dim_ [protected] |
Definition at line 250 of file flann_search.h.
float pcl::search::FlannSearch< PointT, FlannDistance >::eps_ [protected] |
Epsilon for approximate NN search.
Definition at line 245 of file flann_search.h.
bool pcl::search::FlannSearch< PointT, FlannDistance >::identity_mapping_ [protected] |
Definition at line 253 of file flann_search.h.
IndexPtr pcl::search::FlannSearch< PointT, FlannDistance >::index_ [protected] |
The FLANN index.
Definition at line 233 of file flann_search.h.
std::vector<int> pcl::search::FlannSearch< PointT, FlannDistance >::index_mapping_ [protected] |
Definition at line 252 of file flann_search.h.
bool pcl::search::FlannSearch< PointT, FlannDistance >::input_copied_for_flann_ [protected] |
Definition at line 246 of file flann_search.h.
MatrixPtr pcl::search::FlannSearch< PointT, FlannDistance >::input_flann_ [protected] |
Input data in FLANN format.
Definition at line 241 of file flann_search.h.
PointRepresentationConstPtr pcl::search::FlannSearch< PointT, FlannDistance >::point_representation_ [protected] |
Definition at line 248 of file flann_search.h.