test_octree.cpp
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2010, Willow Garage, Inc.
00005  *  All rights reserved.
00006  *
00007  *  Redistribution and use in source and binary forms, with or without
00008  *  modification, are permitted provided that the following conditions
00009  *  are met:
00010  *
00011  *   * Redistributions of source code must retain the above copyright
00012  *     notice, this list of conditions and the following disclaimer.
00013  *   * Redistributions in binary form must reproduce the above
00014  *     copyright notice, this list of conditions and the following
00015  *     disclaimer in the documentation and/or other materials provided
00016  *     with the distribution.
00017  *   * Neither the name of Willow Garage, Inc. nor the names of its
00018  *     contributors may be used to endorse or promote products derived
00019  *     from this software without specific prior written permission.
00020  *
00021  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032  *  POSSIBILITY OF SUCH DAMAGE.
00033  *
00034  *
00035  */
00036 #include <gtest/gtest.h>
00037 
00038 #include <vector>
00039 
00040 #include <stdio.h>
00041 
00042 using namespace std;
00043 
00044 #include <pcl/common/time.h>
00045 #include <pcl/point_cloud.h>
00046 #include <pcl/point_types.h>
00047 
00048 using namespace pcl;
00049 
00050 #include <pcl/octree/octree.h>
00051 #include <pcl/octree/octree_impl.h>
00052 
00053 using namespace octree;
00054 
00055 TEST (PCL, Octree_Test)
00056 {
00057 
00058   unsigned int i, j;
00059   int data[256];
00060 
00061   // create octree instance
00062   OctreeBase<int> octreeA;
00063   OctreeBase<int> octreeB;
00064 
00065   // set octree depth
00066   octreeA.setTreeDepth (8);
00067   octreeB.setTreeDepth (8);
00068 
00069   struct MyVoxel
00070   {
00071     unsigned int x;
00072     unsigned int y;
00073     unsigned int z;
00074   };
00075   MyVoxel voxels[256];
00076 
00077   srand (static_cast<unsigned int> (time (NULL)));
00078 
00079   // generate some voxel indices
00080   for (i = 0; i < 256; i++)
00081   {
00082     data[i] = i;
00083 
00084     voxels[i].x = i;
00085     voxels[i].y = 255 - i;
00086     voxels[i].z = i;
00087 
00088     // add data to leaf node voxel
00089     octreeA.addData (voxels[i].x, voxels[i].y, voxels[i].z, data[i]);
00090   }
00091 
00092   int LeafNode;
00093   for (i = 0; i < 128; i++)
00094   {
00095     // retrieve data from leaf node voxel
00096     octreeA.getData (voxels[i].x, voxels[i].y, voxels[i].z, LeafNode);
00097     // check if retrieved data is identical to data[]
00098     ASSERT_EQ(LeafNode, data[i]);
00099   }
00100 
00101   for (i = 128; i < 256; i++)
00102   {
00103     // check if leaf node exists in tree
00104     ASSERT_EQ( octreeA.existLeaf(voxels[i].x,voxels[i].y,voxels[i].z), true);
00105 
00106     // remove leaf node
00107     octreeA.removeLeaf (voxels[i].x, voxels[i].y, voxels[i].z);
00108 
00109     //  leaf node shouldn't exist in tree anymore
00110     ASSERT_EQ( octreeA.existLeaf(voxels[i].x,voxels[i].y,voxels[i].z), false);
00111   }
00112 
00113   // test serialization
00114 
00115   std::vector<char> treeBinaryA;
00116   std::vector<char> treeBinaryB;
00117 
00118   std::vector<int> leafVectorA;
00119   std::vector<int> leafVectorB;
00120 
00121   // serialize tree - generate binary octree description
00122   octreeA.serializeTree (treeBinaryA);
00123 
00124   // deserialize tree - rebuild octree based on binary octree description
00125   octreeB.deserializeTree (treeBinaryA);
00126 
00127   for (i = 0; i < 128; i++)
00128   {
00129     // check if leafs exist in both octrees
00130     ASSERT_EQ( octreeA.existLeaf(voxels[i].x,voxels[i].y,voxels[i].z), true);
00131     ASSERT_EQ( octreeB.existLeaf(voxels[i].x,voxels[i].y,voxels[i].z), true);
00132   }
00133 
00134   for (i = 128; i < 256; i++)
00135   {
00136     // these leafs were not copies and should not exist
00137     ASSERT_EQ( octreeB.existLeaf(voxels[i].x,voxels[i].y,voxels[i].z), false);
00138   }
00139 
00140   // testing deleteTree();
00141   octreeB.deleteTree ();
00142 
00143   // octreeB.getLeafCount() should be zero now;
00144   ASSERT_EQ (static_cast <unsigned int> (0), octreeB.getLeafCount());
00145 
00146   // .. and previous leafs deleted..
00147   for (i = 0; i < 128; i++)
00148   {
00149     ASSERT_EQ(octreeB.existLeaf(voxels[i].x,voxels[i].y,voxels[i].z), false);
00150   }
00151 
00152   // test tree serialization
00153   octreeA.serializeTree (treeBinaryA, leafVectorA);
00154 
00155   // make sure, we retrieved all data objects
00156   ASSERT_EQ(leafVectorA.size(), octreeA.getLeafCount());
00157 
00158   // check if leaf data is found in octree input data
00159   bool bFound;
00160   for (i = 0; i < 128; i++)
00161   {
00162     int leafInt = leafVectorA.back ();
00163     leafVectorA.pop_back ();
00164 
00165     bFound = false;
00166     for (j = 0; j < 256; j++)
00167       if (data[j] == leafInt)
00168       {
00169         bFound = true;
00170         break;
00171       }
00172 
00173     ASSERT_EQ(bFound, true);
00174   }
00175 
00176   // test tree serialization
00177   octreeA.serializeLeafs (leafVectorA);
00178 
00179   for (i = 0; i < 128; i++)
00180   {
00181     int leafInt = leafVectorA.back ();
00182     leafVectorA.pop_back ();
00183 
00184     bFound = false;
00185     for (j = 0; j < 256; j++)
00186       if (data[j] == leafInt)
00187       {
00188         bFound = true;
00189         break;
00190       }
00191 
00192     ASSERT_EQ(bFound, true);
00193   }
00194 
00195   // test tree serialization with leaf data vectors
00196   octreeA.serializeTree (treeBinaryA, leafVectorA);
00197   octreeB.deserializeTree (treeBinaryA, leafVectorA);
00198 
00199   // test size and leaf count of reconstructed octree
00200   ASSERT_EQ(octreeA.getLeafCount(), octreeB.getLeafCount());
00201   ASSERT_EQ(static_cast<unsigned int> (128), octreeB.getLeafCount());
00202 
00203   octreeB.serializeTree (treeBinaryB, leafVectorB);
00204 
00205   // compare octree data content of octree A and octree B
00206   ASSERT_EQ(leafVectorB.size(), octreeB.getLeafCount());
00207   ASSERT_EQ(leafVectorA.size(), leafVectorB.size());
00208 
00209   for (i = 0; i < leafVectorB.size (); i++)
00210   {
00211     ASSERT_EQ( (leafVectorA[i] == leafVectorB[i]), true);
00212   }
00213 
00214   //  test iterator
00215 
00216   OctreeBase<int>::Iterator a_it (octreeA);
00217   unsigned int node_count = 0;
00218   unsigned int branch_count = 0;
00219   unsigned int leaf_count = 0;
00220 
00221   // iterate over tree
00222   while (*++a_it)
00223   {
00224     // depth should always be less than tree depth
00225     unsigned int depth = a_it.getCurrentOctreeDepth ();
00226     ASSERT_LE(depth, octreeA.getTreeDepth());
00227 
00228     // store node, branch and leaf count
00229     const OctreeNode* node = a_it.getCurrentOctreeNode ();
00230     if (node->getNodeType () == BRANCH_NODE)
00231     {
00232       branch_count++;
00233     }
00234     else if (node->getNodeType () == LEAF_NODE)
00235     {
00236       leaf_count++;
00237     }
00238     node_count++;
00239   }
00240 
00241   // compare node, branch and leaf count against actual tree values
00242   ASSERT_EQ(node_count, branch_count + leaf_count);
00243   ASSERT_EQ(leaf_count, octreeA.getLeafCount ());
00244 
00245 }
00246 
00247 TEST (PCL, Octree_Dynamic_Depth_Test)
00248 {
00249 
00250   size_t i;
00251   int test_runs = 100;
00252   int pointcount = 300;
00253 
00254   int test, point;
00255 
00256   float resolution = 0.01f;
00257 
00258   const static size_t leafAggSize = 5;
00259 
00260   OctreePointCloudPointVector<PointXYZ> octree (resolution);
00261 
00262   // create shared pointcloud instances
00263   PointCloud<PointXYZ>::Ptr cloud (new PointCloud<PointXYZ> ());
00264 
00265   // assign input point clouds to octree
00266   octree.setInputCloud (cloud);
00267 
00268   for (test = 0; test < test_runs; ++test)
00269   {
00270 
00271     // clean up
00272     cloud->points.clear ();
00273     octree.deleteTree ();
00274 
00275     for (point = 0; point < pointcount; point++)
00276     {
00277       // gereate a random point
00278       PointXYZ newPoint (static_cast<float> (1024.0 * rand () / RAND_MAX),
00279           static_cast<float> (1024.0 * rand () / RAND_MAX),
00280           static_cast<float> (1024.0 * rand () / RAND_MAX));
00281 
00282       // OctreePointCloudPointVector can store all points..
00283       cloud->push_back (newPoint);
00284     }
00285 
00286     // check if all points from leaf data can be found in input pointcloud data sets
00287     octree.defineBoundingBox ();
00288     octree.enableDynamicDepth (leafAggSize);
00289     octree.addPointsFromInputCloud ();
00290 
00291     //  test iterator
00292     OctreePointCloudPointVector<PointXYZ>::LeafNodeIterator it (octree);
00293     unsigned int leaf_count = 0;
00294 
00295 
00296     std::vector<int> indexVector;
00297 
00298     // iterate over tree
00299     while (*++it)
00300     {
00301       OctreeNode* node = it.getCurrentOctreeNode ();
00302 
00303       ASSERT_EQ(node->getNodeType(), LEAF_NODE);
00304 
00305       if (it.getCurrentOctreeDepth () < octree.getTreeDepth ())
00306         ASSERT_LE(it.getSize(), leafAggSize);
00307 
00308       // add points from leaf node to indexVector
00309       it.getData (indexVector);
00310 
00311       // test points against bounding box of leaf node
00312       std::vector<int> tmpVector;
00313       it.getData (tmpVector);
00314 
00315       Eigen::Vector3f min_pt, max_pt;
00316       octree.getVoxelBounds (it, min_pt, max_pt);
00317 
00318       for (i=0; i<tmpVector.size(); ++i)
00319       {
00320         ASSERT_GE(cloud->points[tmpVector[i]].x, min_pt(0));
00321         ASSERT_GE(cloud->points[tmpVector[i]].y, min_pt(1));
00322         ASSERT_GE(cloud->points[tmpVector[i]].z, min_pt(2));
00323         ASSERT_LE(cloud->points[tmpVector[i]].x, max_pt(0));
00324         ASSERT_LE(cloud->points[tmpVector[i]].y, max_pt(1));
00325         ASSERT_LE(cloud->points[tmpVector[i]].z, max_pt(2));
00326       }
00327 
00328       leaf_count++;
00329 
00330     }
00331     ASSERT_EQ(pointcount, indexVector.size());
00332 
00333     // make sure all indices are within indexVector
00334     for (i = 0; i < indexVector.size (); ++i)
00335     {
00336 #if !defined(__APPLE__)
00337       bool indexFound = (std::find(indexVector.begin(), indexVector.end(), i) != indexVector.end());
00338       ASSERT_EQ(indexFound, true);
00339 #endif
00340     }
00341 
00342     // compare node, branch and leaf count against actual tree values
00343     ASSERT_EQ(leaf_count, octree.getLeafCount ());
00344 
00345   }
00346 }
00347 
00348 TEST (PCL, Octree2Buf_Test)
00349 {
00350 
00351   // create octree instances
00352   Octree2BufBase<int> octreeA;
00353   Octree2BufBase<int> octreeB;
00354 
00355   // set octree depth
00356   octreeA.setTreeDepth (8);
00357   octreeB.setTreeDepth (8);
00358 
00359   struct MyVoxel
00360   {
00361     unsigned int x;
00362     unsigned int y;
00363     unsigned int z;
00364   };
00365 
00366   unsigned int i, j;
00367   int data[256];
00368   MyVoxel voxels[256];
00369 
00370   srand (static_cast<unsigned int> (time (NULL)));
00371 
00372   // generate some voxel indices
00373   for (i = 0; i < 256; i++)
00374   {
00375     data[i] = i;
00376 
00377     voxels[i].x = i;
00378     voxels[i].y = 255 - i;
00379     voxels[i].z = i;
00380 
00381     // add data to leaf node voxel
00382     octreeA.addData (voxels[i].x, voxels[i].y, voxels[i].z, data[i]);
00383 
00384   }
00385 
00386   ASSERT_EQ(static_cast<unsigned int> (256), octreeA.getLeafCount());
00387 
00388   int TreeData;
00389 
00390   for (i = 0; i < 128; i++)
00391   {
00392     // retrieve and check data from leaf voxel
00393     octreeA.getData (voxels[i].x, voxels[i].y, voxels[i].z, TreeData);
00394     ASSERT_EQ(TreeData, data[i]);
00395   }
00396 
00397   for (i = 128; i < 256; i++)
00398   {
00399     // check if leaf node exists in tree
00400     ASSERT_EQ( octreeA.existLeaf(voxels[i].x,voxels[i].y,voxels[i].z), true);
00401 
00402     // remove leaf node
00403     octreeA.removeLeaf (voxels[i].x, voxels[i].y, voxels[i].z);
00404 
00405     //  leaf node shouldn't exist in tree anymore
00406     ASSERT_EQ( octreeA.existLeaf(voxels[i].x,voxels[i].y,voxels[i].z), false);
00407   }
00408 
00410 
00411   // test serialization
00412 
00413   std::vector<char> treeBinaryA;
00414   std::vector<char> treeBinaryB;
00415 
00416   std::vector<int> leafVectorA;
00417   std::vector<int> leafVectorB;
00418 
00419   // serialize tree - generate binary octree description
00420   octreeA.serializeTree (treeBinaryA);
00421 
00422   // deserialize tree - rebuild octree based on binary octree description
00423   octreeB.deserializeTree (treeBinaryA);
00424 
00425   // check if leafs exist in octrees
00426   for (i = 0; i < 128; i++)
00427   {
00428     ASSERT_EQ( octreeB.existLeaf(voxels[i].x,voxels[i].y,voxels[i].z), true);
00429   }
00430 
00431   // these leafs should not exist..
00432   for (i = 128; i < 256; i++)
00433   {
00434     ASSERT_EQ( octreeB.existLeaf(voxels[i].x,voxels[i].y,voxels[i].z), false);
00435   }
00436 
00437   // checking deleteTree();
00438   octreeB.deleteTree ();
00439   octreeB.setTreeDepth (8);
00440 
00441   // octreeB.getLeafCount() should be zero now;
00442   ASSERT_EQ(static_cast<unsigned int> (0), octreeB.getLeafCount());
00443 
00444   for (i = 0; i < 128; i++)
00445   {
00446     ASSERT_EQ( octreeB.existLeaf(voxels[i].x,voxels[i].y,voxels[i].z), false);
00447   }
00448 
00449   // test tree serialization
00450   octreeA.serializeTree (treeBinaryA, leafVectorA);
00451 
00452   // make sure, we retrieved all data objects
00453   ASSERT_EQ(leafVectorA.size(), octreeA.getLeafCount());
00454 
00455   // check if leaf data is found in octree input data
00456   bool bFound;
00457   for (i = 0; i < 128; i++)
00458   {
00459     int leafInt = leafVectorA.back ();
00460     leafVectorA.pop_back ();
00461 
00462     bFound = false;
00463     for (j = 0; j < 256; j++)
00464       if (data[j] == leafInt)
00465       {
00466         bFound = true;
00467         break;
00468       }
00469 
00470     ASSERT_EQ(bFound, true);
00471   }
00472 
00473   // test tree serialization
00474   octreeA.serializeLeafs (leafVectorA);
00475 
00476   for (i = 0; i < 128; i++)
00477   {
00478     int leafInt = leafVectorA.back ();
00479     leafVectorA.pop_back ();
00480 
00481     bFound = false;
00482     for (j = 0; j < 256; j++)
00483       if (data[j] == leafInt)
00484       {
00485         bFound = true;
00486         break;
00487       }
00488 
00489     ASSERT_EQ(bFound, true);
00490   }
00491 
00492   // test tree serialization with leaf data vectors
00493   octreeA.serializeTree (treeBinaryA, leafVectorA);
00494   octreeB.deserializeTree (treeBinaryA, leafVectorA);
00495 
00496   ASSERT_EQ(octreeA.getLeafCount(), octreeB.getLeafCount());
00497   ASSERT_EQ(static_cast<unsigned int> (128), octreeB.getLeafCount());
00498 
00499   octreeB.serializeTree (treeBinaryB, leafVectorB);
00500 
00501   // test size and leaf count of reconstructed octree
00502   ASSERT_EQ(leafVectorB.size(), octreeB.getLeafCount());
00503   ASSERT_EQ(leafVectorA.size(), leafVectorB.size());
00504 
00505   for (i = 0; i < leafVectorB.size (); i++)
00506   {
00507     ASSERT_EQ( (leafVectorA[i] == leafVectorB[i]), true);
00508   }
00509 
00510 }
00511 
00512 
00513 TEST (PCL, Octree2Buf_Base_Double_Buffering_Test)
00514 {
00515 
00516 #define TESTPOINTS 3000
00517 
00518   // create octree instances
00519   Octree2BufBase<int> octreeA;
00520   Octree2BufBase<int> octreeB;
00521 
00522   std::vector<char> treeBinaryA;
00523   std::vector<char> treeBinaryB;
00524 
00525   std::vector<int> leafVectorA;
00526   std::vector<int> leafVectorB;
00527 
00528   octreeA.setTreeDepth (5);
00529   octreeB.setTreeDepth (5);
00530 
00531   struct MyVoxel
00532   {
00533     unsigned int x;
00534     unsigned int y;
00535     unsigned int z;
00536   };
00537 
00538   unsigned int i, j, k, runs;
00539   int data[TESTPOINTS];
00540   MyVoxel voxels[TESTPOINTS];
00541 
00542   srand (static_cast<unsigned int> (time (NULL)));
00543 
00544   const unsigned int test_runs = 20;
00545 
00546   for (j = 0; j < test_runs; j++)
00547   {
00548     octreeA.deleteTree ();
00549     octreeB.deleteTree ();
00550     octreeA.setTreeDepth (5);
00551     octreeB.setTreeDepth (5);
00552 
00553     runs = rand () % 20 + 1;
00554     for (k = 0; k < runs; k++)
00555     {
00556       // switch buffers
00557       octreeA.switchBuffers ();
00558       octreeB.switchBuffers ();
00559 
00560       for (i = 0; i < TESTPOINTS; i++)
00561       {
00562         data[i] = rand ();
00563 
00564         voxels[i].x = rand () % 4096;
00565         voxels[i].y = rand () % 4096;
00566         voxels[i].z = rand () % 4096;
00567 
00568         // add data to octree
00569 
00570         octreeA.addData (voxels[i].x, voxels[i].y, voxels[i].z, data[i]);
00571 
00572       }
00573 
00574       // test serialization
00575       octreeA.serializeTree (treeBinaryA, leafVectorA, true);
00576       octreeB.deserializeTree (treeBinaryA, leafVectorA, true);
00577     }
00578 
00579     octreeB.serializeTree (treeBinaryB, leafVectorB, true);
00580 
00581     // check leaf count of rebuilt octree
00582     ASSERT_EQ(octreeA.getLeafCount(), octreeB.getLeafCount());
00583     ASSERT_EQ(leafVectorB.size(), octreeB.getLeafCount());
00584     ASSERT_EQ(leafVectorA.size(), leafVectorB.size());
00585 
00586     // check if octree octree structure is consistent.
00587     for (i = 0; i < leafVectorB.size (); i++)
00588     {
00589       ASSERT_EQ( (leafVectorA[i] == leafVectorB[i]), true);
00590     }
00591 
00592   }
00593 
00594 }
00595 
00596 TEST (PCL, Octree2Buf_Base_Double_Buffering_XOR_Test)
00597 {
00598 
00599 #define TESTPOINTS 3000
00600 
00601   // create octree instances
00602   Octree2BufBase<int> octreeA;
00603   Octree2BufBase<int> octreeB;
00604 
00605   std::vector<char> treeBinaryA;
00606   std::vector<char> treeBinaryB;
00607 
00608   std::vector<int> leafVectorA;
00609   std::vector<int> leafVectorB;
00610 
00611   octreeA.setTreeDepth (5);
00612   octreeB.setTreeDepth (5);
00613 
00614   struct MyVoxel
00615   {
00616     unsigned int x;
00617     unsigned int y;
00618     unsigned int z;
00619   };
00620 
00621   unsigned int i, j;
00622   int data[TESTPOINTS];
00623   MyVoxel voxels[TESTPOINTS];
00624 
00625   srand (static_cast<unsigned int> (time (NULL)));
00626 
00627   const unsigned int test_runs = 15;
00628 
00629   for (j = 0; j < test_runs; j++)
00630   {
00631     for (i = 0; i < TESTPOINTS; i++)
00632     {
00633       data[i] = rand ();
00634 
00635       voxels[i].x = rand () % 4096;
00636       voxels[i].y = rand () % 4096;
00637       voxels[i].z = rand () % 4096;
00638 
00639       // add data to octree
00640 
00641       octreeA.addData (voxels[i].x, voxels[i].y, voxels[i].z, data[i]);
00642     }
00643 
00644     // test serialization - XOR tree binary data
00645     octreeA.serializeTree (treeBinaryA, leafVectorA, true);
00646     octreeB.deserializeTree (treeBinaryA, leafVectorA, true);
00647     octreeB.serializeTree (treeBinaryB, leafVectorB, true);
00648 
00649     // check leaf count of rebuilt octree
00650     ASSERT_EQ(octreeA.getLeafCount(), octreeB.getLeafCount());
00651     ASSERT_EQ(leafVectorB.size(), octreeB.getLeafCount());
00652     ASSERT_EQ(leafVectorA.size(), leafVectorB.size());
00653     ASSERT_EQ(treeBinaryA.size(), octreeB.getBranchCount());
00654     ASSERT_EQ(treeBinaryA.size(), treeBinaryB.size());
00655 
00656     // check if octree octree structure is consistent.
00657     for (i = 0; i < leafVectorB.size (); i++)
00658     {
00659       ASSERT_EQ( (leafVectorA[i] == leafVectorB[i]), true);
00660     }
00661 
00662     // switch buffers
00663     octreeA.switchBuffers ();
00664     octreeB.switchBuffers ();
00665 
00666   }
00667 
00668 }
00669 
00670 TEST (PCL, Octree_Pointcloud_Test)
00671 {
00672 
00673   size_t i;
00674   int test_runs = 100;
00675   int pointcount = 300;
00676 
00677   int test, point;
00678 
00679   float resolution = 0.01f;
00680 
00681   // instantiate OctreePointCloudSinglePoint and OctreePointCloudPointVector classes
00682   OctreePointCloudSinglePoint<PointXYZ> octreeA (resolution);
00683   OctreePointCloudSearch<PointXYZ> octreeB (resolution);
00684   OctreePointCloudPointVector<PointXYZ> octreeC (resolution);
00685 
00686   // create shared pointcloud instances
00687   PointCloud<PointXYZ>::Ptr cloudA (new PointCloud<PointXYZ> ());
00688   PointCloud<PointXYZ>::Ptr cloudB (new PointCloud<PointXYZ> ());
00689 
00690   // assign input point clouds to octree
00691   octreeA.setInputCloud (cloudA);
00692   octreeB.setInputCloud (cloudB);
00693   octreeC.setInputCloud (cloudB);
00694 
00695   for (test = 0; test < test_runs; ++test)
00696   {
00697 
00698     // clean up
00699     cloudA->points.clear ();
00700     octreeA.deleteTree ();
00701 
00702     cloudB->points.clear ();
00703     octreeB.deleteTree ();
00704 
00705     octreeC.deleteTree ();
00706 
00707     for (point = 0; point < pointcount; point++)
00708     {
00709       // gereate a random point
00710       PointXYZ newPoint (static_cast<float> (1024.0 * rand () / RAND_MAX), 
00711                          static_cast<float> (1024.0 * rand () / RAND_MAX), 
00712                          static_cast<float> (1024.0 * rand () / RAND_MAX));
00713 
00714       if (!octreeA.isVoxelOccupiedAtPoint (newPoint))
00715       {
00716         // add point only to OctreePointCloudSinglePoint if voxel at point location doesn't exist
00717         octreeA.addPointToCloud (newPoint, cloudA);
00718       }
00719 
00720       // OctreePointCloudPointVector can store all points..
00721       cloudB->push_back (newPoint);
00722     }
00723 
00724     ASSERT_EQ(octreeA.getLeafCount(), cloudA->points.size());
00725 
00726     // checks for getVoxelDataAtPoint() and isVoxelOccupiedAtPoint() functionality
00727     for (i = 0; i < cloudA->points.size (); i++)
00728     {
00729       ASSERT_EQ(octreeA.isVoxelOccupiedAtPoint(cloudA->points[i]), true);
00730       octreeA.deleteVoxelAtPoint (cloudA->points[i]);
00731       ASSERT_EQ(octreeA.isVoxelOccupiedAtPoint(cloudA->points[i]), false);
00732     }
00733 
00734     ASSERT_EQ(octreeA.getLeafCount(), static_cast<unsigned int> (0));
00735 
00736     // check if all points from leaf data can be found in input pointcloud data sets
00737     octreeB.defineBoundingBox ();
00738     octreeB.addPointsFromInputCloud ();
00739 
00740     //  test iterator
00741     OctreePointCloudSearch<PointXYZ>::Iterator b_it (octreeB);
00742     unsigned int node_count = 0;
00743     unsigned int branch_count = 0;
00744     unsigned int leaf_count = 0;
00745 
00746     double minx, miny, minz, maxx, maxy, maxz;
00747     octreeB.getBoundingBox (minx, miny, minz, maxx, maxy, maxz);
00748 
00749     // iterate over tree
00750     while (*++b_it)
00751     {
00752       // depth should always be less than tree depth
00753       unsigned int depth = b_it.getCurrentOctreeDepth ();
00754       ASSERT_LE(depth, octreeB.getTreeDepth());
00755 
00756       Eigen::Vector3f voxel_min, voxel_max;
00757       octreeB.getVoxelBounds (b_it, voxel_min, voxel_max);
00758 
00759       ASSERT_GE(voxel_min.x (), minx - 1e-4);
00760       ASSERT_GE(voxel_min.y (), miny - 1e-4);
00761       ASSERT_GE(voxel_min.z (), minz - 1e-4);
00762 
00763       ASSERT_LE(voxel_max.x (), maxx + 1e-4);
00764       ASSERT_LE(voxel_max.y (), maxy + 1e-4);
00765       ASSERT_LE(voxel_max.z (), maxz + 1e-4);
00766 
00767       // store node, branch and leaf count
00768       const OctreeNode* node = b_it.getCurrentOctreeNode ();
00769       if (node->getNodeType () == BRANCH_NODE)
00770       {
00771         branch_count++;
00772       }
00773       else if (node->getNodeType () == LEAF_NODE)
00774       {
00775         leaf_count++;
00776       }
00777       node_count++;
00778     }
00779 
00780     // compare node, branch and leaf count against actual tree values
00781     ASSERT_EQ(node_count, branch_count + leaf_count);
00782     ASSERT_EQ(leaf_count, octreeB.getLeafCount ());
00783 
00784     for (i = 0; i < cloudB->points.size (); i++)
00785     {
00786 
00787       std::vector<int> pointIdxVec;
00788       octreeB.voxelSearch (cloudB->points[i], pointIdxVec);
00789 
00790       bool bIdxFound = false;
00791       std::vector<int>::const_iterator current = pointIdxVec.begin ();
00792       while (current != pointIdxVec.end ())
00793       {
00794         if (*current == static_cast<int> (i))
00795         {
00796           bIdxFound = true;
00797           break;
00798         }
00799         ++current;
00800       }
00801 
00802       ASSERT_EQ(bIdxFound, true);
00803 
00804     }
00805 
00806     // test octree pointcloud serialization
00807 
00808     std::vector<char> treeBinaryB;
00809     std::vector<char> treeBinaryC;
00810 
00811     std::vector<int> leafVectorB;
00812     std::vector<int> leafVectorC;
00813 
00814     double minX, minY, minZ, maxX, maxY, maxZ;
00815 
00816     // serialize octreeB
00817     octreeB.serializeTree (treeBinaryB, leafVectorB);
00818     octreeB.getBoundingBox (minX, minY, minZ, maxX, maxY, maxZ);
00819 
00820     ASSERT_EQ(cloudB->points.size(), leafVectorB.size());
00821 
00822     // deserialize into octreeC
00823     octreeC.deleteTree ();
00824     octreeC.defineBoundingBox (minX, minY, minZ, maxX, maxY, maxZ);
00825 
00826     octreeC.deserializeTree (treeBinaryB, leafVectorB);
00827 
00828     // retrieve point data content of octreeC
00829     octreeC.serializeTree (treeBinaryC, leafVectorC);
00830 
00831     // check if data is consistent
00832     ASSERT_EQ(octreeB.getLeafCount(), octreeC.getLeafCount());
00833     ASSERT_EQ(treeBinaryB.size(), treeBinaryC.size());
00834     ASSERT_EQ(octreeB.getLeafCount(), cloudB->points.size());
00835 
00836     for (i = 0; i < leafVectorB.size (); ++i)
00837     {
00838       ASSERT_EQ(leafVectorB[i], leafVectorC[i]);
00839     }
00840 
00841     // check if binary octree output of both trees is equal
00842     for (i = 0; i < treeBinaryB.size (); ++i)
00843     {
00844       ASSERT_EQ(treeBinaryB[i], treeBinaryC[i]);
00845     }
00846 
00847   }
00848 
00849 }
00850 
00851 TEST (PCL, Octree_Pointcloud_Density_Test)
00852 {
00853 
00854   // instantiate point cloud and fill it with point data
00855 
00856   PointCloud<PointXYZ>::Ptr cloudIn (new PointCloud<PointXYZ> ());
00857 
00858   for (float z = 0.05f; z < 7.0f; z += 0.1f)
00859     for (float y = 0.05f; y < 7.0f; y += 0.1f)
00860       for (float x = 0.05f; x < 7.0f; x += 0.1f)
00861         cloudIn->push_back (PointXYZ (x, y, z));
00862 
00863   cloudIn->width = static_cast<uint32_t> (cloudIn->points.size ());
00864   cloudIn->height = 1;
00865 
00866   OctreePointCloudDensity<PointXYZ> octreeA (1.0f); // low resolution
00867   OctreePointCloudDensity<PointXYZ> octreeB (0.00001f); // high resolution
00868 
00869   octreeA.defineBoundingBox (7.0, 7.0, 7.0);
00870   octreeB.defineBoundingBox (7.0, 7.0, 7.0);
00871 
00872   // add point data to octree
00873   octreeA.setInputCloud (cloudIn);
00874   octreeB.setInputCloud (cloudIn);
00875 
00876   octreeA.addPointsFromInputCloud ();
00877   octreeB.addPointsFromInputCloud ();
00878 
00879   // check density information
00880   for (float z = 1.5f; z < 3.5f; z += 1.0f)
00881     for (float y = 1.5f; y < 3.5f; y += 1.0f)
00882       for (float x = 1.5f; x < 3.5f; x += 1.0f)
00883         ASSERT_EQ(octreeA.getVoxelDensityAtPoint (PointXYZ(x, y, z)), static_cast<unsigned int> (1000));
00884 
00885   for (float z = 0.05f; z < 5.0f; z += 0.1f)
00886     for (float y = 0.05f; y < 5.0f; y += 0.1f)
00887       for (float x = 0.05f; x < 5.0f; x += 0.1f)
00888         ASSERT_EQ(octreeB.getVoxelDensityAtPoint (PointXYZ(x, y, z)), static_cast<unsigned int> (1));
00889 }
00890 
00891 TEST (PCL, Octree_Pointcloud_Iterator_Test)
00892 {
00893   // instantiate point cloud and fill it with point data
00894 
00895   PointCloud<PointXYZ>::Ptr cloudIn (new PointCloud<PointXYZ> ());
00896 
00897   for (float z = 0.05f; z < 7.0f; z += 0.1f)
00898     for (float y = 0.05f; y < 7.0f; y += 0.1f)
00899       for (float x = 0.05f; x < 7.0f; x += 0.1f)
00900         cloudIn->push_back (PointXYZ (x, y, z));
00901 
00902   cloudIn->width = static_cast<uint32_t> (cloudIn->points.size ());
00903   cloudIn->height = 1;
00904 
00905   OctreePointCloud<PointXYZ> octreeA (1.0f); // low resolution
00906 
00907   // add point data to octree
00908   octreeA.setInputCloud (cloudIn);
00909   octreeA.addPointsFromInputCloud ();
00910 
00911   // instantiate iterator for octreeA
00912   OctreePointCloud<PointXYZ>::LeafNodeIterator it1 (octreeA);
00913 
00914   std::vector<int> indexVector;
00915   unsigned int leafNodeCounter = 0;
00916 
00917   // test preincrement
00918   ++it1;
00919   it1.getData (indexVector);
00920   leafNodeCounter++;
00921 
00922   // test postincrement
00923   it1++;
00924   it1.getData (indexVector);
00925   leafNodeCounter++;
00926 
00927   while (*++it1)
00928   {
00929     it1.getData (indexVector);
00930     leafNodeCounter++;
00931   }
00932 
00933   ASSERT_EQ(indexVector.size(), cloudIn->points.size ());
00934   ASSERT_EQ(leafNodeCounter, octreeA.getLeafCount());
00935 
00936   OctreePointCloud<PointXYZ>::Iterator it2 (octreeA);
00937 
00938   unsigned int traversCounter = 0;
00939   while (*++it2)
00940   {
00941     traversCounter++;
00942   }
00943 
00944   ASSERT_EQ(traversCounter > octreeA.getLeafCount() + octreeA.getBranchCount(), true);
00945 
00946   // breadth-first iterator test
00947 
00948   OctreePointCloud<PointXYZ>::BreadthFirstIterator bfIt (octreeA);
00949 
00950   unsigned int lastDepth = 0;
00951   unsigned int branchNodeCount = 1;
00952   unsigned int leafNodeCount = 0;
00953 
00954   bool leafNodeVisited = false;
00955 
00956   while (*++bfIt)
00957   {
00958     // tree depth of visited nodes must grow
00959     ASSERT_EQ( bfIt.getCurrentOctreeDepth()>=lastDepth, true);
00960     lastDepth = bfIt.getCurrentOctreeDepth ();
00961 
00962     if (bfIt.isBranchNode ())
00963     {
00964       branchNodeCount++;
00965       // leaf nodes are traversed in the end
00966       ASSERT_EQ( leafNodeVisited, false);
00967     }
00968 
00969     if (bfIt.isLeafNode ())
00970     {
00971       leafNodeCount++;
00972       leafNodeVisited = true;
00973     }
00974   }
00975 
00976   // check if every branch node and every leaf node has been visited
00977   ASSERT_EQ( leafNodeCount, octreeA.getLeafCount());
00978   ASSERT_EQ( branchNodeCount, octreeA.getBranchCount());
00979 
00980 }
00981 
00982 TEST(PCL, Octree_Pointcloud_Occupancy_Test)
00983 {
00984   const unsigned int test_runs = 100;
00985   unsigned int test_id;
00986 
00987   // instantiate point cloud
00988 
00989   PointCloud<PointXYZ>::Ptr cloudIn (new PointCloud<PointXYZ> ());
00990 
00991   OctreePointCloudOccupancy<PointXYZ> octree (0.00001f);
00992 
00993   size_t i;
00994 
00995   srand (static_cast<unsigned int> (time (NULL)));
00996 
00997   for (test_id = 0; test_id < test_runs; test_id++)
00998   {
00999 
01000     cloudIn->width = 1000;
01001     cloudIn->height = 1;
01002     cloudIn->points.resize (cloudIn->width * cloudIn->height);
01003 
01004     // generate point data for point cloud
01005     for (i = 0; i < 1000; i++)
01006     {
01007       cloudIn->points[i] = PointXYZ (static_cast<float> (5.0  * rand () / RAND_MAX),
01008                                      static_cast<float> (10.0 * rand () / RAND_MAX),
01009                                      static_cast<float> (10.0 * rand () / RAND_MAX));
01010     }
01011 
01012     // create octree
01013     octree.setInputCloud (cloudIn);
01014     octree.addPointsFromInputCloud ();
01015 
01016     // check occupancy of voxels
01017     for (i = 0; i < 1000; i++)
01018     {
01019       ASSERT_EQ(octree.isVoxelOccupiedAtPoint(cloudIn->points[i]), true);
01020       octree.deleteVoxelAtPoint (cloudIn->points[i]);
01021       ASSERT_EQ(octree.isVoxelOccupiedAtPoint(cloudIn->points[i]), false);
01022     }
01023 
01024   }
01025 
01026 }
01027 
01028 TEST (PCL, Octree_Pointcloud_Change_Detector_Test)
01029 {
01030   // instantiate point cloud
01031 
01032   PointCloud<PointXYZ>::Ptr cloudIn (new PointCloud<PointXYZ> ());
01033 
01034   OctreePointCloudChangeDetector<PointXYZ> octree (0.01f);
01035 
01036   size_t i;
01037 
01038   srand (static_cast<unsigned int> (time (NULL)));
01039 
01040   cloudIn->width = 1000;
01041   cloudIn->height = 1;
01042   cloudIn->points.resize (cloudIn->width * cloudIn->height);
01043 
01044   // generate point data for point cloud
01045   for (i = 0; i < 1000; i++)
01046   {
01047     cloudIn->points[i] = PointXYZ (static_cast<float> (5.0  * rand () / RAND_MAX),
01048                                    static_cast<float> (10.0 * rand () / RAND_MAX),
01049                                    static_cast<float> (10.0 * rand () / RAND_MAX));
01050   }
01051 
01052   // assign point cloud to octree
01053   octree.setInputCloud (cloudIn);
01054 
01055   // add points from cloud to octree
01056   octree.addPointsFromInputCloud ();
01057 
01058   // switch buffers - reset tree
01059   octree.switchBuffers ();
01060 
01061   // add points from cloud to new octree buffer
01062   octree.addPointsFromInputCloud ();
01063 
01064   // add 1000 additional points
01065   for (i = 0; i < 1000; i++)
01066   {
01067     octree.addPointToCloud (
01068         PointXYZ (static_cast<float> (100.0 + 5.0  * rand () / RAND_MAX), 
01069                   static_cast<float> (100.0 + 10.0 * rand () / RAND_MAX),
01070                   static_cast<float> (100.0 + 10.0 * rand () / RAND_MAX)),
01071         cloudIn);
01072   }
01073 
01074   vector<int> newPointIdxVector;
01075 
01076   // get a vector of new points, which did not exist in previous buffer
01077   octree.getPointIndicesFromNewVoxels (newPointIdxVector);
01078 
01079   // should be 1000
01080   ASSERT_EQ( newPointIdxVector.size(), static_cast<std::size_t> (1000));
01081 
01082   // all point indices found should have an index of >= 1000
01083   for (i = 0; i < 1000; i++)
01084   {
01085     ASSERT_EQ( ( newPointIdxVector [i] >= 1000 ), true);
01086   }
01087 
01088 }
01089 
01090 TEST (PCL, Octree_Pointcloud_Voxel_Centroid_Test)
01091 {
01092 
01093   // instantiate point cloud
01094 
01095   PointCloud<PointXYZ>::Ptr cloudIn (new PointCloud<PointXYZ> ());
01096 
01097   OctreePointCloudVoxelCentroid<PointXYZ> octree (1.0f);
01098   octree.defineBoundingBox (10.0, 10.0, 10.0);
01099 
01100   size_t i;
01101 
01102   srand (static_cast<unsigned int> (time (NULL)));
01103 
01104   cloudIn->width = 10 * 3;
01105   cloudIn->height = 1;
01106   cloudIn->points.resize (cloudIn->width * cloudIn->height);
01107 
01108   // generate point data for point cloud
01109   for (i = 0; i < 10; i++)
01110   {
01111     // these three points should always be assigned to the same voxel in the octree
01112     cloudIn->points[i * 3 + 0] = PointXYZ (static_cast<float> (i) + 0.2f, static_cast<float> (i) + 0.2f, static_cast<float> (i) + 0.2f);
01113     cloudIn->points[i * 3 + 1] = PointXYZ (static_cast<float> (i) + 0.4f, static_cast<float> (i) + 0.4f, static_cast<float> (i) + 0.4f);
01114     cloudIn->points[i * 3 + 2] = PointXYZ (static_cast<float> (i) + 0.6f, static_cast<float> (i) + 0.6f, static_cast<float> (i) + 0.6f);
01115   }
01116 
01117   // assign point cloud to octree
01118   octree.setInputCloud (cloudIn);
01119 
01120   // add points from cloud to octree
01121   octree.addPointsFromInputCloud ();
01122 
01123   pcl::PointCloud<PointXYZ>::VectorType voxelCentroids;
01124   octree.getVoxelCentroids (voxelCentroids);
01125 
01126   // we expect 10 voxel centroids
01127   ASSERT_EQ (voxelCentroids.size(), static_cast<std::size_t> (10));
01128 
01129   // check centroid calculation
01130   for (i = 0; i < 10; i++)
01131   {
01132     EXPECT_NEAR(voxelCentroids[i].x, static_cast<float> (i)+0.4, 1e-4);
01133     EXPECT_NEAR(voxelCentroids[i].y, static_cast<float> (i)+0.4, 1e-4);
01134     EXPECT_NEAR(voxelCentroids[i].z, static_cast<float> (i)+0.4, 1e-4);
01135   }
01136 
01137 }
01138 
01139 // helper class for priority queue
01140 class prioPointQueueEntry
01141 {
01142 public:
01143   prioPointQueueEntry () : point_ (), pointDistance_ (), pointIdx_ ()
01144   {
01145   }
01146   prioPointQueueEntry (PointXYZ& point_arg, double pointDistance_arg, int pointIdx_arg) :
01147     point_ (point_arg),
01148     pointDistance_ (pointDistance_arg),
01149     pointIdx_ (pointIdx_arg)
01150   {
01151   }
01152 
01153   bool
01154   operator< (const prioPointQueueEntry& rhs_arg) const
01155   {
01156     return (this->pointDistance_ < rhs_arg.pointDistance_);
01157   }
01158 
01159   PointXYZ point_;
01160   double pointDistance_;
01161   int pointIdx_;
01162 
01163 };
01164 
01165 TEST (PCL, Octree_Pointcloud_Nearest_K_Neighbour_Search)
01166 {
01167 
01168   const unsigned int test_runs = 10;
01169   unsigned int test_id;
01170 
01171   // instantiate point cloud
01172   PointCloud<PointXYZ>::Ptr cloudIn (new PointCloud<PointXYZ> ());
01173 
01174   size_t i;
01175 
01176   srand (static_cast<unsigned int> (time (NULL)));
01177 
01178   unsigned int K;
01179 
01180   std::priority_queue<prioPointQueueEntry, pcl::PointCloud<prioPointQueueEntry>::VectorType> pointCandidates;
01181 
01182   // create octree
01183   OctreePointCloudSearch<PointXYZ> octree (0.1);
01184   octree.setInputCloud (cloudIn);
01185 
01186   std::vector<int> k_indices;
01187   std::vector<float> k_sqr_distances;
01188 
01189   std::vector<int> k_indices_bruteforce;
01190   std::vector<float> k_sqr_distances_bruteforce;
01191 
01192   for (test_id = 0; test_id < test_runs; test_id++)
01193   {
01194     // define a random search point
01195 
01196     PointXYZ searchPoint (static_cast<float> (10.0 * rand () / RAND_MAX), 
01197                           static_cast<float> (10.0 * rand () / RAND_MAX),
01198                           static_cast<float> (10.0 * rand () / RAND_MAX));
01199 
01200     K = 1 + rand () % 10;
01201 
01202     // generate point cloud
01203     cloudIn->width = 1000;
01204     cloudIn->height = 1;
01205     cloudIn->points.resize (cloudIn->width * cloudIn->height);
01206     for (i = 0; i < 1000; i++)
01207     {
01208       cloudIn->points[i] = PointXYZ (static_cast<float> (5.0  * rand () / RAND_MAX),
01209                                      static_cast<float> (10.0 * rand () / RAND_MAX),
01210                                      static_cast<float> (10.0 * rand () / RAND_MAX));
01211     }
01212 
01213     double pointDist;
01214 
01215     k_indices.clear ();
01216     k_sqr_distances.clear ();
01217 
01218     k_indices_bruteforce.clear ();
01219     k_sqr_distances_bruteforce.clear ();
01220 
01221     // push all points and their distance to the search point into a priority queue - bruteforce approach.
01222     for (i = 0; i < cloudIn->points.size (); i++)
01223     {
01224       pointDist = ((cloudIn->points[i].x - searchPoint.x) * (cloudIn->points[i].x - searchPoint.x)
01225           + (cloudIn->points[i].y - searchPoint.y) * (cloudIn->points[i].y - searchPoint.y)
01226           + (cloudIn->points[i].z - searchPoint.z) * (cloudIn->points[i].z - searchPoint.z));
01227 
01228       prioPointQueueEntry pointEntry (cloudIn->points[i], pointDist, static_cast<int> (i));
01229 
01230       pointCandidates.push (pointEntry);
01231     }
01232 
01233     // pop priority queue until we have the nearest K elements
01234     while (pointCandidates.size () > K)
01235       pointCandidates.pop ();
01236 
01237     // copy results into vectors
01238     unsigned idx = static_cast<unsigned> (pointCandidates.size ());
01239     k_indices_bruteforce.resize (idx);
01240     k_sqr_distances_bruteforce.resize (idx);
01241     while (pointCandidates.size ())
01242     {
01243       --idx;
01244       k_indices_bruteforce [idx] = pointCandidates.top ().pointIdx_;
01245       k_sqr_distances_bruteforce [idx] = static_cast<float> (pointCandidates.top ().pointDistance_);
01246 
01247       pointCandidates.pop ();
01248     }
01249     
01250     // octree nearest neighbor search
01251     octree.deleteTree ();
01252     octree.addPointsFromInputCloud ();
01253     octree.nearestKSearch (searchPoint, static_cast<int> (K), k_indices, k_sqr_distances);
01254 
01255     ASSERT_EQ( k_indices.size(), k_indices_bruteforce.size());
01256 
01257     // compare nearest neighbor results of octree with bruteforce search
01258     i = 0;
01259     while (k_indices_bruteforce.size ())
01260     {
01261       ASSERT_EQ( k_indices.back(), k_indices_bruteforce.back());
01262       EXPECT_NEAR(k_sqr_distances.back(), k_sqr_distances_bruteforce.back(), 1e-4);
01263 
01264       k_indices_bruteforce.pop_back ();
01265       k_indices.pop_back ();
01266 
01267       k_sqr_distances_bruteforce.pop_back ();
01268       k_sqr_distances.pop_back ();
01269 
01270     }
01271 
01272   }
01273 
01274 }
01275 
01276 TEST (PCL, Octree_Pointcloud_Box_Search)
01277 {
01278 
01279   const unsigned int test_runs = 30;
01280   unsigned int test_id;
01281 
01282   // instantiate point cloud
01283   PointCloud<PointXYZ>::Ptr cloudIn (new PointCloud<PointXYZ> ());
01284 
01285   size_t i;
01286 
01287   srand (static_cast<unsigned int> (time (NULL)));
01288 
01289   // create octree
01290   OctreePointCloudSearch<PointXYZ> octree (1);
01291   octree.setInputCloud (cloudIn);
01292 
01293   for (test_id = 0; test_id < test_runs; test_id++)
01294   {
01295     std::vector<int> k_indices;
01296 
01297     // generate point cloud
01298     cloudIn->width = 300;
01299     cloudIn->height = 1;
01300     cloudIn->points.resize (cloudIn->width * cloudIn->height);
01301     for (i = 0; i < cloudIn->points.size(); i++)
01302     {
01303       cloudIn->points[i] = PointXYZ (static_cast<float> (10.0 * rand () / RAND_MAX),
01304                                      static_cast<float> (10.0 * rand () / RAND_MAX),
01305                                      static_cast<float> (10.0 * rand () / RAND_MAX));
01306     }
01307 
01308 
01309     // octree points to octree
01310     octree.deleteTree ();
01311     octree.addPointsFromInputCloud ();
01312 
01313     // define a random search area
01314 
01315     Eigen::Vector3f lowerBoxCorner (static_cast<float> (4.0 * rand () / RAND_MAX),
01316                                     static_cast<float> (4.0 * rand () / RAND_MAX),
01317                                     static_cast<float> (4.0 * rand () / RAND_MAX));
01318     Eigen::Vector3f upperBoxCorner (static_cast<float> (5.0 + 4.0 * rand () / RAND_MAX),
01319                                     static_cast<float> (5.0 + 4.0 * rand () / RAND_MAX),
01320                                     static_cast<float> (5.0 + 4.0 * rand () / RAND_MAX));
01321 
01322     octree.boxSearch (lowerBoxCorner, upperBoxCorner, k_indices);
01323 
01324     // test every point in point cloud
01325     for (i = 0; i < 300; i++)
01326     {
01327       std::size_t j;
01328       bool inBox;
01329       bool idxInResults;
01330       const PointXYZ& pt = cloudIn->points[i];
01331 
01332       inBox = (pt.x > lowerBoxCorner (0)) && (pt.x < upperBoxCorner (0)) &&
01333               (pt.y > lowerBoxCorner (1)) && (pt.y < upperBoxCorner (1)) &&
01334               (pt.z > lowerBoxCorner (2)) && (pt.z < upperBoxCorner (2));
01335 
01336       idxInResults = false;
01337       for (j = 0; (j < k_indices.size ()) && (!idxInResults); ++j)
01338       {
01339         if (i == static_cast<unsigned int> (k_indices[j]))
01340           idxInResults = true;
01341       }
01342 
01343       ASSERT_EQ(idxInResults, inBox);
01344 
01345     }
01346 
01347   }
01348 }
01349 
01350 TEST(PCL, Octree_Pointcloud_Approx_Nearest_Neighbour_Search)
01351 {
01352   const unsigned int test_runs = 100;
01353   unsigned int test_id;
01354 
01355   unsigned int bestMatchCount = 0;
01356 
01357   // instantiate point cloud
01358   PointCloud<PointXYZ>::Ptr cloudIn (new PointCloud<PointXYZ> ());
01359 
01360   size_t i;
01361   srand (static_cast<unsigned int> (time (NULL)));
01362 
01363   double voxelResolution = 0.1;
01364 
01365   // create octree
01366   OctreePointCloudSearch<PointXYZ> octree (voxelResolution);
01367   octree.setInputCloud (cloudIn);
01368 
01369   for (test_id = 0; test_id < test_runs; test_id++)
01370   {
01371     // define a random search point
01372 
01373     PointXYZ searchPoint (static_cast<float> (10.0 * rand () / RAND_MAX), 
01374                           static_cast<float> (10.0 * rand () / RAND_MAX),
01375                           static_cast<float> (10.0 * rand () / RAND_MAX));
01376 
01377     // generate point cloud
01378     cloudIn->width = 1000;
01379     cloudIn->height = 1;
01380     cloudIn->points.resize (cloudIn->width * cloudIn->height);
01381     for (i = 0; i < 1000; i++)
01382     {
01383       cloudIn->points[i] = PointXYZ (static_cast<float> (5.0  * rand () / RAND_MAX),
01384                                      static_cast<float> (10.0 * rand () / RAND_MAX),
01385                                      static_cast<float> (10.0 * rand () / RAND_MAX));
01386     }
01387 
01388     // brute force search
01389     double pointDist;
01390     double BFdistance = numeric_limits<double>::max ();
01391     int BFindex = 0;
01392 
01393     for (i = 0; i < cloudIn->points.size (); i++)
01394     {
01395       pointDist = ((cloudIn->points[i].x - searchPoint.x) * (cloudIn->points[i].x - searchPoint.x)
01396           + (cloudIn->points[i].y - searchPoint.y) * (cloudIn->points[i].y - searchPoint.y)
01397           + (cloudIn->points[i].z - searchPoint.z) * (cloudIn->points[i].z - searchPoint.z));
01398 
01399       if (pointDist < BFdistance)
01400       {
01401         BFindex = static_cast<int> (i);
01402         BFdistance = pointDist;
01403       }
01404 
01405     }
01406 
01407     int ANNindex;
01408     float ANNdistance;
01409 
01410     // octree approx. nearest neighbor search
01411     octree.deleteTree ();
01412     octree.addPointsFromInputCloud ();
01413     octree.approxNearestSearch (searchPoint, ANNindex, ANNdistance);
01414 
01415     if (BFindex == ANNindex)
01416     {
01417       EXPECT_NEAR(ANNdistance, BFdistance, 1e-4);
01418       bestMatchCount++;
01419     }
01420 
01421   }
01422 
01423   // we should have found the absolute nearest neighbor at least once
01424   ASSERT_EQ( (bestMatchCount > 0), true);
01425 
01426 }
01427 
01428 TEST (PCL, Octree_Pointcloud_Neighbours_Within_Radius_Search)
01429 {
01430 
01431   const unsigned int test_runs = 100;
01432   unsigned int test_id;
01433 
01434   // instantiate point clouds
01435   PointCloud<PointXYZ>::Ptr cloudIn (new PointCloud<PointXYZ> ());
01436   PointCloud<PointXYZ>::Ptr cloudOut (new PointCloud<PointXYZ> ());
01437 
01438   size_t i;
01439 
01440   srand (static_cast<unsigned int> (time (NULL)));
01441 
01442   for (test_id = 0; test_id < test_runs; test_id++)
01443   {
01444     // define a random search point
01445     PointXYZ searchPoint (static_cast<float> (10.0 * rand () / RAND_MAX), 
01446                           static_cast<float> (10.0 * rand () / RAND_MAX),
01447                           static_cast<float> (10.0 * rand () / RAND_MAX));
01448 
01449     cloudIn->width = 1000;
01450     cloudIn->height = 1;
01451     cloudIn->points.resize (cloudIn->width * cloudIn->height);
01452 
01453     // generate point cloud data
01454     for (i = 0; i < 1000; i++)
01455     {
01456       cloudIn->points[i] = PointXYZ (static_cast<float> (10.0 * rand () / RAND_MAX),
01457                                      static_cast<float> (10.0 * rand () / RAND_MAX),
01458                                      static_cast<float> (5.0  * rand () / RAND_MAX));
01459     }
01460 
01461     OctreePointCloudSearch<PointXYZ> octree (0.001);
01462 
01463     // build octree
01464     octree.setInputCloud (cloudIn);
01465     octree.addPointsFromInputCloud ();
01466 
01467     double pointDist;
01468     double searchRadius = 5.0 * static_cast<float> (rand () / RAND_MAX);
01469 
01470     // bruteforce radius search
01471     vector<int> cloudSearchBruteforce;
01472     for (i = 0; i < cloudIn->points.size (); i++)
01473     {
01474       pointDist = sqrt (
01475           (cloudIn->points[i].x - searchPoint.x) * (cloudIn->points[i].x - searchPoint.x)
01476               + (cloudIn->points[i].y - searchPoint.y) * (cloudIn->points[i].y - searchPoint.y)
01477               + (cloudIn->points[i].z - searchPoint.z) * (cloudIn->points[i].z - searchPoint.z));
01478 
01479       if (pointDist <= searchRadius)
01480       {
01481         // add point candidates to vector list
01482         cloudSearchBruteforce.push_back (static_cast<int> (i));
01483       }
01484     }
01485 
01486     vector<int> cloudNWRSearch;
01487     vector<float> cloudNWRRadius;
01488 
01489     // execute octree radius search
01490     octree.radiusSearch (searchPoint, searchRadius, cloudNWRSearch, cloudNWRRadius);
01491 
01492     ASSERT_EQ( cloudNWRRadius.size(), cloudSearchBruteforce.size());
01493 
01494     // check if result from octree radius search can be also found in bruteforce search
01495     std::vector<int>::const_iterator current = cloudNWRSearch.begin ();
01496     while (current != cloudNWRSearch.end ())
01497     {
01498       pointDist = sqrt (
01499           (cloudIn->points[*current].x - searchPoint.x) * (cloudIn->points[*current].x - searchPoint.x)
01500               + (cloudIn->points[*current].y - searchPoint.y) * (cloudIn->points[*current].y - searchPoint.y)
01501               + (cloudIn->points[*current].z - searchPoint.z) * (cloudIn->points[*current].z - searchPoint.z));
01502 
01503       ASSERT_EQ( (pointDist<=searchRadius), true);
01504 
01505       ++current;
01506     }
01507 
01508     // check if result limitation works
01509     octree.radiusSearch (searchPoint, searchRadius, cloudNWRSearch, cloudNWRRadius, 5);
01510 
01511     ASSERT_EQ( cloudNWRRadius.size() <= 5, true);
01512 
01513   }
01514 
01515 }
01516 
01517 TEST (PCL, Octree_Pointcloud_Ray_Traversal)
01518 {
01519 
01520   const unsigned int test_runs = 100;
01521   unsigned int test_id;
01522 
01523   // instantiate point clouds
01524   PointCloud<PointXYZ>::Ptr cloudIn (new PointCloud<PointXYZ> ());
01525 
01526   octree::OctreePointCloudSearch<PointXYZ> octree_search (0.02f);
01527 
01528   // Voxels in ray
01529   pcl::PointCloud<pcl::PointXYZ>::VectorType voxelsInRay, voxelsInRay2;
01530 
01531   // Indices in ray
01532   std::vector<int> indicesInRay, indicesInRay2;
01533 
01534   srand (static_cast<unsigned int> (time (NULL)));
01535 
01536   for (test_id = 0; test_id < test_runs; test_id++)
01537   {
01538     // delete octree
01539     octree_search.deleteTree ();
01540     // define octree bounding box 10x10x10
01541     octree_search.defineBoundingBox (0.0, 0.0, 0.0, 10.0, 10.0, 10.0);
01542 
01543     cloudIn->width = 4;
01544     cloudIn->height = 1;
01545     cloudIn->points.resize (cloudIn->width * cloudIn->height);
01546 
01547     Eigen::Vector3f p (static_cast<float> (10.0 * rand () / RAND_MAX), 
01548                        static_cast<float> (10.0 * rand () / RAND_MAX),
01549                        static_cast<float> (10.0 * rand () / RAND_MAX));
01550 
01551     // origin
01552     Eigen::Vector3f o (static_cast<float> (12.0 * rand () / RAND_MAX), 
01553                        static_cast<float> (12.0 * rand () / RAND_MAX),
01554                        static_cast<float> (12.0 * rand () / RAND_MAX));
01555 
01556     cloudIn->points[0] = pcl::PointXYZ (p[0], p[1], p[2]);
01557 
01558     // direction vector
01559     Eigen::Vector3f dir (p - o);
01560 
01561     float tmin = 1.0;
01562     for (unsigned int j = 1; j < 4; j++)
01563     {
01564       tmin = tmin - 0.25f;
01565       Eigen::Vector3f n_p = o + (tmin * dir);
01566       cloudIn->points[j] = pcl::PointXYZ (n_p[0], n_p[1], n_p[2]);
01567     }
01568 
01569     // insert cloud point into octree
01570     octree_search.setInputCloud (cloudIn);
01571     octree_search.addPointsFromInputCloud ();
01572 
01573     octree_search.getIntersectedVoxelCenters (o, dir, voxelsInRay);
01574     octree_search.getIntersectedVoxelIndices (o, dir, indicesInRay);
01575 
01576     // check if all voxels in the cloud are penetraded by the ray
01577     ASSERT_EQ( voxelsInRay.size (), cloudIn->points.size ());
01578     // check if all indices of penetrated voxels are in cloud
01579     ASSERT_EQ( indicesInRay.size (), cloudIn->points.size ());
01580 
01581     octree_search.getIntersectedVoxelCenters (o, dir, voxelsInRay2, 1);
01582     octree_search.getIntersectedVoxelIndices (o, dir, indicesInRay2, 1);
01583 
01584     // check if only the point from a single voxel has been returned
01585     ASSERT_EQ( voxelsInRay2.size (), 1u );
01586     ASSERT_EQ( indicesInRay2.size (), 1u );
01587 
01588     // check if this point is the closest point to the origin
01589     pcl::PointXYZ pt = cloudIn->points[ indicesInRay2[0] ];
01590     Eigen::Vector3f d = Eigen::Vector3f (pt.x, pt.y, pt.z) - o;
01591     float min_dist = d.norm ();
01592 
01593     for (unsigned int i = 0; i < cloudIn->width * cloudIn->height; i++) {
01594         pt = cloudIn->points[i];
01595         d = Eigen::Vector3f (pt.x, pt.y, pt.z) - o;
01596         ASSERT_GE( d.norm (), min_dist );
01597     }
01598 
01599   }
01600 
01601 }
01602 
01603 /* ---[ */
01604 int
01605 main (int argc, char** argv)
01606 {
01607   testing::InitGoogleTest (&argc, argv);
01608   return (RUN_ALL_TESTS ());
01609 }
01610 /* ]--- */


pcl
Author(s): Open Perception
autogenerated on Mon Oct 6 2014 03:18:23