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
00039
00040
00041
00042
00043
00044
00045 #include <gtest/gtest.h>
00046
00047 #include <vector>
00048 #include <cstdio>
00049 #include <iostream>
00050 using namespace std;
00051
00052 #include <pcl/common/time.h>
00053 #include <pcl/console/print.h>
00054
00055 #include <pcl/point_cloud.h>
00056 #include <pcl/point_types.h>
00057
00058 using namespace pcl;
00059
00060 #include <pcl/outofcore/outofcore.h>
00061 #include <pcl/outofcore/outofcore_impl.h>
00062
00063 #include <pcl/PCLPointCloud2.h>
00064
00065 using namespace pcl::outofcore;
00066
00067 #include <boost/random/mersenne_twister.hpp>
00068 #include <boost/random/uniform_real.hpp>
00069 #include <boost/random/normal_distribution.hpp>
00070 #include <boost/foreach.hpp>
00071
00075
00076
00077 const static uint64_t numPts (10000);
00078
00079 const static boost::uint32_t rngseed = 0xAAFF33DD;
00080
00081 const static boost::filesystem::path filename_otreeA = "treeA/tree_test.oct_idx";
00082 const static boost::filesystem::path filename_otreeB = "treeB/tree_test.oct_idx";
00083
00084 const static boost::filesystem::path filename_otreeA_LOD = "treeA_LOD/tree_test.oct_idx";
00085 const static boost::filesystem::path filename_otreeB_LOD = "treeB_LOD/tree_test.oct_idx";
00086
00087 const static boost::filesystem::path outofcore_path ("point_cloud_octree/tree_test.oct_idx");
00088
00089
00090 typedef pcl::PointXYZ PointT;
00091
00092
00093 typedef OutofcoreOctreeBase<OutofcoreOctreeDiskContainer < PointT > , PointT > octree_disk;
00094 typedef OutofcoreOctreeBaseNode<OutofcoreOctreeDiskContainer < PointT > , PointT > octree_disk_node;
00095
00096 typedef OutofcoreOctreeBase<OutofcoreOctreeRamContainer< PointT> , PointT> octree_ram;
00097 typedef OutofcoreOctreeBaseNode<OutofcoreOctreeRamContainer<PointT> , PointT> octree_ram_node;
00098
00099 typedef std::vector<PointT, Eigen::aligned_allocator<PointT> > AlignedPointTVector;
00100
00101 AlignedPointTVector points;
00102
00103
00105 bool
00106 compPt (const PointT &p1, const PointT &p2)
00107 {
00108 if (p1.x != p2.x || p1.y != p2.y || p1.z != p2.z)
00109 return false;
00110
00111 return true;
00112 }
00113
00114 TEST (PCL, Outofcore_Octree_Build)
00115 {
00116
00117 boost::filesystem::remove_all (filename_otreeA.parent_path ());
00118 boost::filesystem::remove_all (filename_otreeB.parent_path ());
00119
00120 Eigen::Vector3d min (-32.0, -32.0, -32.0);
00121 Eigen::Vector3d max (32.0, 32.0, 32.0);
00122
00123
00124
00125
00126 octree_disk treeA (min, max, .1, filename_otreeA, "ECEF");
00127 octree_disk treeB (4, min, max, filename_otreeB, "ECEF");
00128
00129
00130 boost::mt19937 rng(rngseed);
00131
00132
00133
00134
00135
00136 boost::normal_distribution<float> dist (0.5f, .1f);
00137
00138
00139 PointT p;
00140 points.resize (numPts);
00141
00142
00143
00144
00145
00146
00147
00148
00149
00150 for (size_t i = 0; i < numPts; i++)
00151 {
00152 p.x = dist (rng);
00153 p.y = dist (rng);
00154 p.z = dist (rng);
00155
00156 points[i] = p;
00157 }
00158
00159
00160 treeA.addDataToLeaf (points);
00161
00162
00163 treeB.addDataToLeaf (points);
00164
00165 }
00166
00167 TEST (PCL, Outofcore_Octree_Build_LOD)
00168 {
00169
00170 boost::filesystem::remove_all (filename_otreeA_LOD.parent_path ());
00171 boost::filesystem::remove_all (filename_otreeB_LOD.parent_path ());
00172
00173 Eigen::Vector3d min (0.0, 0.0, 0.0);
00174 Eigen::Vector3d max (1.0, 1.0, 1.0);
00175
00176
00177 octree_disk treeA (min, max, .1, filename_otreeA_LOD, "ECEF");
00178 octree_disk treeB (4, min, max, filename_otreeB_LOD, "ECEF");
00179
00180
00181 boost::mt19937 rng (rngseed);
00182
00183
00184
00185 boost::normal_distribution<float> dist (0.5f, .1f);
00186
00187
00188 PointT p;
00189
00190
00191
00192
00193
00194
00195
00196
00197 points.resize (numPts);
00198
00199
00200 for (size_t i = 0; i < numPts; i++)
00201 {
00202 p.x = dist (rng);
00203 p.y = dist (rng);
00204 p.z = dist (rng);
00205
00206 points[i] = p;
00207 }
00208
00209
00210 treeA.addDataToLeaf_and_genLOD (points);
00211
00212
00213 treeB.addDataToLeaf_and_genLOD (points);
00214 }
00215
00216 TEST(PCL, Outofcore_Bounding_Box)
00217 {
00218
00219 Eigen::Vector3d min (-32.0,-32.0,-32.0);
00220 Eigen::Vector3d max (32.0, 32.0, 32.0);
00221
00222 octree_disk treeA (filename_otreeA, false);
00223 octree_disk treeB (filename_otreeB, false);
00224
00225 Eigen::Vector3d min_otreeA;
00226 Eigen::Vector3d max_otreeA;
00227 treeA.getBoundingBox (min_otreeA, max_otreeA);
00228
00229 Eigen::Vector3d min_otreeB;
00230 Eigen::Vector3d max_otreeB;
00231 treeB.getBoundingBox (min_otreeB, max_otreeB);
00232
00233 for (int i=0; i<3; i++)
00234 {
00235
00236 EXPECT_LE (min_otreeA[i], min[i]);
00237 EXPECT_NEAR (min_otreeA[i], min[i], 1e4);
00238
00239 EXPECT_GE (max_otreeA[i], max[i]);
00240 EXPECT_NEAR (max_otreeA[i], max[i], 1e4);
00241
00242 EXPECT_LE (min_otreeB[i] , min[i]);
00243 EXPECT_NEAR (min_otreeB[i], min[i], 1e4);
00244
00245 EXPECT_GE (max_otreeB[i] , max[i]);
00246 EXPECT_NEAR (max_otreeB[i], max[i], 1e4);
00247 }
00248 }
00249
00250 void
00251 point_test (octree_disk& t)
00252 {
00253 boost::mt19937 rng (rngseed);
00254 boost::uniform_real<float> dist(0,1);
00255
00256 Eigen::Vector3d query_box_min;
00257 Eigen::Vector3d qboxmax;
00258
00259 for (int i = 0; i < 10; i++)
00260 {
00261
00262 for (int j = 0; j < 3; j++)
00263 {
00264 query_box_min[j] = dist (rng);
00265 qboxmax[j] = dist (rng);
00266
00267 if (qboxmax[j] < query_box_min[j])
00268 {
00269 std::swap (query_box_min[j], qboxmax[j]);
00270 assert (query_box_min[j] < qboxmax[j]);
00271 }
00272 }
00273
00274
00275 AlignedPointTVector p_ot;
00276
00277 t.queryBBIncludes (query_box_min, qboxmax, t.getDepth (), p_ot);
00278
00279
00280 AlignedPointTVector pointsinregion;
00281
00282 for (AlignedPointTVector::iterator pointit = points.begin (); pointit != points.end (); ++pointit)
00283 {
00284 if ((query_box_min[0] <= pointit->x) && (pointit->x < qboxmax[0]) && (query_box_min[1] < pointit->y) && (pointit->y < qboxmax[1]) && (query_box_min[2] <= pointit->z) && (pointit->z < qboxmax[2]))
00285 {
00286 pointsinregion.push_back (*pointit);
00287 }
00288 }
00289
00290 EXPECT_EQ (p_ot.size (), pointsinregion.size ());
00291
00292
00293 while(!p_ot.empty ())
00294 {
00295 AlignedPointTVector::iterator it;
00296 it = std::find_first_of (p_ot.begin (), p_ot.end(), pointsinregion.begin (), pointsinregion.end (), compPt);
00297
00298 if (it != p_ot.end ())
00299 {
00300 p_ot.erase (it);
00301 }
00302 else
00303 {
00304 FAIL () << "Dropped Point from tree1!" << std::endl;
00305 break;
00306 }
00307 }
00308
00309 EXPECT_TRUE (p_ot.empty ());
00310 }
00311 }
00312
00313 TEST (PCL, Outofcore_Point_Query)
00314 {
00315 octree_disk treeA(filename_otreeA, false);
00316 octree_disk treeB(filename_otreeB, false);
00317
00318 point_test(treeA);
00319 point_test(treeB);
00320 }
00321
00322 #if 0 //this class will be deprecated soon.
00323 TEST (PCL, Outofcore_Ram_Tree)
00324 {
00325 Eigen::Vector3d min (0.0,0.0,0.0);
00326 Eigen::Vector3d max (1.0, 1.0, 1.0);
00327
00328 const boost::filesystem::path filename_otreeA = "ram_tree/ram_tree.oct_idx";
00329
00330 octree_ram t (min, max, .1, filename_otreeA, "ECEF");
00331
00332 boost::mt19937 rng (rngseed);
00333
00334 boost::normal_distribution<float> dist (0.5f, .1f);
00335 PointT p;
00336
00337 points.resize (numPts);
00338 for (size_t i = 0; i < numPts; i++)
00339 {
00340 p.x = dist(rng);
00341 p.y = dist(rng);
00342 p.z = dist(rng);
00343
00344 points[i] = p;
00345 }
00346
00347 t.addDataToLeaf_and_genLOD (points);
00348
00349
00350 Eigen::Vector3d qboxmin;
00351 Eigen::Vector3d qboxmax;
00352 for (int i = 0; i < 10; i++)
00353 {
00354
00355 for (int j = 0; j < 3; j++)
00356 {
00357 qboxmin[j] = dist (rng);
00358 qboxmax[j] = dist (rng);
00359
00360 if (qboxmax[j] < qboxmin[j])
00361 {
00362 std::swap (qboxmin[j], qboxmax[j]);
00363 }
00364 }
00365
00366
00367 AlignedPointTVector p_ot1;
00368 t.queryBBIncludes (qboxmin, qboxmax, t.getDepth (), p_ot1);
00369
00370
00371 AlignedPointTVector pointsinregion;
00372 BOOST_FOREACH(const PointT& p, points)
00373 {
00374 if ((qboxmin[0] <= p.x) && (p.x <= qboxmax[0]) && (qboxmin[1] <= p.y) && (p.y <= qboxmax[1]) && (qboxmin[2] <= p.z) && (p.z <= qboxmax[2]))
00375 {
00376 pointsinregion.push_back (p);
00377 }
00378 }
00379
00380 EXPECT_EQ (p_ot1.size (), pointsinregion.size ());
00381
00382
00383 while (!p_ot1.empty ())
00384 {
00385 AlignedPointTVector::iterator it;
00386 it = std::find_first_of (p_ot1.begin (), p_ot1.end (), pointsinregion.begin (), pointsinregion.end (), compPt);
00387
00388 if (it != p_ot1.end ())
00389 {
00390 p_ot1.erase(it);
00391 }
00392 else
00393 {
00394 break;
00395 FAIL () << "Dropped Point from tree1!" << std::endl;
00396 }
00397 }
00398
00399 EXPECT_TRUE (p_ot1.empty ());
00400 }
00401 }
00402 #endif
00403 class OutofcoreTest : public testing::Test
00404 {
00405 protected:
00406
00407 OutofcoreTest () : smallest_voxel_dim () {}
00408
00409 virtual void SetUp ()
00410 {
00411 smallest_voxel_dim = 3.0f;
00412 }
00413
00414 virtual void TearDown ()
00415 {
00416
00417 }
00418
00419 void cleanUpFilesystem ()
00420 {
00421
00422
00423 boost::filesystem::remove_all (filename_otreeA.parent_path ());
00424 boost::filesystem::remove_all (filename_otreeB.parent_path ());
00425
00426 boost::filesystem::remove_all (filename_otreeA_LOD.parent_path ());
00427 boost::filesystem::remove_all (filename_otreeB_LOD.parent_path ());
00428
00429 boost::filesystem::remove_all (outofcore_path.parent_path ());
00430
00431 }
00432
00433 double smallest_voxel_dim;
00434
00435 };
00436
00437
00439 TEST_F (OutofcoreTest, Outofcore_Constructors)
00440 {
00441
00442
00443
00444
00445
00446
00447 cleanUpFilesystem ();
00448
00449
00450 const Eigen::Vector3d min (-1024.0, -1024.0, -1024.0);
00451
00452 const Eigen::Vector3d max (1024.0, 1024.0, 1024.0);
00453
00454 AlignedPointTVector some_points;
00455
00456 for (unsigned int i=0; i< numPts; i++)
00457 some_points.push_back (PointT (static_cast<float>(rand () % 1024), static_cast<float>(rand () % 1024), static_cast<float>(rand () % 1024)));
00458
00459
00460
00461
00462 octree_disk octreeA (min, max, smallest_voxel_dim, filename_otreeA, "ECEF");
00463
00464 EXPECT_EQ (some_points.size (), octreeA.addDataToLeaf (some_points)) << "Dropped points in voxel resolution constructor\n";
00465
00466 EXPECT_EQ (some_points.size (), octreeA.getNumPointsAtDepth (octreeA.getDepth ()));
00467
00468
00469
00470 int depth = 2;
00471 octree_disk octreeB (depth, min, max, filename_otreeB, "ECEF");
00472 EXPECT_EQ (some_points.size (), octreeB.addDataToLeaf (some_points)) << "Dropped points in fixed-depth constructor\n";
00473
00474 EXPECT_EQ (some_points.size (), octreeB.getNumPointsAtDepth (octreeB.getDepth ()));
00475 }
00476
00477 TEST_F (OutofcoreTest, Outofcore_ConstructorSafety)
00478 {
00479
00480 const Eigen::Vector3d min (-1024, -1024, -1024);
00481
00482 const Eigen::Vector3d max (1024, 1024, 1024);
00483
00484 int depth = 2;
00485
00486
00487
00488 ASSERT_TRUE (boost::filesystem::exists (filename_otreeA)) << "No tree detected on disk. This test will fail. Perhaps this test was run out of order.\n";
00489 ASSERT_TRUE (boost::filesystem::exists (filename_otreeB)) << "No tree detected on disk. This test will fail. Perhaps this test was run out of order.\n";
00490
00491 EXPECT_ANY_THROW ({ octree_disk octreeC (min, max, smallest_voxel_dim, filename_otreeA, "ECEF"); }) << "Failure to detect existing tree on disk with the same name. Data may be overwritten.\n";
00492 EXPECT_ANY_THROW ({ octree_disk octreeD (depth, min, max, filename_otreeB, "ECEF"); }) << "Failure to detect existing tree on disk with the same name. Data may be overwritten.\n";
00493
00494
00495 octree_disk octree_from_disk (filename_otreeB, true);
00496 vector<uint64_t> numPoints = octree_from_disk.getNumPointsVector ();
00497 EXPECT_EQ (numPts , octree_from_disk.getNumPointsAtDepth (octree_from_disk.getDepth ())) << "Failure to count the number of points in a tree already existing on disk\n";
00498 }
00499
00500 TEST_F (OutofcoreTest, Outofcore_ConstructorBadPaths)
00501 {
00502
00503
00505 boost::filesystem::path non_existent_path_name ("treeBogus/tree_bogus.oct_idx");
00506 boost::filesystem::path bad_extension_path ("treeBadExtension/tree_bogus.bad_extension");
00507
00508 EXPECT_FALSE (boost::filesystem::exists (non_existent_path_name));
00509 EXPECT_ANY_THROW ({octree_disk octree_bogus_path (non_existent_path_name, true);});
00510
00511 EXPECT_FALSE (boost::filesystem::exists (bad_extension_path));
00512 EXPECT_ANY_THROW ({octree_disk octree_bad_extension (bad_extension_path, true);});
00513
00514 }
00515
00516 TEST_F (OutofcoreTest, Outofcore_PointcloudConstructor)
00517 {
00518 cleanUpFilesystem ();
00519
00520
00521 const Eigen::Vector3d min (-1,-1,-1);
00522
00523 const Eigen::Vector3d max (1024, 1024, 1024);
00524
00525
00526 PointCloud<PointT>::Ptr test_cloud (new PointCloud<PointT> ());
00527
00528 test_cloud->width = numPts;
00529 test_cloud->height = 1;
00530 test_cloud->reserve (numPts);
00531
00532
00533 for (size_t i=0; i < numPts; i++)
00534 {
00535 PointT tmp (static_cast<float> (i % 1024),
00536 static_cast<float> (i % 1024),
00537 static_cast<float> (i % 1024));
00538
00539 test_cloud->points.push_back (tmp);
00540 }
00541
00542 EXPECT_EQ (numPts, test_cloud->points.size ());
00543
00544 octree_disk pcl_cloud (4, min, max, outofcore_path, "ECEF");
00545
00546 pcl_cloud.addPointCloud (test_cloud);
00547
00548 EXPECT_EQ (test_cloud->points.size (), pcl_cloud.getNumPointsAtDepth (pcl_cloud.getDepth ()));
00549
00550 cleanUpFilesystem ();
00551 }
00552
00553 TEST_F (OutofcoreTest, Outofcore_PointsOnBoundaries)
00554 {
00555 cleanUpFilesystem ();
00556
00557 const Eigen::Vector3d min (-1,-1,-1);
00558 const Eigen::Vector3d max (1,1,1);
00559
00560 PointCloud<PointT>::Ptr cloud (new PointCloud<PointT> ());
00561 cloud->width = 8;
00562 cloud->height =1;
00563 cloud->reserve (8);
00564
00565 for (int i=0; i<8; i++)
00566 {
00567 PointT tmp;
00568 tmp.x = static_cast<float> (pow (-1.0, i)) * 1.0f;
00569 tmp.y = static_cast<float> (pow (-1.0, i+1)) * 1.0f;
00570 tmp.z = static_cast<float> (pow (-1.0, 3*i)) * 1.0f;
00571
00572 cloud->points.push_back (tmp);
00573 }
00574
00575 octree_disk octree (4, min, max, outofcore_path, "ECEF");
00576
00577 octree.addPointCloud (cloud);
00578
00579 EXPECT_EQ (8, octree.getNumPointsAtDepth (octree.getDepth ()));
00580
00581 }
00582
00583
00584
00585
00586
00587
00588
00589
00590
00591
00592
00593
00594
00595
00596 TEST_F (OutofcoreTest, Outofcore_MultiplePointClouds)
00597 {
00598 cleanUpFilesystem ();
00599
00600
00601 const Eigen::Vector3d min (-1024,-1024,-1024);
00602
00603
00604 const Eigen::Vector3d max (1024,1024,1024);
00605
00606
00607 PointCloud<PointT>::Ptr test_cloud (new PointCloud<PointT> ());
00608 PointCloud<PointT>::Ptr second_cloud (new PointCloud<PointT> ());
00609
00610 test_cloud->width = numPts;
00611 test_cloud->height = 1;
00612 test_cloud->reserve (numPts);
00613
00614 second_cloud->width = numPts;
00615 second_cloud->height = 1;
00616 second_cloud->reserve (numPts);
00617
00618
00619 for (size_t i=0; i < numPts; i++)
00620 {
00621 PointT tmp (static_cast<float> (i % 1024),
00622 static_cast<float> (i % 1024),
00623 static_cast<float> (i % 1024));
00624
00625 test_cloud->points.push_back (tmp);
00626 }
00627
00628 for (size_t i=0; i < numPts; i++)
00629 {
00630 PointT tmp (static_cast<float> (i % 1024),
00631 static_cast<float> (i % 1024),
00632 static_cast<float> (i % 1024));
00633
00634 second_cloud->points.push_back (tmp);
00635 }
00636
00637 octree_disk pcl_cloud (4, min, max, outofcore_path, "ECEF");
00638
00639 ASSERT_EQ (test_cloud->points.size (), pcl_cloud.addPointCloud (test_cloud)) << "Points lost when adding the first cloud to the tree\n";
00640
00641 ASSERT_EQ (numPts, pcl_cloud.getNumPointsAtDepth (pcl_cloud.getDepth ())) << "Book keeping of number of points at query depth does not match number of points inserted to the leaves\n";
00642
00643 pcl_cloud.addPointCloud (second_cloud);
00644
00645 EXPECT_EQ (2*numPts, pcl_cloud.getNumPointsAtDepth (pcl_cloud.getDepth ())) << "Points are lost when two points clouds are added to the outofcore file system\n";
00646
00647 pcl_cloud.setSamplePercent (0.125);
00648 pcl_cloud.buildLOD ();
00649
00650
00651 for (size_t i=0; i<pcl_cloud.getDepth (); i++)
00652 EXPECT_GE (pcl_cloud.getNumPointsAtDepth (i), 1) << "No points in the LOD indicates buildLOD failed\n";
00653
00654 EXPECT_EQ (2*numPts, pcl_cloud.getNumPointsAtDepth (pcl_cloud.getDepth ())) << "Points in leaves were lost while building LOD!\n";
00655
00656 cleanUpFilesystem ();
00657 }
00658
00659 TEST_F (OutofcoreTest, Outofcore_PointCloudInput_LOD)
00660 {
00661 cleanUpFilesystem ();
00662
00663
00664 const Eigen::Vector3d min (-1024,-1024,-1024);
00665
00666
00667 const Eigen::Vector3d max (1024,1024,1024);
00668
00669
00670 PointCloud<PointT>::Ptr test_cloud (new PointCloud<PointT> ());
00671 PointCloud<PointT>::Ptr second_cloud (new PointCloud<PointT> ());
00672
00673 test_cloud->width = numPts;
00674 test_cloud->height = 1;
00675 test_cloud->reserve (numPts);
00676
00677 second_cloud->width = numPts;
00678 second_cloud->height = 1;
00679 second_cloud->reserve (numPts);
00680
00681
00682 for (size_t i=0; i < numPts; i++)
00683 {
00684 PointT tmp (static_cast<float> (i % 1024),
00685 static_cast<float> (i % 1024),
00686 static_cast<float> (i % 1024));
00687
00688 test_cloud->points.push_back (tmp);
00689 }
00690
00691 for (size_t i=0; i < numPts; i++)
00692 {
00693 PointT tmp (static_cast<float> (i % 1024),
00694 static_cast<float> (i % 1024),
00695 static_cast<float> (i % 1024));
00696
00697 second_cloud->points.push_back (tmp);
00698 }
00699
00700 octree_disk pcl_cloud (4, min, max, outofcore_path, "ECEF");
00701
00702 pcl_cloud.addPointCloud_and_genLOD (second_cloud);
00703
00704
00705 cleanUpFilesystem ();
00706 }
00707
00708 TEST_F (OutofcoreTest, PointCloud2_Constructors)
00709 {
00710 cleanUpFilesystem ();
00711
00712
00713 const Eigen::Vector3d min (-100.1, -100.1, -100.1);
00714 const Eigen::Vector3d max (100.1, 100.1, 100.1);
00715
00716 const boost::uint64_t depth = 2;
00717
00718
00719 PointCloud<PointT>::Ptr test_cloud (new PointCloud<PointT> ());
00720
00721 test_cloud->width = numPts;
00722 test_cloud->height = 1;
00723 test_cloud->reserve (numPts);
00724
00725
00726 for (size_t i=0; i < numPts; i++)
00727 {
00728 PointT tmp (static_cast<float> (i % 200) - 99 ,
00729 static_cast<float> (i % 200) - 99,
00730 static_cast<float> (i % 200) - 99);
00731
00732 test_cloud->points.push_back (tmp);
00733 }
00734
00735 boost::shared_ptr<pcl::PCLPointCloud2> point_cloud (new pcl::PCLPointCloud2 ());
00736
00737 pcl::toPCLPointCloud2 (*test_cloud, *point_cloud);
00738
00739 octree_disk octreeA (depth, min, max, filename_otreeA, "ECEF");
00740 octree_disk octreeB (depth, min, max, filename_otreeB, "ECEF");
00741
00742 EXPECT_EQ (octreeA.addPointCloud (point_cloud, false) , point_cloud->width*point_cloud->height) << "Number of points returned by constructor indicates some points were not properly inserted to the outofcore cloud\n";
00743
00744 EXPECT_EQ (octreeB.addPointCloud_and_genLOD (point_cloud), point_cloud->width*point_cloud->height) << "Number of points inserted when generating LOD does not match the size of the point cloud\n";
00745 }
00746
00747 TEST_F (OutofcoreTest, PointCloud2_Insertion)
00748 {
00749 cleanUpFilesystem ();
00750
00751 const Eigen::Vector3d min (-11, -11, -11);
00752 const Eigen::Vector3d max (11,11,11);
00753
00754 pcl::PointCloud<pcl::PointXYZ> point_cloud;
00755
00756 point_cloud.points.reserve (numPts);
00757 point_cloud.width = static_cast<uint32_t> (numPts);
00758 point_cloud.height = 1;
00759
00760 for (size_t i=0; i < numPts; i++)
00761 point_cloud.points.push_back (PointT (static_cast<float>(rand () % 10), static_cast<float>(rand () % 10), static_cast<float>(rand () % 10)));
00762
00763
00764 pcl::PCLPointCloud2::Ptr input_cloud (new pcl::PCLPointCloud2 ());
00765
00766 toPCLPointCloud2<PointXYZ> (point_cloud, *input_cloud);
00767 ASSERT_EQ (point_cloud.width*point_cloud.height, input_cloud->width*input_cloud->height);
00768
00769 octree_disk octreeA (min, max, smallest_voxel_dim, filename_otreeA, "ECEF");
00770 octree_disk octreeB (1, min, max, filename_otreeB, "ECEF");
00771
00772
00773 uint64_t points_in_input_cloud = input_cloud->width*input_cloud->height;
00774 EXPECT_EQ (octreeA.addPointCloud (input_cloud, false), points_in_input_cloud) << "Insertion failure. Number of points successfully added does not match size of input cloud\n";
00775 EXPECT_EQ (octreeB.addPointCloud (input_cloud, false), points_in_input_cloud) << "Insertion failure. Number of points successfully added does not match size of input cloud\n";
00776 }
00777
00778 TEST_F (OutofcoreTest, PointCloud2_MultiplePointCloud)
00779 {
00780
00781 cleanUpFilesystem ();
00782
00783
00784 const Eigen::Vector3d min (-100.1, -100.1, -100.1);
00785 const Eigen::Vector3d max (100.1, 100.1, 100.1);
00786
00787
00788 PointCloud<PointT>::Ptr first_cloud (new PointCloud<PointT> ());
00789 PointCloud<PointT>::Ptr second_cloud (new PointCloud<PointT> ());
00790
00791 first_cloud->width = numPts;
00792 first_cloud->height = 1;
00793 first_cloud->reserve (numPts);
00794
00795 second_cloud->width = numPts;
00796 second_cloud->height = 1;
00797 second_cloud->reserve (numPts);
00798
00799
00800 for (size_t i=0; i < numPts; i++)
00801 {
00802 PointT tmp (static_cast<float> (i % 50),
00803 static_cast<float> (i % 50),
00804 static_cast<float> (i % 50));
00805
00806 first_cloud->points.push_back (tmp);
00807 }
00808
00809 for (size_t i=0; i < numPts; i++)
00810 {
00811 PointT tmp (static_cast<float> (i % 50),
00812 static_cast<float> (i % 50),
00813 static_cast<float> (i % 50));
00814
00815 second_cloud->points.push_back (tmp);
00816 }
00817
00818 pcl::PCLPointCloud2::Ptr first_cloud_ptr (new pcl::PCLPointCloud2 ());
00819 pcl::PCLPointCloud2::Ptr second_cloud_ptr (new pcl::PCLPointCloud2 ());
00820
00821 toPCLPointCloud2<PointT> (*first_cloud, *first_cloud_ptr);
00822 toPCLPointCloud2<PointT> (*second_cloud, *second_cloud_ptr);
00823
00824
00825 octree_disk shallow_outofcore (0, min, max, filename_otreeB, "ECEF");
00826
00827 shallow_outofcore.addPointCloud (first_cloud);
00828 shallow_outofcore.addPointCloud (second_cloud);
00829
00830 pcl::PCLPointCloud2::Ptr result (new pcl::PCLPointCloud2 ());
00831 shallow_outofcore.queryBBIncludes (min, max, 0, result);
00832
00833 size_t num_points_queried = result->width*result->height;
00834 size_t num_points_inserted = first_cloud->width*first_cloud->height + second_cloud->width*second_cloud->height;
00835
00836 EXPECT_EQ (num_points_inserted, num_points_queried) << "If num_points_inserted > num_points_on_disk, then points were dropped on insertion of multiple clouds in the outofcore octree";
00837 }
00838
00839 TEST_F (OutofcoreTest, PointCloud2_QueryBoundingBox)
00840 {
00841 cleanUpFilesystem ();
00842
00843
00844 const Eigen::Vector3d min (-100.1, -100.1, -100.1);
00845 const Eigen::Vector3d max (100.1, 100.1, 100.1);
00846
00847 const boost::uint64_t depth = 2;
00848
00849
00850 PointCloud<PointT>::Ptr test_cloud (new PointCloud<PointT> ());
00851
00852 test_cloud->width = numPts;
00853 test_cloud->height = 1;
00854 test_cloud->reserve (numPts);
00855
00856
00857 for (size_t i=0; i < numPts; i++)
00858 {
00859 PointT tmp (static_cast<float> (i % 50) - 50 ,
00860 static_cast<float> (i % 50) - 50,
00861 static_cast<float> (i % 50) - 50);
00862
00863 test_cloud->points.push_back (tmp);
00864 }
00865
00866 pcl::PCLPointCloud2::Ptr dst_blob (new pcl::PCLPointCloud2 ());
00867
00868 pcl::toPCLPointCloud2 (*test_cloud, *dst_blob);
00869
00870 octree_disk octreeA (depth, min, max, filename_otreeA, "ECEF");
00871 octree_disk octreeB (depth, min, max, filename_otreeB, "ECEF");
00872
00873 uint64_t points_added = octreeA.addPointCloud (dst_blob, false);
00874 EXPECT_EQ (points_added, dst_blob->width*dst_blob->height);
00875
00876 pcl::PCLPointCloud2::Ptr dst_blob2 (new pcl::PCLPointCloud2 ());
00877
00878 octreeA.queryBoundingBox (min, max, 2, dst_blob2);
00879 std::list<std::string> filenames;
00880 octreeA.queryBoundingBox (min, max, 2, filenames);
00881 EXPECT_GE (filenames.size (), 1);
00882
00883 octreeA.queryBoundingBox (min, max, 2, dst_blob2, 0.125);
00884 EXPECT_GE (dst_blob2->width*dst_blob2->height, 1);
00885 cleanUpFilesystem ();
00886 }
00887
00888
00889
00890 TEST_F (OutofcoreTest, PointCloud2_Query)
00891 {
00892
00893 cleanUpFilesystem ();
00894
00895
00896 const Eigen::Vector3d min (-100.1, -100.1, -100.1);
00897 const Eigen::Vector3d max (100.1, 100.1, 100.1);
00898
00899 const boost::uint64_t depth = 2;
00900
00901
00902 PointCloud<PointT>::Ptr test_cloud (new PointCloud<PointT> ());
00903
00904 test_cloud->width = numPts;
00905 test_cloud->height = 1;
00906 test_cloud->reserve (numPts);
00907
00908
00909 for (size_t i=0; i < numPts; i++)
00910 {
00911 PointT tmp (static_cast<float> (i % 50) - 50 ,
00912 static_cast<float> (i % 50) - 50,
00913 static_cast<float> (i % 50) - 50);
00914
00915 test_cloud->points.push_back (tmp);
00916 }
00917
00918 pcl::PCLPointCloud2::Ptr dst_blob (new pcl::PCLPointCloud2 ());
00919
00920 pcl::toPCLPointCloud2 (*test_cloud, *dst_blob);
00921
00922 octree_disk octreeA (depth, min, max, filename_otreeA, "ECEF");
00923 octree_disk octreeB (depth, min, max, filename_otreeB, "ECEF");
00924
00925 uint64_t points_added = octreeA.addPointCloud (dst_blob, false);
00926 uint64_t LOD_points_added = octreeB.addPointCloud_and_genLOD (dst_blob);
00927
00928 ASSERT_EQ (points_added, dst_blob->width*dst_blob->height) << "Number of points returned by addPointCloud does not match the number of poitns in the input point cloud\n";
00929 ASSERT_EQ (LOD_points_added, dst_blob->width*dst_blob->height) << "Number of points returned by addPointCloud_and_genLOD does not match the number of points in the input point cloud\n";
00930
00931 pcl::PCLPointCloud2::Ptr query_result_a (new pcl::PCLPointCloud2 ());
00932 pcl::PCLPointCloud2::Ptr query_result_b (new pcl::PCLPointCloud2 ());
00933
00934 octreeA.queryBBIncludes (min, max, int (octreeA.getDepth ()), query_result_a);
00935
00936 EXPECT_EQ (test_cloud->width*test_cloud->height, query_result_a->width*query_result_a->height) << "PCLPointCloud2 Query number of points returned failed\n";
00937
00938 uint64_t total_octreeB_LOD_query = 0;
00939
00940 for (int i=0; i <= octreeB.getDepth (); i++)
00941 {
00942 octreeB.queryBBIncludes (min, max, i, query_result_b);
00943 total_octreeB_LOD_query += query_result_b->width*query_result_b->height;
00944 query_result_b->data.clear ();
00945 query_result_b->width =0;
00946 query_result_b->height =0;
00947 }
00948
00949 EXPECT_EQ (test_cloud->width*test_cloud->height, total_octreeB_LOD_query) << "PCLPointCloud2 Query number of points returned failed\n";
00950
00951 cleanUpFilesystem ();
00952 }
00953
00954
00955 int
00956 main (int argc, char** argv)
00957 {
00958
00959 testing::InitGoogleTest (&argc, argv);
00960 return (RUN_ALL_TESTS ());
00961 }
00962