test_mesh_conversion.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) 2009-2012, Willow Garage, Inc.
00006  * Copyright (c) 2012-, Open Perception, Inc.
00007  *
00008  * All rights reserved.
00009  *
00010  * Redistribution and use in source and binary forms, with or without
00011  * modification, are permitted provided that the following conditions
00012  * are met:
00013  *
00014  *  * Redistributions of source code must retain the above copyright
00015  *    notice, this list of conditions and the following disclaimer.
00016  *  * Redistributions in binary form must reproduce the above
00017  *    copyright notice, this list of conditions and the following
00018  *    disclaimer in the documentation and/or other materials provided
00019  *    with the distribution.
00020  *  * Neither the name of the copyright holder(s) nor the names of its
00021  *    contributors may be used to endorse or promote products derived
00022  *    from this software without specific prior written permission.
00023  *
00024  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00025  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00026  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00027  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00028  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00029  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00030  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00031  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00032  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00033  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00034  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00035  * POSSIBILITY OF SUCH DAMAGE.
00036  *
00037  * $Id$
00038  *
00039  */
00040 
00041 #include <gtest/gtest.h>
00042 
00043 #include <pcl/geometry/triangle_mesh.h>
00044 #include <pcl/geometry/quad_mesh.h>
00045 #include <pcl/geometry/polygon_mesh.h>
00046 #include <pcl/geometry/mesh_conversion.h>
00047 #include <pcl/point_types.h>
00048 #include <pcl/point_cloud.h>
00049 
00050 #include "test_mesh_common_functions.h"
00051 
00053 
00054 template <class MeshTraitsT>
00055 class TestMeshConversion : public ::testing::Test
00056 {
00057   protected:
00058 
00059     typedef MeshTraitsT MeshTraits;
00060 
00061     // 2 - 1  7 - 6         17 - 16   //
00062     //  \ /   |   |        /       \  //
00063     //   0    8 - 5 - 11  12       15 //
00064     //  / \       |    |   \       /  //
00065     // 3 - 4      9 - 10    13 - 14   //
00066     void
00067     SetUp ()
00068     {
00069       // Vertices
00070       pcl::PointXYZRGBNormal pt;
00071       for (unsigned int i=0; i<18; ++i)
00072       {
00073         pt.x = static_cast <float> (10 * i);
00074         pt.y = static_cast <float> (20 * i);
00075         pt.z = static_cast <float> (30 * i);
00076 
00077         pt.normal_x = static_cast <float> (100 * i);
00078         pt.normal_y = static_cast <float> (200 * i);
00079         pt.normal_z = static_cast <float> (300 * i);
00080 
00081         pt.r = static_cast <uint8_t> (1 * i);
00082         pt.g = static_cast <uint8_t> (2 * i);
00083         pt.b = static_cast <uint8_t> (3 * i);
00084 
00085         vertices_.push_back (pt);
00086       }
00087 
00088       // Faces
00089       std::vector <uint32_t> face;
00090 
00091       face.push_back (0);
00092       face.push_back (1);
00093       face.push_back (2);
00094       manifold_faces_.push_back (face);
00095       non_manifold_faces_.push_back (face);
00096 
00097       face.clear ();
00098       face.push_back (0);
00099       face.push_back (3);
00100       face.push_back (4);
00101       non_manifold_faces_.push_back (face);
00102 
00103       face.clear ();
00104       face.push_back (5);
00105       face.push_back (6);
00106       face.push_back (7);
00107       face.push_back (8);
00108       manifold_faces_.push_back (face);
00109       non_manifold_faces_.push_back (face);
00110 
00111       face.clear ();
00112       face.push_back ( 5);
00113       face.push_back ( 9);
00114       face.push_back (10);
00115       face.push_back (11);
00116       non_manifold_faces_.push_back (face);
00117 
00118       face.clear ();
00119       face.push_back (12);
00120       face.push_back (13);
00121       face.push_back (14);
00122       face.push_back (15);
00123       face.push_back (16);
00124       face.push_back (17);
00125       manifold_faces_.push_back (face);
00126       non_manifold_faces_.push_back (face);
00127     }
00128 
00129     pcl::PointCloud <pcl::PointXYZRGBNormal> vertices_;
00130     std::vector <std::vector <uint32_t> >    non_manifold_faces_;
00131     std::vector <std::vector <uint32_t> >    manifold_faces_;
00132 
00133   public:
00134     EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00135 };
00136 
00137 template <bool IsManifoldT>
00138 struct MeshTraits
00139 {
00140     typedef pcl::PointXYZRGBNormal                       VertexData;
00141     typedef pcl::geometry::NoData                        HalfEdgeData;
00142     typedef pcl::geometry::NoData                        EdgeData;
00143     typedef pcl::geometry::NoData                        FaceData;
00144     typedef boost::integral_constant <bool, IsManifoldT> IsManifold;
00145 };
00146 
00147 typedef MeshTraits <true > ManifoldMeshTraits;
00148 typedef MeshTraits <false> NonManifoldMeshTraits;
00149 
00150 typedef testing::Types <ManifoldMeshTraits, NonManifoldMeshTraits> MeshTraitsTypes;
00151 
00152 TYPED_TEST_CASE (TestMeshConversion, MeshTraitsTypes);
00153 
00155 
00156 TYPED_TEST (TestMeshConversion, HalfEdgeMeshToFaceVertexMesh)
00157 {
00158   typedef typename TestFixture::MeshTraits    Traits;
00159   typedef pcl::geometry::PolygonMesh <Traits> Mesh;
00160   typedef typename Mesh::VertexIndex          VertexIndex;
00161   typedef typename Mesh::VertexIndices        VertexIndices;
00162 
00163   const std::vector <std::vector <uint32_t> > faces =
00164       Mesh::IsManifold::value ? this->manifold_faces_ :
00165                                 this->non_manifold_faces_;
00166 
00167   // Generate the mesh
00168   Mesh half_edge_mesh;
00169   VertexIndices vi;
00170 
00171   for (size_t i=0; i<this->vertices_.size (); ++i)
00172   {
00173     half_edge_mesh.addVertex (this->vertices_ [i]);
00174   }
00175 
00176   for (size_t i=0; i<faces.size (); ++i)
00177   {
00178     vi.clear ();
00179     for (int j=0; j<faces [i].size (); ++j)
00180     {
00181       vi.push_back (VertexIndex (static_cast <int> (faces [i][j])));
00182     }
00183 
00184     ASSERT_TRUE (half_edge_mesh.addFace (vi).isValid ()) << "Face number " << i;
00185   }
00186 
00187   // Convert
00188   pcl::PolygonMesh face_vertex_mesh;
00189   pcl::geometry::toFaceVertexMesh (half_edge_mesh, face_vertex_mesh);
00190 
00191   // Check if the cloud got copied correctly.
00192   pcl::PointCloud <pcl::PointXYZRGBNormal> converted_cloud;
00193   pcl::fromPCLPointCloud2 (face_vertex_mesh.cloud, converted_cloud);
00194   ASSERT_EQ (this->vertices_.size (), converted_cloud.size ());
00195   for (size_t i=0; i<this->vertices_.size (); ++i)
00196   {
00197     const pcl::PointXYZRGBNormal& expected_pt = this->vertices_ [i];
00198     const pcl::PointXYZRGBNormal& actual_pt   = converted_cloud [i];
00199 
00200     EXPECT_FLOAT_EQ (expected_pt.x, actual_pt.x);
00201     EXPECT_FLOAT_EQ (expected_pt.y, actual_pt.y);
00202     EXPECT_FLOAT_EQ (expected_pt.z, actual_pt.z);
00203 
00204     EXPECT_FLOAT_EQ (expected_pt.normal_x, actual_pt.normal_x);
00205     EXPECT_FLOAT_EQ (expected_pt.normal_y, actual_pt.normal_y);
00206     EXPECT_FLOAT_EQ (expected_pt.normal_z, actual_pt.normal_z);
00207 
00208     EXPECT_EQ (expected_pt.r, actual_pt.r);
00209     EXPECT_EQ (expected_pt.g, actual_pt.g);
00210     EXPECT_EQ (expected_pt.b, actual_pt.b);
00211   }
00212 
00213   // Check the polygons
00214   ASSERT_EQ (faces.size (), face_vertex_mesh.polygons.size ());
00215   for (size_t i=0; i<faces.size (); ++i)
00216   {
00217     EXPECT_TRUE (isCircularPermutation (faces [i], face_vertex_mesh.polygons [i].vertices)) << "Face number " << i;
00218   }
00219 }
00220 
00222 
00223 TYPED_TEST (TestMeshConversion, FaceVertexMeshToHalfEdgeMesh)
00224 {
00225   typedef typename TestFixture::MeshTraits          Traits;
00226   typedef pcl::geometry::PolygonMesh <Traits>       Mesh;
00227   typedef typename Mesh::FaceIndex                  FaceIndex;
00228   typedef typename Mesh::VertexAroundFaceCirculator VAFC;
00229 
00230   // Generate the mesh
00231   pcl::PolygonMesh face_vertex_mesh;
00232   pcl::toPCLPointCloud2 (this->vertices_, face_vertex_mesh.cloud);
00233   pcl::Vertices face;
00234   for (size_t i=0; i<this->non_manifold_faces_.size (); ++i)
00235   {
00236     face.vertices = this->non_manifold_faces_ [i];
00237     face_vertex_mesh.polygons.push_back (face);
00238   }
00239 
00240   // Convert
00241   Mesh half_edge_mesh;
00242 
00243   int n_not_added = pcl::geometry::toHalfEdgeMesh (face_vertex_mesh, half_edge_mesh);
00244   if (Mesh::IsManifold::value) ASSERT_EQ (2, n_not_added);
00245   else                         ASSERT_EQ (0, n_not_added);
00246 
00247   // Check if the cloud got copied correctly.
00248   ASSERT_EQ (this->vertices_.size (), half_edge_mesh.getVertexDataCloud ().size ());
00249   for (size_t i=0; i<this->vertices_.size (); ++i)
00250   {
00251     const pcl::PointXYZRGBNormal& expected_pt = this->vertices_ [i];
00252     const pcl::PointXYZRGBNormal& actual_pt   = half_edge_mesh.getVertexDataCloud () [i];
00253 
00254     EXPECT_FLOAT_EQ (expected_pt.x, actual_pt.x);
00255     EXPECT_FLOAT_EQ (expected_pt.y, actual_pt.y);
00256     EXPECT_FLOAT_EQ (expected_pt.z, actual_pt.z);
00257 
00258     EXPECT_FLOAT_EQ (expected_pt.normal_x, actual_pt.normal_x);
00259     EXPECT_FLOAT_EQ (expected_pt.normal_y, actual_pt.normal_y);
00260     EXPECT_FLOAT_EQ (expected_pt.normal_z, actual_pt.normal_z);
00261 
00262     EXPECT_EQ (expected_pt.r, actual_pt.r);
00263     EXPECT_EQ (expected_pt.g, actual_pt.g);
00264     EXPECT_EQ (expected_pt.b, actual_pt.b);
00265   }
00266 
00267   // Check the faces
00268   const std::vector <std::vector <uint32_t> > expected_faces =
00269       Mesh::IsManifold::value ? this->manifold_faces_ :
00270                                 this->non_manifold_faces_;
00271 
00272   ASSERT_EQ (expected_faces.size (), half_edge_mesh.sizeFaces ());
00273 
00274   std::vector <uint32_t> converted_face;
00275   for (size_t i=0; i<half_edge_mesh.sizeFaces (); ++i)
00276   {
00277     VAFC       circ     = half_edge_mesh.getVertexAroundFaceCirculator (FaceIndex (i));
00278     const VAFC circ_end = circ;
00279     converted_face.clear ();
00280     do
00281     {
00282       converted_face.push_back (static_cast <uint32_t> (circ.getTargetIndex ().get ()));
00283     } while (++circ != circ_end);
00284 
00285     EXPECT_TRUE (isCircularPermutation (expected_faces [i], converted_face)) << "Face number " << i;
00286   }
00287 }
00288 
00290 
00291 // This test should not compile (mesh has no vertex data).
00292 
00293 //TEST (TestFaceVertexMeshToHalfEdgeMesh, NoVertexData)
00294 //{
00295 //  typedef pcl::geometry::DefaultMeshTraits <>     MeshTraits;
00296 //  typedef pcl::geometry::PolygonMesh <MeshTraits> Mesh;
00297 
00298 //  Mesh half_edge_mesh;
00299 //  pcl::PolygonMesh face_vertex_mesh;
00300 
00301 //  pcl::geometry::toHalfEdgeMesh (face_vertex_mesh, half_edge_mesh);
00302 //}
00303 
00305 
00306 TYPED_TEST (TestMeshConversion, NonConvertibleCases)
00307 {
00308   typedef typename TestFixture::MeshTraits     Traits;
00309   typedef pcl::geometry::TriangleMesh <Traits> TriangleMesh;
00310   typedef pcl::geometry::QuadMesh     <Traits> QuadMesh;
00311   typedef pcl::geometry::PolygonMesh  <Traits> PolygonMesh;
00312 
00313   // Generate the mesh
00314   pcl::PolygonMesh face_vertex_mesh;
00315   pcl::toPCLPointCloud2 (this->vertices_, face_vertex_mesh.cloud);
00316   pcl::Vertices face;
00317   for (size_t i=0; i<this->non_manifold_faces_.size (); ++i)
00318   {
00319     face.vertices = this->non_manifold_faces_ [i];
00320     face_vertex_mesh.polygons.push_back (face);
00321   }
00322 
00323   // Convert
00324   TriangleMesh tm;
00325   QuadMesh     qm;
00326   PolygonMesh  pm;
00327 
00328   const int n_not_added_t = pcl::geometry::toHalfEdgeMesh (face_vertex_mesh, tm);
00329   const int n_not_added_q = pcl::geometry::toHalfEdgeMesh (face_vertex_mesh, qm);
00330   const int n_not_added_p = pcl::geometry::toHalfEdgeMesh (face_vertex_mesh, pm);
00331 
00332   if (Traits::IsManifold::value)
00333   {
00334     ASSERT_EQ (4, n_not_added_t);
00335     ASSERT_EQ (4, n_not_added_q);
00336     ASSERT_EQ (2, n_not_added_p);
00337   }
00338   else
00339   {
00340     ASSERT_EQ (3, n_not_added_t);
00341     ASSERT_EQ (3, n_not_added_q);
00342     ASSERT_EQ (0, n_not_added_p);
00343   }
00344 }
00345 
00347 
00348 int
00349 main (int argc, char** argv)
00350 {
00351   testing::InitGoogleTest (&argc, argv);
00352   return (RUN_ALL_TESTS ());
00353 }


pcl
Author(s): Open Perception
autogenerated on Wed Aug 26 2015 15:35:08