Defines | Functions | Variables
test_search.cpp File Reference
#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/smart_ptr/shared_array.hpp>
#include <boost/random/mersenne_twister.hpp>
#include <boost/random/uniform_int.hpp>
#include <boost/random/uniform_real.hpp>
#include <boost/random/variate_generator.hpp>
#include <pcl/common/time.h>
Include dependency graph for test/test_search.cpp:

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 Documentation

#define DEBUG_OUT   1

if set to value other than 0 -> fine grained output

Definition at line 56 of file test/test_search.cpp.

#define EXCESSIVE_TESTING   0

Definition at line 57 of file test/test_search.cpp.

Definition at line 68 of file test/test_search.cpp.

Definition at line 70 of file test/test_search.cpp.

Definition at line 69 of file test/test_search.cpp.

Definition at line 71 of file test/test_search.cpp.

Definition at line 59 of file test/test_search.cpp.

Definition at line 64 of file test/test_search.cpp.

Definition at line 60 of file test/test_search.cpp.

Definition at line 65 of file test/test_search.cpp.

Definition at line 63 of file test/test_search.cpp.

Definition at line 61 of file test/test_search.cpp.

Definition at line 66 of file test/test_search.cpp.

Definition at line 62 of file test/test_search.cpp.

Definition at line 67 of file test/test_search.cpp.


Function Documentation

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

Parameters:
indices1
distances1
name1
indices2
distances2
name2
epsthreshold for comparing the distances
Returns:
true if both sets are the same, false otherwise

Definition at line 235 of file test/test_search.cpp.

void createIndices ( std::vector< int > &  indices,
unsigned  max_index 
)

create an approx 50% view (subset) of a cloud.

Parameters:
indices
max_indexhighest accented index usually given by cloud->size () - 1

Definition at line 544 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

Parameters:
[out]query_indicesresulting query indices - not guaranteed to have size of query_count but guaranteed not to exceed that value
cloudinput cloud required to check for nans and to get number of points
[in]query_countmaximum number of query points

Definition at line 529 of file test/test_search.cpp.

int main ( int  argc,
char **  argv 
)

Definition at line 564 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 420 of file test/test_search.cpp.

TEST ( PCL  ,
unorganized_dense_cloud_View_KNN   
)

Definition at line 428 of file test/test_search.cpp.

TEST ( PCL  ,
unorganized_sparse_cloud_Complete_KNN   
)

Definition at line 436 of file test/test_search.cpp.

TEST ( PCL  ,
unorganized_sparse_cloud_View_KNN   
)

Definition at line 443 of file test/test_search.cpp.

TEST ( PCL  ,
unorganized_dense_cloud_Complete_Radius   
)

Definition at line 451 of file test/test_search.cpp.

TEST ( PCL  ,
unorganized_grid_cloud_Complete_Radius   
)

Definition at line 459 of file test/test_search.cpp.

TEST ( PCL  ,
unorganized_dense_cloud_View_Radius   
)

Definition at line 475 of file test/test_search.cpp.

TEST ( PCL  ,
unorganized_sparse_cloud_Complete_Radius   
)

Definition at line 483 of file test/test_search.cpp.

TEST ( PCL  ,
unorganized_sparse_cloud_View_Radius   
)

Definition at line 490 of file test/test_search.cpp.

TEST ( PCL  ,
Organized_Sparse_Complete_KNN   
)

Definition at line 497 of file test/test_search.cpp.

TEST ( PCL  ,
Organized_Sparse_View_KNN   
)

Definition at line 504 of file test/test_search.cpp.

TEST ( PCL  ,
Organized_Sparse_Complete_Radius   
)

Definition at line 511 of file test/test_search.cpp.

TEST ( PCL  ,
Organized_Sparse_View_Radius   
)

Definition at line 518 of file test/test_search.cpp.

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

Parameters:
cloudthe input point cloud
search_methodsvector of all search methods to be tested
query_indicesindices of query points in the point cloud (not necessarily in input_indices)
input_indicesindices defining a subset of the point cloud.

Definition at line 283 of file test/test_search.cpp.

bool testOrder ( const vector< float > &  distances,
const string &  name 
)

tests whether the ordering of results is ascending on distances

Parameters:
distancesresulting distances from a search
namename of the search method that returned these distances
Returns:
true if distances in weak ascending order, false otherwise

Definition at line 166 of file test/test_search.cpp.

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

Parameters:
cloudthe input point cloud
search_methodsvector of all search methods to be tested
query_indicesindices of query points in the point cloud (not necessarily in input_indices)
input_indicesindices defining a subset of the point cloud.

Definition at line 354 of file test/test_search.cpp.

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

Parameters:
indices_maskdefines the subset of allowed points (view) in the result of the search
nan_maskdefines a lookup that indicates whether a point at a given position is finite or not
indicesresult of a search to be tested
namename of search method that returned the result
Returns:
true if result is valid, false otherwise

Definition at line 193 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

Parameters:
indicesresulting indices from a search
namename of the search method that returned these distances
Returns:
true if indices are unique, false otherwise

Definition at line 138 of file test/test_search.cpp.


Variable Documentation

instance of brute force search method to be tested

Definition at line 111 of file test/test_search.cpp.

instance of KDTree search method to be tested

Definition at line 114 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 120 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 108 of file test/test_search.cpp.

list of search methods for organized search test

Definition at line 126 of file test/test_search.cpp.

organized point cloud

Definition at line 131 of file test/test_search.cpp.

const unsigned int query_count = 100

number of search operations on ordered point clouds

Definition at line 84 of file test/test_search.cpp.

unorganized point cloud

lists of indices to be used as query points for various search methods and different cloud types

Definition at line 129 of file test/test_search.cpp.

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 105 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 81 of file test/test_search.cpp.

list of search methods for unorganized search test

Definition at line 123 of file test/test_search.cpp.

unorganized point cloud

Definition at line 130 of file test/test_search.cpp.



pcl
Author(s): Open Perception
autogenerated on Mon Oct 6 2014 03:19:14