00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037
00038 #include <gtest/gtest.h>
00039 #include <pcl/search/brute_force.h>
00040 #include <pcl/search/kdtree.h>
00041 #include <pcl/search/organized.h>
00042 #include <pcl/search/octree.h>
00043 #include <pcl/io/pcd_io.h>
00044 #include "boost.h"
00045
00046 #include <pcl/common/time.h>
00047
00048 using namespace pcl;
00049 using namespace std;
00050
00052 #define DEBUG_OUT 1
00053 #define EXCESSIVE_TESTING 0
00054
00055 #define TEST_unorganized_dense_cloud_COMPLETE_KNN 1
00056 #define TEST_unorganized_dense_cloud_VIEW_KNN 1
00057 #define TEST_unorganized_sparse_cloud_COMPLETE_KNN 1
00058 #define TEST_unorganized_sparse_cloud_VIEW_KNN 1
00059 #define TEST_unorganized_grid_cloud_COMPLETE_RADIUS 1
00060 #define TEST_unorganized_dense_cloud_COMPLETE_RADIUS 1
00061 #define TEST_unorganized_dense_cloud_VIEW_RADIUS 1
00062 #define TEST_unorganized_sparse_cloud_COMPLETE_RADIUS 1
00063 #define TEST_unorganized_sparse_cloud_VIEW_RADIUS 1
00064 #define TEST_ORGANIZED_SPARSE_COMPLETE_KNN 1
00065 #define TEST_ORGANIZED_SPARSE_VIEW_KNN 1
00066 #define TEST_ORGANIZED_SPARSE_COMPLETE_RADIUS 1
00067 #define TEST_ORGANIZED_SPARSE_VIEW_RADIUS 1
00068
00069 #if EXCESSIVE_TESTING
00070
00071 const unsigned int unorganized_point_count = 100000;
00072
00074 const unsigned int query_count = 5000;
00075 #else
00076
00077 const unsigned int unorganized_point_count = 1200;
00078
00080 const unsigned int query_count = 100;
00081 #endif
00082
00084 PointCloud<PointXYZ>::Ptr organized_sparse_cloud (new PointCloud<PointXYZ>);
00085
00087 PointCloud<PointXYZ>::Ptr unorganized_dense_cloud (new PointCloud<PointXYZ>);
00088
00090 PointCloud<PointXYZ>::Ptr unorganized_sparse_cloud (new PointCloud<PointXYZ>);
00091
00093 PointCloud<PointXYZ>::Ptr unorganized_grid_cloud (new PointCloud<PointXYZ>);
00094
00096 boost::variate_generator< boost::mt19937, boost::uniform_int<unsigned> > rand_uint(boost::mt19937 (), boost::uniform_int<unsigned> (0, 10));
00098 boost::variate_generator< boost::mt19937, boost::uniform_real<float> > rand_float(boost::mt19937 (), boost::uniform_real<float> (0, 1));
00099
00101 std::vector<int> unorganized_input_indices;
00102
00104 std::vector<int> organized_input_indices;
00105
00107 pcl::search::BruteForce<pcl::PointXYZ> brute_force;
00108
00110 pcl::search::KdTree<pcl::PointXYZ> KDTree;
00111
00113 pcl::search::Octree<pcl::PointXYZ> octree_search (0.1);
00114
00116 pcl::search::OrganizedNeighbor<pcl::PointXYZ> organized;
00117
00119 vector<search::Search<PointXYZ>* > unorganized_search_methods;
00120
00122 vector<search::Search<PointXYZ>* > organized_search_methods;
00123
00125 vector<int> unorganized_dense_cloud_query_indices;
00126 vector<int> unorganized_sparse_cloud_query_indices;
00127 vector<int> organized_sparse_query_indices;
00128
00134 bool testUniqueness (const vector<int>& indices, const string& name)
00135 {
00136 bool uniqueness = true;
00137 for (unsigned idx1 = 1; idx1 < indices.size () && uniqueness; ++idx1)
00138 {
00139
00140 for (unsigned idx2 = 0; idx2 < idx1; ++idx2)
00141 {
00142 if (indices [idx1] == indices [idx2])
00143 {
00144 #if DEBUG_OUT
00145 std::cout << name << " search: index is twice at positions: " << idx1 << " (" << indices [idx1] << ") , " << idx2 << " (" << indices [idx2] << ")" << std::endl;
00146 #endif
00147
00148 uniqueness = false;
00149 break;
00150 }
00151 }
00152 }
00153 return uniqueness;
00154 }
00155
00156
00162 bool testOrder (const vector<float>& distances, const string& name)
00163 {
00164 bool ordered = true;
00165 for (unsigned idx1 = 1; idx1 < distances.size (); ++idx1)
00166 {
00167 if (distances [idx1-1] > distances [idx1])
00168 {
00169 #if DEBUG_OUT
00170 std::cout << name << " search: not properly sorted: " << idx1 - 1 << "(" << distances [idx1-1] << ") > "
00171 << idx1 << "(" << distances [idx1] << ")"<< std::endl;
00172 #endif
00173 ordered = false;
00174 break;
00175 }
00176 }
00177
00178 return ordered;
00179 }
00180
00188 template<typename PointT> bool
00189 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)
00190 {
00191 bool validness = true;
00192 for (vector<int>::const_iterator iIt = indices.begin (); iIt != indices.end (); ++iIt)
00193 {
00194 if (!indices_mask [*iIt])
00195 {
00196 #if DEBUG_OUT
00197 cerr << name << ": result contains an invalid point: " << *iIt << " not in indices list.\n";
00198
00199
00200
00201
00202 #endif
00203 validness = false;
00204 break;
00205 }
00206 else if (!nan_mask [*iIt])
00207 {
00208 #if DEBUG_OUT
00209 cerr << name << ": result contains an invalid point: " << *iIt << " = NaN (" << point_cloud->points [*iIt].x << " , "
00210 << point_cloud->points [*iIt].y << " , "
00211 << point_cloud->points [*iIt].z << ")\n";
00212 #endif
00213 validness = false;
00214 break;
00215 }
00216 }
00217
00218 return validness;
00219 }
00220
00231 bool compareResults (const std::vector<int>& indices1, const::vector<float>& distances1, const std::string& name1,
00232 const std::vector<int>& indices2, const::vector<float>& distances2, const std::string& name2, float eps)
00233 {
00234 bool equal = true;
00235 if (indices1.size () != indices2.size ())
00236 {
00237 #if DEBUG_OUT
00238 cerr << "size of results between " << name1 << " search and " << name2 << " search do not match " <<indices1.size () << " vs. " << indices2.size () << endl;
00239
00240
00241
00242
00243
00244
00245
00246
00247
00248
00249
00250 #endif
00251 equal = false;
00252 }
00253 else
00254 {
00255 for (unsigned idx = 0; idx < indices1.size (); ++idx)
00256 {
00257 if (indices1[idx] != indices2[idx] && fabs (distances1[idx] - distances2[idx]) > eps)
00258 {
00259 #if DEBUG_OUT
00260 cerr << "results between " << name1 << " search and " << name2 << " search do not match: " << idx << " nearest neighbor: "
00261 << indices1[idx] << " with distance: " << distances1[idx] << " vs. "
00262 << indices2[idx] << " with distance: " << distances2[idx] << endl;
00263 #endif
00264 equal = false;
00265 break;
00266 }
00267 }
00268 }
00269 return equal;
00270 }
00271
00278 template<typename PointT> void
00279 testKNNSearch (typename PointCloud<PointT>::ConstPtr point_cloud, vector<search::Search<PointT>*> search_methods,
00280 const vector<int>& query_indices, const vector<int>& input_indices = vector<int> () )
00281 {
00282 vector< vector<int> >indices (search_methods.size ());
00283 vector< vector<float> >distances (search_methods.size ());
00284 vector<bool> passed (search_methods.size (), true);
00285
00286 vector<bool> indices_mask (point_cloud->size (), true);
00287 vector<bool> nan_mask (point_cloud->size (), true);
00288
00289 if (input_indices.size () != 0)
00290 {
00291 indices_mask.assign (point_cloud->size (), false);
00292 for (vector<int>::const_iterator iIt = input_indices.begin (); iIt != input_indices.end (); ++iIt)
00293 indices_mask [*iIt] = true;
00294 }
00295
00296
00297 #pragma omp parallel for
00298 for (int pIdx = 0; pIdx < int (point_cloud->size ()); ++pIdx)
00299 {
00300 if (!isFinite (point_cloud->points [pIdx]))
00301 nan_mask [pIdx] = false;
00302 }
00303
00304 boost::shared_ptr<vector<int> > input_indices_;
00305 if (input_indices.size ())
00306 input_indices_.reset (new vector<int> (input_indices));
00307
00308 #pragma omp parallel for
00309 for (int sIdx = 0; sIdx < int (search_methods.size ()); ++sIdx)
00310 search_methods [sIdx]->setInputCloud (point_cloud, input_indices_);
00311
00312
00313 for (unsigned knn = 1; knn <= 512; knn <<= 3)
00314 {
00315
00316 for (vector<int>::const_iterator qIt = query_indices.begin (); qIt != query_indices.end (); ++qIt)
00317 {
00318 #pragma omp parallel for
00319 for (int sIdx = 0; sIdx < int (search_methods.size ()); ++sIdx)
00320 {
00321 search_methods [sIdx]->nearestKSearch (point_cloud->points[*qIt], knn, indices [sIdx], distances [sIdx]);
00322 passed [sIdx] = passed [sIdx] && testUniqueness (indices [sIdx], search_methods [sIdx]->getName ());
00323 passed [sIdx] = passed [sIdx] && testOrder (distances [sIdx], search_methods [sIdx]->getName ());
00324 passed [sIdx] = passed [sIdx] && testResultValidity<PointT>(point_cloud, indices_mask, nan_mask, indices [sIdx], input_indices, search_methods [sIdx]->getName ());
00325 }
00326
00327
00328 #pragma omp parallel for
00329 for (int sIdx = 1; sIdx < int (search_methods.size ()); ++sIdx)
00330 {
00331 passed [sIdx] = passed [sIdx] && compareResults (indices [0], distances [0], search_methods [0]->getName (),
00332 indices [sIdx], distances [sIdx], search_methods [sIdx]->getName (), 1e-6f);
00333 }
00334 }
00335 }
00336 for (size_t sIdx = 0; sIdx < search_methods.size (); ++sIdx)
00337 {
00338 cout << search_methods [sIdx]->getName () << ": " << (passed[sIdx]?"passed":"failed") << endl;
00339 EXPECT_TRUE (passed [sIdx]);
00340 }
00341 }
00342
00349 template<typename PointT> void
00350 testRadiusSearch (typename PointCloud<PointT>::ConstPtr point_cloud, vector<search::Search<PointT>*> search_methods,
00351 const vector<int>& query_indices, const vector<int>& input_indices = vector<int> ())
00352 {
00353 vector< vector<int> >indices (search_methods.size ());
00354 vector< vector<float> >distances (search_methods.size ());
00355 vector <bool> passed (search_methods.size (), true);
00356 vector<bool> indices_mask (point_cloud->size (), true);
00357 vector<bool> nan_mask (point_cloud->size (), true);
00358
00359 if (input_indices.size () != 0)
00360 {
00361 indices_mask.assign (point_cloud->size (), false);
00362 for (vector<int>::const_iterator iIt = input_indices.begin (); iIt != input_indices.end (); ++iIt)
00363 indices_mask [*iIt] = true;
00364 }
00365
00366
00367 #pragma omp parallel for
00368 for (int pIdx = 0; pIdx < int (point_cloud->size ()); ++pIdx)
00369 {
00370 if (!isFinite (point_cloud->points [pIdx]))
00371 nan_mask [pIdx] = false;
00372 }
00373
00374 boost::shared_ptr<vector<int> > input_indices_;
00375 if (input_indices.size ())
00376 input_indices_.reset (new vector<int> (input_indices));
00377
00378 #pragma omp parallel for
00379 for (int sIdx = 0; sIdx < int (search_methods.size ()); ++sIdx)
00380 search_methods [sIdx]->setInputCloud (point_cloud, input_indices_);
00381
00382
00383 for (float radius = 0.01f; radius < 0.1f; radius *= 2.0f)
00384 {
00385
00386
00387 for (vector<int>::const_iterator qIt = query_indices.begin (); qIt != query_indices.end (); ++qIt)
00388 {
00389 #pragma omp parallel for
00390 for (int sIdx = 0; sIdx < static_cast<int> (search_methods.size ()); ++sIdx)
00391 {
00392 search_methods [sIdx]->radiusSearch (point_cloud->points[*qIt], radius, indices [sIdx], distances [sIdx], 0);
00393 passed [sIdx] = passed [sIdx] && testUniqueness (indices [sIdx], search_methods [sIdx]->getName ());
00394 passed [sIdx] = passed [sIdx] && testOrder (distances [sIdx], search_methods [sIdx]->getName ());
00395 passed [sIdx] = passed [sIdx] && testResultValidity<PointT>(point_cloud, indices_mask, nan_mask, indices [sIdx], input_indices, search_methods [sIdx]->getName ());
00396 }
00397
00398
00399 #pragma omp parallel for
00400 for (int sIdx = 1; sIdx < static_cast<int> (search_methods.size ()); ++sIdx)
00401 {
00402 passed [sIdx] = passed [sIdx] && compareResults (indices [0], distances [0], search_methods [0]->getName (),
00403 indices [sIdx], distances [sIdx], search_methods [sIdx]->getName (), 1e-6f);
00404 }
00405 }
00406 }
00407 for (unsigned sIdx = 0; sIdx < search_methods.size (); ++sIdx)
00408 {
00409 cout << search_methods [sIdx]->getName () << ": " << (passed[sIdx]?"passed":"failed") << endl;
00410 EXPECT_TRUE (passed [sIdx]);
00411 }
00412 }
00413
00414 #if TEST_unorganized_dense_cloud_COMPLETE_KNN
00415
00416 TEST (PCL, unorganized_dense_cloud_Complete_KNN)
00417 {
00418 testKNNSearch (unorganized_dense_cloud, unorganized_search_methods, unorganized_dense_cloud_query_indices);
00419 }
00420 #endif
00421
00422 #if TEST_unorganized_dense_cloud_VIEW_KNN
00423
00424 TEST (PCL, unorganized_dense_cloud_View_KNN)
00425 {
00426 testKNNSearch (unorganized_dense_cloud, unorganized_search_methods, unorganized_dense_cloud_query_indices, unorganized_input_indices);
00427 }
00428 #endif
00429
00430 #if TEST_unorganized_sparse_cloud_COMPLETE_KNN
00431
00432 TEST (PCL, unorganized_sparse_cloud_Complete_KNN)
00433 {
00434 testKNNSearch (unorganized_sparse_cloud, unorganized_search_methods, unorganized_sparse_cloud_query_indices);
00435 }
00436 #endif
00437
00438 #if TEST_unorganized_sparse_cloud_VIEW_KNN
00439 TEST (PCL, unorganized_sparse_cloud_View_KNN)
00440 {
00441 testKNNSearch (unorganized_sparse_cloud, unorganized_search_methods, unorganized_sparse_cloud_query_indices, unorganized_input_indices);
00442 }
00443 #endif
00444
00445 #if TEST_unorganized_dense_cloud_COMPLETE_RADIUS
00446
00447 TEST (PCL, unorganized_dense_cloud_Complete_Radius)
00448 {
00449 testRadiusSearch (unorganized_dense_cloud, unorganized_search_methods, unorganized_dense_cloud_query_indices);
00450 }
00451 #endif
00452
00453 #if TEST_unorganized_grid_cloud_COMPLETE_RADIUS
00454
00455 TEST (PCL, unorganized_grid_cloud_Complete_Radius)
00456 {
00457 vector<int> query_indices;
00458 query_indices.reserve (query_count);
00459
00460 unsigned skip = static_cast<unsigned> (unorganized_grid_cloud->size ()) / query_count;
00461 for (unsigned idx = 0; idx < unorganized_grid_cloud->size () && query_indices.size () < query_count; ++idx)
00462 if ((rand () % skip) == 0 && isFinite (unorganized_grid_cloud->points [idx]))
00463 query_indices.push_back (idx);
00464
00465 testRadiusSearch (unorganized_grid_cloud, unorganized_search_methods, query_indices);
00466 }
00467 #endif
00468
00469 #if TEST_unorganized_dense_cloud_VIEW_RADIUS
00470
00471 TEST (PCL, unorganized_dense_cloud_View_Radius)
00472 {
00473 testRadiusSearch (unorganized_dense_cloud, unorganized_search_methods, unorganized_dense_cloud_query_indices, unorganized_input_indices);
00474 }
00475 #endif
00476
00477 #if TEST_unorganized_sparse_cloud_COMPLETE_RADIUS
00478
00479 TEST (PCL, unorganized_sparse_cloud_Complete_Radius)
00480 {
00481 testRadiusSearch (unorganized_sparse_cloud, unorganized_search_methods, unorganized_sparse_cloud_query_indices);
00482 }
00483 #endif
00484
00485 #if TEST_unorganized_sparse_cloud_VIEW_RADIUS
00486 TEST (PCL, unorganized_sparse_cloud_View_Radius)
00487 {
00488 testRadiusSearch (unorganized_sparse_cloud, unorganized_search_methods, unorganized_sparse_cloud_query_indices, unorganized_input_indices);
00489 }
00490 #endif
00491
00492 #if TEST_ORGANIZED_SPARSE_COMPLETE_KNN
00493 TEST (PCL, Organized_Sparse_Complete_KNN)
00494 {
00495 testKNNSearch (organized_sparse_cloud, organized_search_methods, organized_sparse_query_indices);
00496 }
00497 #endif
00498
00499 #if TEST_ORGANIZED_SPARSE_VIEW_KNN
00500 TEST (PCL, Organized_Sparse_View_KNN)
00501 {
00502 testKNNSearch (organized_sparse_cloud, organized_search_methods, organized_sparse_query_indices, organized_input_indices);
00503 }
00504 #endif
00505
00506 #if TEST_ORGANIZED_SPARSE_COMPLETE_RADIUS
00507 TEST (PCL, Organized_Sparse_Complete_Radius)
00508 {
00509 testRadiusSearch (organized_sparse_cloud, organized_search_methods, organized_sparse_query_indices);
00510 }
00511 #endif
00512
00513 #if TEST_ORGANIZED_SPARSE_VIEW_RADIUS
00514 TEST (PCL, Organized_Sparse_View_Radius)
00515 {
00516 testRadiusSearch (organized_sparse_cloud, organized_search_methods, organized_sparse_query_indices, organized_input_indices);
00517 }
00518 #endif
00519
00525 void createQueryIndices (std::vector<int>& query_indices, PointCloud<PointXYZ>::ConstPtr point_cloud, unsigned query_count)
00526 {
00527 query_indices.clear ();
00528 query_indices.reserve (query_count);
00529
00530 unsigned skip = static_cast<unsigned> (point_cloud->size ()) / query_count;
00531 for (unsigned idx = 0; idx < point_cloud->size () && query_indices.size () < query_count; ++idx)
00532 if ((rand () % skip) == 0 && isFinite (point_cloud->points [idx]))
00533 query_indices.push_back (idx);
00534 }
00535
00540 void createIndices (std::vector<int>& indices, unsigned max_index)
00541 {
00542
00543 for (unsigned idx = 0; idx <= max_index; ++idx)
00544 if (rand_uint () == 0)
00545 indices.push_back (idx);
00546
00547 boost::variate_generator< boost::mt19937, boost::uniform_int<> > rand_indices(boost::mt19937 (), boost::uniform_int<> (0, static_cast<int> (indices.size ()) - 1));
00548
00549 for (unsigned idx = 0; idx < max_index; ++idx)
00550 {
00551 unsigned idx1 = rand_indices ();
00552 unsigned idx2 = rand_indices ();
00553
00554 std::swap (indices[idx1], indices[idx2]);
00555 }
00556 }
00557
00558
00559 int
00560 main (int argc, char** argv)
00561 {
00562 if (argc < 2)
00563 {
00564 std::cout << "need path to table_scene_mug_stereo_textured.pcd file\n";
00565 return (-1);
00566 }
00567
00568 pcl::io::loadPCDFile (argv [1], *organized_sparse_cloud);
00569
00570
00571 unorganized_dense_cloud->resize (unorganized_point_count);
00572 unorganized_dense_cloud->height = 1;
00573 unorganized_dense_cloud->width = unorganized_point_count;
00574 unorganized_dense_cloud->is_dense = true;
00575
00576 unorganized_sparse_cloud->resize (unorganized_point_count);
00577 unorganized_sparse_cloud->height = 1;
00578 unorganized_sparse_cloud->width = unorganized_point_count;
00579 unorganized_sparse_cloud->is_dense = false;
00580
00581 PointXYZ point;
00582 for (unsigned pIdx = 0; pIdx < unorganized_point_count; ++pIdx)
00583 {
00584 point.x = rand_float ();
00585 point.y = rand_float ();
00586 point.z = rand_float ();
00587
00588 unorganized_dense_cloud->points [pIdx] = point;
00589
00590 if (rand_uint () == 0)
00591 unorganized_sparse_cloud->points [pIdx].x = unorganized_sparse_cloud->points [pIdx].y = unorganized_sparse_cloud->points [pIdx].z = std::numeric_limits<float>::quiet_NaN ();
00592 else
00593 unorganized_sparse_cloud->points [pIdx] = point;
00594 }
00595
00596 unorganized_grid_cloud->reserve (1000);
00597 unorganized_grid_cloud->height = 1;
00598 unorganized_grid_cloud->width = 1000;
00599 unorganized_grid_cloud->is_dense = true;
00600
00601
00602 for (unsigned xIdx = 0; xIdx < 10; ++xIdx)
00603 {
00604 for (unsigned yIdx = 0; yIdx < 10; ++yIdx)
00605 {
00606 for (unsigned zIdx = 0; zIdx < 10; ++zIdx)
00607 {
00608 point.x = 0.1f * static_cast<float>(xIdx);
00609 point.y = 0.1f * static_cast<float>(yIdx);
00610 point.z = 0.1f * static_cast<float>(zIdx);
00611 unorganized_grid_cloud->push_back (point);
00612 }
00613 }
00614 }
00615
00616 createIndices (organized_input_indices, static_cast<unsigned> (organized_sparse_cloud->size () - 1));
00617 createIndices (unorganized_input_indices, unorganized_point_count - 1);
00618
00619 brute_force.setSortedResults (true);
00620 KDTree.setSortedResults (true);
00621 octree_search.setSortedResults (true);
00622 organized.setSortedResults (true);
00623
00624 unorganized_search_methods.push_back (&brute_force);
00625 unorganized_search_methods.push_back (&KDTree);
00626 unorganized_search_methods.push_back (&octree_search);
00627
00628 organized_search_methods.push_back (&brute_force);
00629 organized_search_methods.push_back (&KDTree);
00630 organized_search_methods.push_back (&octree_search);
00631 organized_search_methods.push_back (&organized);
00632
00633 createQueryIndices (unorganized_dense_cloud_query_indices, unorganized_dense_cloud, query_count);
00634 createQueryIndices (unorganized_sparse_cloud_query_indices, unorganized_sparse_cloud, query_count);
00635 createQueryIndices (organized_sparse_query_indices, organized_sparse_cloud, query_count);
00636
00637 testing::InitGoogleTest (&argc, argv);
00638 return (RUN_ALL_TESTS ());
00639 }
00640