Classes | Public Member Functions | Private Types | Private Member Functions
pcl::search::BruteForce< PointT > Class Template Reference

Implementation of a simple brute force search algorithm. More...

#include <brute_force.h>

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

List of all members.

Classes

struct  Entry

Public Member Functions

 BruteForce (bool sorted_results=false)
int nearestKSearch (const PointT &point, int k, std::vector< int > &k_indices, std::vector< float > &k_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 ~BruteForce ()
 Destructor for KdTree.

Private Types

typedef boost::shared_ptr
< const std::vector< int > > 
IndicesConstPtr
typedef boost::shared_ptr
< std::vector< int > > 
IndicesPtr
typedef Search< PointT >
::PointCloud 
PointCloud
typedef Search< PointT >
::PointCloudConstPtr 
PointCloudConstPtr

Private Member Functions

int denseKSearch (const PointT &point, int k, std::vector< int > &k_indices, std::vector< float > &k_distances) const
int denseRadiusSearch (const PointT &point, double radius, std::vector< int > &k_indices, std::vector< float > &k_sqr_distances, unsigned int max_nn=0) const
float getDistSqr (const PointT &point1, const PointT &point2) const
int sparseKSearch (const PointT &point, int k, std::vector< int > &k_indices, std::vector< float > &k_distances) const
int sparseRadiusSearch (const PointT &point, double radius, std::vector< int > &k_indices, std::vector< float > &k_sqr_distances, unsigned int max_nn=0) const

Detailed Description

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

Implementation of a simple brute force search algorithm.

Author:
Suat Gedikli

Definition at line 52 of file brute_force.h.


Member Typedef Documentation

template<typename PointT >
typedef boost::shared_ptr<const std::vector<int> > pcl::search::BruteForce< PointT >::IndicesConstPtr [private]

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

Definition at line 58 of file brute_force.h.

template<typename PointT >
typedef boost::shared_ptr<std::vector<int> > pcl::search::BruteForce< PointT >::IndicesPtr [private]

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

Definition at line 57 of file brute_force.h.

template<typename PointT >
typedef Search<PointT>::PointCloud pcl::search::BruteForce< PointT >::PointCloud [private]

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

Definition at line 54 of file brute_force.h.

template<typename PointT >
typedef Search<PointT>::PointCloudConstPtr pcl::search::BruteForce< PointT >::PointCloudConstPtr [private]

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

Definition at line 55 of file brute_force.h.


Constructor & Destructor Documentation

template<typename PointT >
pcl::search::BruteForce< PointT >::BruteForce ( bool  sorted_results = false) [inline]

Definition at line 88 of file brute_force.h.

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

Destructor for KdTree.

Definition at line 95 of file brute_force.h.


Member Function Documentation

template<typename PointT >
int pcl::search::BruteForce< PointT >::denseKSearch ( const PointT point,
int  k,
std::vector< int > &  k_indices,
std::vector< float > &  k_distances 
) const [private]

Definition at line 72 of file brute_force.hpp.

template<typename PointT >
int pcl::search::BruteForce< PointT >::denseRadiusSearch ( const PointT point,
double  radius,
std::vector< int > &  k_indices,
std::vector< float > &  k_sqr_distances,
unsigned int  max_nn = 0 
) const [private]

Definition at line 219 of file brute_force.hpp.

template<typename PointT >
float pcl::search::BruteForce< PointT >::getDistSqr ( const PointT point1,
const PointT point2 
) const [private]

Definition at line 46 of file brute_force.hpp.

template<typename PointT >
int pcl::search::BruteForce< PointT >::nearestKSearch ( const PointT point,
int  k,
std::vector< int > &  k_indices,
std::vector< float > &  k_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_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 54 of file brute_force.hpp.

template<typename PointT >
int pcl::search::BruteForce< PointT >::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 335 of file brute_force.hpp.

template<typename PointT >
int pcl::search::BruteForce< PointT >::sparseKSearch ( const PointT point,
int  k,
std::vector< int > &  k_indices,
std::vector< float > &  k_distances 
) const [private]

Definition at line 140 of file brute_force.hpp.

template<typename PointT >
int pcl::search::BruteForce< PointT >::sparseRadiusSearch ( const PointT point,
double  radius,
std::vector< int > &  k_indices,
std::vector< float > &  k_sqr_distances,
unsigned int  max_nn = 0 
) const [private]

Definition at line 274 of file brute_force.hpp.


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


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