#include <gtest/gtest.h>
#include <pcl/search/brute_force.h>
#include <pcl/search/kdtree.h>
#include <pcl/search/organized.h>
#include <pcl/search/octree.h>
#include <pcl/io/pcd_io.h>
#include "boost.h"
#include <pcl/common/time.h>
Go to the source code of this file.
Defines | |
#define | DEBUG_OUT 1 |
if set to value other than 0 -> fine grained output | |
#define | EXCESSIVE_TESTING 0 |
#define | TEST_ORGANIZED_SPARSE_COMPLETE_KNN 1 |
#define | TEST_ORGANIZED_SPARSE_COMPLETE_RADIUS 1 |
#define | TEST_ORGANIZED_SPARSE_VIEW_KNN 1 |
#define | TEST_ORGANIZED_SPARSE_VIEW_RADIUS 1 |
#define | TEST_unorganized_dense_cloud_COMPLETE_KNN 1 |
#define | TEST_unorganized_dense_cloud_COMPLETE_RADIUS 1 |
#define | TEST_unorganized_dense_cloud_VIEW_KNN 1 |
#define | TEST_unorganized_dense_cloud_VIEW_RADIUS 1 |
#define | TEST_unorganized_grid_cloud_COMPLETE_RADIUS 1 |
#define | TEST_unorganized_sparse_cloud_COMPLETE_KNN 1 |
#define | TEST_unorganized_sparse_cloud_COMPLETE_RADIUS 1 |
#define | TEST_unorganized_sparse_cloud_VIEW_KNN 1 |
#define | TEST_unorganized_sparse_cloud_VIEW_RADIUS 1 |
Functions | |
bool | compareResults (const std::vector< int > &indices1, const ::vector< float > &distances1, const std::string &name1, const std::vector< int > &indices2, const ::vector< float > &distances2, const std::string &name2, float eps) |
compares two sets of search results | |
void | createIndices (std::vector< int > &indices, unsigned max_index) |
create an approx 50% view (subset) of a cloud. | |
void | createQueryIndices (std::vector< int > &query_indices, PointCloud< PointXYZ >::ConstPtr point_cloud, unsigned query_count) |
create subset of point in cloud to use as query points | |
int | main (int argc, char **argv) |
boost::variate_generator < boost::mt19937, boost::uniform_real< float > > | rand_float (boost::mt19937(), boost::uniform_real< float >(0, 1)) |
uniform distributed random number generator for floats in the range [0;1] | |
boost::variate_generator < boost::mt19937, boost::uniform_int< unsigned > > | rand_uint (boost::mt19937(), boost::uniform_int< unsigned >(0, 10)) |
uniform distributed random number generator for unsigned it in range [0;10] | |
TEST (PCL, unorganized_dense_cloud_Complete_KNN) | |
TEST (PCL, unorganized_dense_cloud_View_KNN) | |
TEST (PCL, unorganized_sparse_cloud_Complete_KNN) | |
TEST (PCL, unorganized_sparse_cloud_View_KNN) | |
TEST (PCL, unorganized_dense_cloud_Complete_Radius) | |
TEST (PCL, unorganized_grid_cloud_Complete_Radius) | |
TEST (PCL, unorganized_dense_cloud_View_Radius) | |
TEST (PCL, unorganized_sparse_cloud_Complete_Radius) | |
TEST (PCL, unorganized_sparse_cloud_View_Radius) | |
TEST (PCL, Organized_Sparse_Complete_KNN) | |
TEST (PCL, Organized_Sparse_View_KNN) | |
TEST (PCL, Organized_Sparse_Complete_Radius) | |
TEST (PCL, Organized_Sparse_View_Radius) | |
template<typename PointT > | |
void | testKNNSearch (typename PointCloud< PointT >::ConstPtr point_cloud, vector< search::Search< PointT > * > search_methods, const vector< int > &query_indices, const vector< int > &input_indices=vector< int >()) |
does KNN search and tests the results to be unique, valid and ordered. Additionally it test whether all test methods are returning the same results | |
bool | testOrder (const vector< float > &distances, const string &name) |
tests whether the ordering of results is ascending on distances | |
template<typename PointT > | |
void | testRadiusSearch (typename PointCloud< PointT >::ConstPtr point_cloud, vector< search::Search< PointT > * > search_methods, const vector< int > &query_indices, const vector< int > &input_indices=vector< int >()) |
does radius search and tests the results to be unique, valid and ordered. Additionally it test whether all test methods are returning the same results | |
template<typename PointT > | |
bool | testResultValidity (const typename PointCloud< PointT >::ConstPtr point_cloud, const vector< bool > &indices_mask, const vector< bool > &nan_mask, const vector< int > &indices, const vector< int > &, const string &name) |
test whether the results are from the view (subset of the cloud) given by input_indices and also not Nan | |
bool | testUniqueness (const vector< int > &indices, const string &name) |
Variables | |
pcl::search::BruteForce < pcl::PointXYZ > | brute_force |
instance of brute force search method to be tested | |
pcl::search::KdTree < pcl::PointXYZ > | KDTree |
instance of KDTree search method to be tested | |
pcl::search::Octree < pcl::PointXYZ > | octree_search (0.1) |
instance of Octree search method to be tested | |
pcl::search::OrganizedNeighbor < pcl::PointXYZ > | organized |
instance of Organized search method to be tested | |
std::vector< int > | organized_input_indices |
used by the *_VIEW_* tests to use only a subset of points from the point cloud | |
vector< search::Search < PointXYZ > * > | organized_search_methods |
list of search methods for organized search test | |
PointCloud< PointXYZ >::Ptr | organized_sparse_cloud (new PointCloud< PointXYZ >) |
organized point cloud | |
vector< int > | organized_sparse_query_indices |
const unsigned int | query_count = 100 |
number of search operations on ordered point clouds | |
PointCloud< PointXYZ >::Ptr | unorganized_dense_cloud (new PointCloud< PointXYZ >) |
unorganized point cloud | |
vector< int > | unorganized_dense_cloud_query_indices |
lists of indices to be used as query points for various search methods and different cloud types | |
PointCloud< PointXYZ >::Ptr | unorganized_grid_cloud (new PointCloud< PointXYZ >) |
unorganized point cloud | |
std::vector< int > | unorganized_input_indices |
used by the *_VIEW_* tests to use only a subset of points from the point cloud | |
const unsigned int | unorganized_point_count = 1200 |
number of points used for creating unordered point clouds | |
vector< search::Search < PointXYZ > * > | unorganized_search_methods |
list of search methods for unorganized search test | |
PointCloud< PointXYZ >::Ptr | unorganized_sparse_cloud (new PointCloud< PointXYZ >) |
unorganized point cloud | |
vector< int > | unorganized_sparse_cloud_query_indices |
#define DEBUG_OUT 1 |
if set to value other than 0 -> fine grained output
Definition at line 52 of file test/test_search.cpp.
#define EXCESSIVE_TESTING 0 |
Definition at line 53 of file test/test_search.cpp.
#define TEST_ORGANIZED_SPARSE_COMPLETE_KNN 1 |
Definition at line 64 of file test/test_search.cpp.
#define TEST_ORGANIZED_SPARSE_COMPLETE_RADIUS 1 |
Definition at line 66 of file test/test_search.cpp.
#define TEST_ORGANIZED_SPARSE_VIEW_KNN 1 |
Definition at line 65 of file test/test_search.cpp.
#define TEST_ORGANIZED_SPARSE_VIEW_RADIUS 1 |
Definition at line 67 of file test/test_search.cpp.
Definition at line 55 of file test/test_search.cpp.
Definition at line 60 of file test/test_search.cpp.
#define TEST_unorganized_dense_cloud_VIEW_KNN 1 |
Definition at line 56 of file test/test_search.cpp.
#define TEST_unorganized_dense_cloud_VIEW_RADIUS 1 |
Definition at line 61 of file test/test_search.cpp.
Definition at line 59 of file test/test_search.cpp.
Definition at line 57 of file test/test_search.cpp.
Definition at line 62 of file test/test_search.cpp.
#define TEST_unorganized_sparse_cloud_VIEW_KNN 1 |
Definition at line 58 of file test/test_search.cpp.
Definition at line 63 of file test/test_search.cpp.
bool compareResults | ( | const std::vector< int > & | indices1, |
const ::vector< float > & | distances1, | ||
const std::string & | name1, | ||
const std::vector< int > & | indices2, | ||
const ::vector< float > & | distances2, | ||
const std::string & | name2, | ||
float | eps | ||
) |
compares two sets of search results
indices1 | |
distances1 | |
name1 | |
indices2 | |
distances2 | |
name2 | |
eps | threshold for comparing the distances |
Definition at line 231 of file test/test_search.cpp.
void createIndices | ( | std::vector< int > & | indices, |
unsigned | max_index | ||
) |
create an approx 50% view (subset) of a cloud.
indices | |
max_index | highest accented index usually given by cloud->size () - 1 |
Definition at line 540 of file test/test_search.cpp.
void createQueryIndices | ( | std::vector< int > & | query_indices, |
PointCloud< PointXYZ >::ConstPtr | point_cloud, | ||
unsigned | query_count | ||
) |
create subset of point in cloud to use as query points
[out] | query_indices | resulting query indices - not guaranteed to have size of query_count but guaranteed not to exceed that value |
cloud | input cloud required to check for nans and to get number of points | |
[in] | query_count | maximum number of query points |
Definition at line 525 of file test/test_search.cpp.
int main | ( | int | argc, |
char ** | argv | ||
) |
Definition at line 560 of file test/test_search.cpp.
boost::variate_generator< boost::mt19937, boost::uniform_real<float> > rand_float | ( | boost:: | mt19937(), |
boost::uniform_real< float > | 0, 1 | ||
) |
uniform distributed random number generator for floats in the range [0;1]
boost::variate_generator< boost::mt19937, boost::uniform_int<unsigned> > rand_uint | ( | boost:: | mt19937(), |
boost::uniform_int< unsigned > | 0, 10 | ||
) |
uniform distributed random number generator for unsigned it in range [0;10]
TEST | ( | PCL | , |
unorganized_dense_cloud_Complete_KNN | |||
) |
Definition at line 416 of file test/test_search.cpp.
TEST | ( | PCL | , |
unorganized_dense_cloud_View_KNN | |||
) |
Definition at line 424 of file test/test_search.cpp.
TEST | ( | PCL | , |
unorganized_sparse_cloud_Complete_KNN | |||
) |
Definition at line 432 of file test/test_search.cpp.
TEST | ( | PCL | , |
unorganized_sparse_cloud_View_KNN | |||
) |
Definition at line 439 of file test/test_search.cpp.
TEST | ( | PCL | , |
unorganized_dense_cloud_Complete_Radius | |||
) |
Definition at line 447 of file test/test_search.cpp.
TEST | ( | PCL | , |
unorganized_grid_cloud_Complete_Radius | |||
) |
Definition at line 455 of file test/test_search.cpp.
TEST | ( | PCL | , |
unorganized_dense_cloud_View_Radius | |||
) |
Definition at line 471 of file test/test_search.cpp.
TEST | ( | PCL | , |
unorganized_sparse_cloud_Complete_Radius | |||
) |
Definition at line 479 of file test/test_search.cpp.
TEST | ( | PCL | , |
unorganized_sparse_cloud_View_Radius | |||
) |
Definition at line 486 of file test/test_search.cpp.
TEST | ( | PCL | , |
Organized_Sparse_Complete_KNN | |||
) |
Definition at line 493 of file test/test_search.cpp.
TEST | ( | PCL | , |
Organized_Sparse_View_KNN | |||
) |
Definition at line 500 of file test/test_search.cpp.
TEST | ( | PCL | , |
Organized_Sparse_Complete_Radius | |||
) |
Definition at line 507 of file test/test_search.cpp.
TEST | ( | PCL | , |
Organized_Sparse_View_Radius | |||
) |
Definition at line 514 of file test/test_search.cpp.
void testKNNSearch | ( | typename PointCloud< PointT >::ConstPtr | point_cloud, |
vector< search::Search< PointT > * > | search_methods, | ||
const vector< int > & | query_indices, | ||
const vector< int > & | input_indices = vector<int> () |
||
) |
does KNN search and tests the results to be unique, valid and ordered. Additionally it test whether all test methods are returning the same results
cloud | the input point cloud |
search_methods | vector of all search methods to be tested |
query_indices | indices of query points in the point cloud (not necessarily in input_indices) |
input_indices | indices defining a subset of the point cloud. |
Definition at line 279 of file test/test_search.cpp.
tests whether the ordering of results is ascending on distances
distances | resulting distances from a search |
name | name of the search method that returned these distances |
Definition at line 162 of file test/test_search.cpp.
void testRadiusSearch | ( | typename PointCloud< PointT >::ConstPtr | point_cloud, |
vector< search::Search< PointT > * > | search_methods, | ||
const vector< int > & | query_indices, | ||
const vector< int > & | input_indices = vector<int> () |
||
) |
does radius search and tests the results to be unique, valid and ordered. Additionally it test whether all test methods are returning the same results
cloud | the input point cloud |
search_methods | vector of all search methods to be tested |
query_indices | indices of query points in the point cloud (not necessarily in input_indices) |
input_indices | indices defining a subset of the point cloud. |
Definition at line 350 of file test/test_search.cpp.
bool testResultValidity | ( | const typename PointCloud< PointT >::ConstPtr | point_cloud, |
const vector< bool > & | indices_mask, | ||
const vector< bool > & | nan_mask, | ||
const vector< int > & | indices, | ||
const vector< int > & | , | ||
const string & | name | ||
) |
test whether the results are from the view (subset of the cloud) given by input_indices and also not Nan
indices_mask | defines the subset of allowed points (view) in the result of the search |
nan_mask | defines a lookup that indicates whether a point at a given position is finite or not |
indices | result of a search to be tested |
name | name of search method that returned the result |
Definition at line 189 of file test/test_search.cpp.
bool testUniqueness | ( | const vector< int > & | indices, |
const string & | name | ||
) |
test whether the result of a search containes unique point ids or not
indices | resulting indices from a search |
name | name of the search method that returned these distances |
Definition at line 134 of file test/test_search.cpp.
instance of brute force search method to be tested
Definition at line 107 of file test/test_search.cpp.
instance of KDTree search method to be tested
Definition at line 110 of file test/test_search.cpp.
instance of Octree search method to be tested
instance of Organized search method to be tested
Definition at line 116 of file test/test_search.cpp.
std::vector<int> organized_input_indices |
used by the *_VIEW_* tests to use only a subset of points from the point cloud
Definition at line 104 of file test/test_search.cpp.
vector<search::Search<PointXYZ>* > organized_search_methods |
list of search methods for organized search test
Definition at line 122 of file test/test_search.cpp.
PointCloud<PointXYZ>::Ptr organized_sparse_cloud(new PointCloud< PointXYZ >) |
organized point cloud
vector<int> organized_sparse_query_indices |
Definition at line 127 of file test/test_search.cpp.
const unsigned int query_count = 100 |
number of search operations on ordered point clouds
Definition at line 80 of file test/test_search.cpp.
PointCloud<PointXYZ>::Ptr unorganized_dense_cloud(new PointCloud< PointXYZ >) |
unorganized point cloud
vector<int> unorganized_dense_cloud_query_indices |
lists of indices to be used as query points for various search methods and different cloud types
Definition at line 125 of file test/test_search.cpp.
PointCloud<PointXYZ>::Ptr unorganized_grid_cloud(new PointCloud< PointXYZ >) |
unorganized point cloud
std::vector<int> unorganized_input_indices |
used by the *_VIEW_* tests to use only a subset of points from the point cloud
Definition at line 101 of file test/test_search.cpp.
const unsigned int unorganized_point_count = 1200 |
number of points used for creating unordered point clouds
Definition at line 77 of file test/test_search.cpp.
vector<search::Search<PointXYZ>* > unorganized_search_methods |
list of search methods for unorganized search test
Definition at line 119 of file test/test_search.cpp.
PointCloud<PointXYZ>::Ptr unorganized_sparse_cloud(new PointCloud< PointXYZ >) |
unorganized point cloud
vector<int> unorganized_sparse_cloud_query_indices |
Definition at line 126 of file test/test_search.cpp.