Go to the documentation of this file.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 #include <gtest/gtest.h>
00041 
00042 #include <pcl/point_types.h>
00043 #include <pcl/io/pcd_io.h>
00044 #include <pcl/io/vtk_io.h>
00045 #include <pcl/features/normal_3d.h>
00046 #include <pcl/surface/mls.h>
00047 #include <pcl/surface/gp3.h>
00048 #include <pcl/surface/marching_cubes_hoppe.h>
00049 #include <pcl/surface/marching_cubes_rbf.h>
00050 #include <pcl/common/common.h>
00051 
00052 using namespace pcl;
00053 using namespace pcl::io;
00054 using namespace std;
00055 
00056 PointCloud<PointXYZ>::Ptr cloud (new PointCloud<PointXYZ>);
00057 PointCloud<PointNormal>::Ptr cloud_with_normals (new PointCloud<PointNormal>);
00058 search::KdTree<PointXYZ>::Ptr tree;
00059 search::KdTree<PointNormal>::Ptr tree2;
00060 
00061 
00062 PointCloud<PointXYZ>::Ptr cloud1 (new PointCloud<PointXYZ>);
00063 PointCloud<PointNormal>::Ptr cloud_with_normals1 (new PointCloud<PointNormal>);
00064 search::KdTree<PointXYZ>::Ptr tree3;
00065 search::KdTree<PointNormal>::Ptr tree4;
00066 
00068 TEST (PCL, MarchingCubesTest)
00069 {
00070   MarchingCubesHoppe<PointNormal> hoppe;
00071   hoppe.setIsoLevel (0);
00072   hoppe.setGridResolution (30, 30, 30);
00073   hoppe.setPercentageExtendGrid (0.3f);
00074   hoppe.setInputCloud (cloud_with_normals);
00075   PointCloud<PointNormal> points;
00076   std::vector<Vertices> vertices;
00077   hoppe.reconstruct (points, vertices);
00078 
00079   EXPECT_NEAR (points.points[points.size()/2].x, -0.042528, 1e-3);
00080   EXPECT_NEAR (points.points[points.size()/2].y, 0.080196, 1e-3);
00081   EXPECT_NEAR (points.points[points.size()/2].z, 0.043159, 1e-3);
00082   EXPECT_EQ (vertices[vertices.size ()/2].vertices[0], 10854);
00083   EXPECT_EQ (vertices[vertices.size ()/2].vertices[1], 10855);
00084   EXPECT_EQ (vertices[vertices.size ()/2].vertices[2], 10856);
00085 
00086 
00087   MarchingCubesRBF<PointNormal> rbf;
00088   rbf.setIsoLevel (0);
00089   rbf.setGridResolution (20, 20, 20);
00090   rbf.setPercentageExtendGrid (0.1f);
00091   rbf.setInputCloud (cloud_with_normals);
00092   rbf.setOffSurfaceDisplacement (0.02f);
00093   rbf.reconstruct (points, vertices);
00094 
00095   EXPECT_NEAR (points.points[points.size()/2].x, -0.033919, 1e-3);
00096   EXPECT_NEAR (points.points[points.size()/2].y, 0.151683, 1e-3);
00097   EXPECT_NEAR (points.points[points.size()/2].z, -0.000086, 1e-3);
00098   EXPECT_EQ (vertices[vertices.size ()/2].vertices[0], 4284);
00099   EXPECT_EQ (vertices[vertices.size ()/2].vertices[1], 4285);
00100   EXPECT_EQ (vertices[vertices.size ()/2].vertices[2], 4286);
00101 }
00102 
00103 
00104 
00105 int
00106 main (int argc, char** argv)
00107 {
00108   if (argc < 2)
00109   {
00110     std::cerr << "No test file given. Please download `bun0.pcd` and pass its path to the test." << std::endl;
00111     return (-1);
00112   }
00113 
00114   
00115   pcl::PCLPointCloud2 cloud_blob;
00116   loadPCDFile (argv[1], cloud_blob);
00117   fromPCLPointCloud2 (cloud_blob, *cloud);
00118 
00119   
00120   tree.reset (new search::KdTree<PointXYZ> (false));
00121   tree->setInputCloud (cloud);
00122 
00123   
00124   NormalEstimation<PointXYZ, Normal> n;
00125   PointCloud<Normal>::Ptr normals (new PointCloud<Normal> ());
00126   n.setInputCloud (cloud);
00127   
00128   n.setSearchMethod (tree);
00129   n.setKSearch (20);
00130   n.compute (*normals);
00131 
00132   
00133   pcl::concatenateFields (*cloud, *normals, *cloud_with_normals);
00134       
00135   
00136   tree2.reset (new search::KdTree<PointNormal>);
00137   tree2->setInputCloud (cloud_with_normals);
00138 
00139   
00140   if(argc == 3){
00141     pcl::PCLPointCloud2 cloud_blob1;
00142     loadPCDFile (argv[2], cloud_blob1);
00143     fromPCLPointCloud2 (cloud_blob1, *cloud1);
00144         
00145     tree3.reset (new search::KdTree<PointXYZ> (false));
00146     tree3->setInputCloud (cloud1);
00147 
00148     
00149     NormalEstimation<PointXYZ, Normal> n1;
00150     PointCloud<Normal>::Ptr normals1 (new PointCloud<Normal> ());
00151     n1.setInputCloud (cloud1);
00152 
00153     n1.setSearchMethod (tree3);
00154     n1.setKSearch (20);
00155     n1.compute (*normals1);
00156 
00157     
00158     pcl::concatenateFields (*cloud1, *normals1, *cloud_with_normals1);
00159     
00160     tree4.reset (new search::KdTree<PointNormal>);
00161     tree4->setInputCloud (cloud_with_normals1);
00162   }
00163 
00164   
00165   testing::InitGoogleTest (&argc, argv);
00166   return (RUN_ALL_TESTS ());
00167 }
00168