Implementation of a simple brute force search algorithm. More...
#include <brute_force.h>
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 |
Implementation of a simple brute force search algorithm.
Definition at line 52 of file brute_force.h.
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.
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.
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.
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.
pcl::search::BruteForce< PointT >::BruteForce | ( | bool | sorted_results = false | ) | [inline] |
Definition at line 88 of file brute_force.h.
virtual pcl::search::BruteForce< PointT >::~BruteForce | ( | ) | [inline, virtual] |
Destructor for KdTree.
Definition at line 95 of file brute_force.h.
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.
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.
float pcl::search::BruteForce< PointT >::getDistSqr | ( | const PointT & | point1, |
const PointT & | point2 | ||
) | const [private] |
Definition at line 46 of file brute_force.hpp.
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.
[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_distances | the resultant squared distances to the neighboring points (must be resized to k a priori!) |
Implements pcl::search::Search< PointT >.
Definition at line 54 of file brute_force.hpp.
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.
[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 335 of file brute_force.hpp.
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.
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.