test_gp3.cpp
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Point Cloud Library (PCL) - www.pointclouds.org
00005  *  Copyright (c) 2012-, Open Perception, Inc.
00006  *
00007  *  All rights reserved.
00008  *
00009  *  Redistribution and use in source and binary forms, with or without
00010  *  modification, are permitted provided that the following conditions
00011  *  are met:
00012  *
00013  *   * Redistributions of source code must retain the above copyright
00014  *     notice, this list of conditions and the following disclaimer.
00015  *   * Redistributions in binary form must reproduce the above
00016  *     copyright notice, this list of conditions and the following
00017  *     disclaimer in the documentation and/or other materials provided
00018  *     with the distribution.
00019  *   * Neither the name of the copyright holder(s) nor the names of its
00020  *     contributors may be used to endorse or promote products derived
00021  *     from this software without specific prior written permission.
00022  *
00023  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00024  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00025  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00026  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00027  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00028  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00029  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00030  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00031  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00032  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00033  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00034  *  POSSIBILITY OF SUCH DAMAGE.
00035  *
00036  * $Id: test_surface.cpp 6579 2012-07-27 18:57:32Z rusu $
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/gp3.h>
00047 #include <pcl/common/common.h>
00048 
00049 #include <pcl/io/obj_io.h>
00050 #include <pcl/TextureMesh.h>
00051 #include <pcl/surface/texture_mapping.h>
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 // add by ktran to test update functions
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, GreedyProjectionTriangulation)
00069 {
00070   // Init objects
00071   PolygonMesh triangles;
00072   GreedyProjectionTriangulation<PointNormal> gp3;
00073 
00074   // Set parameters
00075   gp3.setInputCloud (cloud_with_normals);
00076   gp3.setSearchMethod (tree2);
00077   gp3.setSearchRadius (0.025);
00078   gp3.setMu (2.5);
00079   gp3.setMaximumNearestNeighbors (100);
00080   gp3.setMaximumSurfaceAngle(M_PI/4); // 45 degrees
00081   gp3.setMinimumAngle(M_PI/18); // 10 degrees
00082   gp3.setMaximumAngle(2*M_PI/3); // 120 degrees
00083   gp3.setNormalConsistency(false);
00084 
00085   // Reconstruct
00086   gp3.reconstruct (triangles);
00087   //saveVTKFile ("./test/bun0-gp3.vtk", triangles);
00088   EXPECT_EQ (triangles.cloud.width, cloud_with_normals->width);
00089   EXPECT_EQ (triangles.cloud.height, cloud_with_normals->height);
00090   EXPECT_NEAR (int (triangles.polygons.size ()), 685, 5);
00091 
00092   // Check triangles
00093   EXPECT_EQ (int (triangles.polygons.at (0).vertices.size ()), 3);
00094   EXPECT_EQ (int (triangles.polygons.at (0).vertices.at (0)), 0);
00095   EXPECT_EQ (int (triangles.polygons.at (0).vertices.at (1)), 12);
00096   EXPECT_EQ (int (triangles.polygons.at (0).vertices.at (2)), 198);
00097   EXPECT_EQ (int (triangles.polygons.at (684).vertices.size ()), 3);
00098   EXPECT_EQ (int (triangles.polygons.at (684).vertices.at (0)), 393);
00099   EXPECT_EQ (int (triangles.polygons.at (684).vertices.at (1)), 394);
00100   EXPECT_EQ (int (triangles.polygons.at (684).vertices.at (2)), 395);
00101 
00102   // Additional vertex information
00103   std::vector<int> parts = gp3.getPartIDs();
00104   std::vector<int> states = gp3.getPointStates();
00105   int nr_points = cloud_with_normals->width * cloud_with_normals->height;
00106   EXPECT_EQ (int (parts.size ()), nr_points);
00107   EXPECT_EQ (int (states.size ()), nr_points);
00108   EXPECT_EQ (parts[0], 0);
00109   EXPECT_EQ (states[0], gp3.COMPLETED);
00110   EXPECT_EQ (parts[393], 5);
00111   EXPECT_EQ (states[393], gp3.BOUNDARY);
00112 }
00113 
00115 TEST (PCL, GreedyProjectionTriangulation_Merge2Meshes)
00116 {
00117   // check if exist update cloud
00118   if(cloud_with_normals1->width * cloud_with_normals1->height > 0){
00119     // Init objects
00120     PolygonMesh triangles;
00121     PolygonMesh triangles1;
00122     GreedyProjectionTriangulation<PointNormal> gp3;
00123     GreedyProjectionTriangulation<PointNormal> gp31;
00124 
00125     // Set parameters
00126     gp3.setInputCloud (cloud_with_normals);
00127     gp3.setSearchMethod (tree2);
00128     gp3.setSearchRadius (0.025);
00129     gp3.setMu (2.5);
00130     gp3.setMaximumNearestNeighbors (100);
00131     gp3.setMaximumSurfaceAngle(M_PI/4); // 45 degrees
00132     gp3.setMinimumAngle(M_PI/18); // 10 degrees
00133     gp3.setMaximumAngle(2*M_PI/3); // 120 degrees
00134     gp3.setNormalConsistency(false);
00135 
00136     // for mesh 2
00137     // Set parameters
00138     gp31.setInputCloud (cloud_with_normals1);
00139     gp31.setSearchMethod (tree4);
00140     gp31.setSearchRadius (0.025);
00141     gp31.setMu (2.5);
00142     gp31.setMaximumNearestNeighbors (100);
00143     gp31.setMaximumSurfaceAngle(M_PI/4); // 45 degrees
00144     gp31.setMinimumAngle(M_PI/18); // 10 degrees
00145     gp31.setMaximumAngle(2*M_PI/3); // 120 degrees
00146     gp31.setNormalConsistency(false);
00147 
00148 
00149     // Reconstruct
00150     //gp3.reconstruct (triangles);
00151     //saveVTKFile ("bun01.vtk", triangles);
00152 
00153     //gp31.reconstruct (triangles1);
00154     //saveVTKFile ("bun02.vtk", triangles1);
00155   }
00156 }
00158 TEST (PCL, UpdateMesh_With_TextureMapping)
00159 {
00160   if(cloud_with_normals1->width * cloud_with_normals1->height > 0){
00161     // Init objects
00162     PolygonMesh triangles;
00163     PolygonMesh triangles1;
00164     GreedyProjectionTriangulation<PointNormal> gp3;
00165     GreedyProjectionTriangulation<PointNormal> gp31;
00166 
00167     // Set parameters
00168     gp3.setInputCloud (cloud_with_normals);
00169     gp3.setSearchMethod (tree2);
00170     gp3.setSearchRadius (0.025);
00171     gp3.setMu (2.5);
00172     gp3.setMaximumNearestNeighbors (100);
00173     gp3.setMaximumSurfaceAngle(M_PI/4); // 45 degrees
00174     gp3.setMinimumAngle(M_PI/18); // 10 degrees
00175     gp3.setMaximumAngle(2*M_PI/3); // 120 degrees
00176     gp3.setNormalConsistency(false);
00177 
00178     gp3.reconstruct (triangles);
00179 
00180     EXPECT_EQ (triangles.cloud.width, cloud_with_normals->width);
00181     EXPECT_EQ (triangles.cloud.height, cloud_with_normals->height);
00182     EXPECT_EQ (int (triangles.polygons.size ()), 685);
00183 
00184     // update with texture mapping
00185     // set 2 texture for 2 mesh
00186     std::vector<std::string> tex_files;
00187     tex_files.push_back("tex4.jpg");
00188 
00189     // initialize texture mesh
00190     TextureMesh tex_mesh;
00191     tex_mesh.cloud = triangles.cloud;
00192 
00193     // add the 1st mesh
00194     tex_mesh.tex_polygons.push_back(triangles.polygons);
00195 
00196     // update mesh and texture mesh
00197     //gp3.updateMesh(cloud_with_normals1, triangles, tex_mesh);
00198     // set texture for added cloud
00199     //tex_files.push_back("tex8.jpg");
00200     // save updated mesh
00201     //saveVTKFile ("update_bunny.vtk", triangles);
00202 
00203     //TextureMapping<PointXYZ> tm;
00204 
00206     //tm.setF(0.01);
00207 
00209     //tm.setVectorField(1, 0, 0);
00210 
00211     //TexMaterial tex_material;
00212 
00214     //tex_material.tex_Ka.r = 0.2f;
00215     //tex_material.tex_Ka.g = 0.2f;
00216     //tex_material.tex_Ka.b = 0.2f;
00217 
00218     //tex_material.tex_Kd.r = 0.8f;
00219     //tex_material.tex_Kd.g = 0.8f;
00220     //tex_material.tex_Kd.b = 0.8f;
00221 
00222     //tex_material.tex_Ks.r = 1.0f;
00223     //tex_material.tex_Ks.g = 1.0f;
00224     //tex_material.tex_Ks.b = 1.0f;
00225     //tex_material.tex_d = 1.0f;
00226     //tex_material.tex_Ns = 0.0f;
00227     //tex_material.tex_illum = 2;
00228 
00230     //tm.setTextureMaterials(tex_material);
00231 
00233     //tm.setTextureFiles(tex_files);
00234 
00236     //tm.mapTexture2Mesh(tex_mesh);
00237 
00238     //saveOBJFile ("update_bunny.obj", tex_mesh);
00239   }
00240 }
00241 
00242 /* ---[ */
00243 int
00244 main (int argc, char** argv)
00245 {
00246   if (argc < 2)
00247   {
00248     std::cerr << "No test file given. Please download `bun0.pcd` and pass its path to the test." << std::endl;
00249     return (-1);
00250   }
00251 
00252   // Load file
00253   pcl::PCLPointCloud2 cloud_blob;
00254   loadPCDFile (argv[1], cloud_blob);
00255   fromPCLPointCloud2 (cloud_blob, *cloud);
00256 
00257   // Create search tree
00258   tree.reset (new search::KdTree<PointXYZ> (false));
00259   tree->setInputCloud (cloud);
00260 
00261   // Normal estimation
00262   NormalEstimation<PointXYZ, Normal> n;
00263   PointCloud<Normal>::Ptr normals (new PointCloud<Normal> ());
00264   n.setInputCloud (cloud);
00265   //n.setIndices (indices[B);
00266   n.setSearchMethod (tree);
00267   n.setKSearch (20);
00268   n.compute (*normals);
00269 
00270   // Concatenate XYZ and normal information
00271   pcl::concatenateFields (*cloud, *normals, *cloud_with_normals);
00272       
00273   // Create search tree
00274   tree2.reset (new search::KdTree<PointNormal>);
00275   tree2->setInputCloud (cloud_with_normals);
00276 
00277   // Process for update cloud
00278   if(argc == 3){
00279     pcl::PCLPointCloud2 cloud_blob1;
00280     loadPCDFile (argv[2], cloud_blob1);
00281     fromPCLPointCloud2 (cloud_blob1, *cloud1);
00282         // Create search tree
00283     tree3.reset (new search::KdTree<PointXYZ> (false));
00284     tree3->setInputCloud (cloud1);
00285 
00286     // Normal estimation
00287     NormalEstimation<PointXYZ, Normal> n1;
00288     PointCloud<Normal>::Ptr normals1 (new PointCloud<Normal> ());
00289     n1.setInputCloud (cloud1);
00290 
00291     n1.setSearchMethod (tree3);
00292     n1.setKSearch (20);
00293     n1.compute (*normals1);
00294 
00295     // Concatenate XYZ and normal information
00296     pcl::concatenateFields (*cloud1, *normals1, *cloud_with_normals1);
00297     // Create search tree
00298     tree4.reset (new search::KdTree<PointNormal>);
00299     tree4->setInputCloud (cloud_with_normals1);
00300   }
00301 
00302   // Testing
00303   testing::InitGoogleTest (&argc, argv);
00304   return (RUN_ALL_TESTS ());
00305 }
00306 /* ]--- */


pcl
Author(s): Open Perception
autogenerated on Wed Aug 26 2015 15:34:55