test_polygon_mesh.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 <vector>
00042 #include <typeinfo>
00043 
00044 #include <gtest/gtest.h>
00045 
00046 #include <pcl/geometry/polygon_mesh.h>
00047 
00048 #include "test_mesh_common_functions.h"
00049 
00051 
00052 typedef pcl::geometry::VertexIndex   VertexIndex;
00053 typedef pcl::geometry::HalfEdgeIndex HalfEdgeIndex;
00054 typedef pcl::geometry::EdgeIndex     EdgeIndex;
00055 typedef pcl::geometry::FaceIndex     FaceIndex;
00056 
00057 typedef std::vector <VertexIndex>   VertexIndices;
00058 typedef std::vector <HalfEdgeIndex> HalfEdgeIndices;
00059 typedef std::vector <FaceIndex>     FaceIndices;
00060 
00061 template <bool IsManifoldT>
00062 struct MeshTraits
00063 {
00064     typedef int                                          VertexData;
00065     typedef pcl::geometry::NoData                        HalfEdgeData;
00066     typedef pcl::geometry::NoData                        EdgeData;
00067     typedef pcl::geometry::NoData                        FaceData;
00068     typedef boost::integral_constant <bool, IsManifoldT> IsManifold;
00069 };
00070 
00071 typedef pcl::geometry::PolygonMesh <MeshTraits <true > > ManifoldPolygonMesh;
00072 typedef pcl::geometry::PolygonMesh <MeshTraits <false> > NonManifoldPolygonMesh;
00073 
00074 typedef testing::Types <ManifoldPolygonMesh, NonManifoldPolygonMesh> PolygonMeshTypes;
00075 
00076 template <class MeshT>
00077 class TestPolygonMesh : public testing::Test
00078 {
00079   protected:
00080     typedef MeshT Mesh;
00081 };
00082 
00083 TYPED_TEST_CASE (TestPolygonMesh, PolygonMeshTypes);
00084 
00086 
00087 TYPED_TEST (TestPolygonMesh, CorrectMeshTag)
00088 {
00089   typedef typename TestFixture::Mesh Mesh;
00090   typedef typename Mesh::MeshTag     MeshTag;
00091 
00092   ASSERT_EQ (typeid (pcl::geometry::PolygonMeshTag), typeid (MeshTag));
00093 }
00094 
00096 
00097 // NOTE: It is the responsibility of the user to ensure that all vertex indices are valid.
00098 
00099 //TYPED_TEST (TestPolygonMesh, OutOfRange)
00100 //{
00101 //  typedef typename TestFixture::Mesh Mesh;
00102 
00103 //  Mesh mesh;
00104 //  VertexIndices vi;
00105 //  for (unsigned int i=0; i<3; ++i)
00106 //  {
00107 //    vi.push_back (VertexIndex (i));
00108 //  }
00109 //  EXPECT_FALSE (mesh.addFace (vi).isValid ());
00110 
00111 //  mesh.addVertex (0);
00112 //  EXPECT_FALSE (mesh.addFace (vi).isValid ());
00113 
00114 //  mesh.addVertex (1);
00115 //  EXPECT_FALSE (mesh.addFace (vi).isValid ());
00116 
00117 //  mesh.addVertex (2);
00118 //  EXPECT_TRUE (mesh.addFace (vi).isValid ());
00119 //}
00120 
00122 
00123 TYPED_TEST (TestPolygonMesh, CorrectNumberOfVertices)
00124 {
00125   // Make sure that only quads can be added
00126   typedef typename TestFixture::Mesh Mesh;
00127 
00128   for (unsigned int n=1; n<=5; ++n)
00129   {
00130     Mesh mesh;
00131     VertexIndices vi;
00132     for (unsigned int i=0; i<n; ++i)
00133     {
00134       vi.push_back (VertexIndex (i));
00135       mesh.addVertex (i);
00136     }
00137 
00138     const FaceIndex index = mesh.addFace (vi);
00139     if (n>=3) EXPECT_TRUE  (index.isValid ()) << "Number of vertices in the face: " << n;
00140     else      EXPECT_FALSE (index.isValid ()) << "Number of vertices in the face: " << n;
00141   }
00142 }
00143 
00145 
00146 TYPED_TEST (TestPolygonMesh, ThreePolygons)
00147 {
00148   typedef typename TestFixture::Mesh Mesh;
00149 
00150   //   1 - 6   //
00151   //  / \   \  //
00152   // 2 - 0   5 //
00153   //  \   \ /  //
00154   //   3 - 4   //
00155   Mesh mesh;
00156   for (unsigned int i=0; i<7; ++i) mesh.addVertex (i);
00157 
00158   std::vector <VertexIndices> faces;
00159   VertexIndices vi;
00160   vi.push_back (VertexIndex (0));
00161   vi.push_back (VertexIndex (1));
00162   vi.push_back (VertexIndex (2));
00163   faces.push_back (vi);
00164   vi.clear ();
00165 
00166   vi.push_back (VertexIndex (0));
00167   vi.push_back (VertexIndex (2));
00168   vi.push_back (VertexIndex (3));
00169   vi.push_back (VertexIndex (4));
00170   faces.push_back (vi);
00171   vi.clear ();
00172 
00173   vi.push_back (VertexIndex (0));
00174   vi.push_back (VertexIndex (4));
00175   vi.push_back (VertexIndex (5));
00176   vi.push_back (VertexIndex (6));
00177   vi.push_back (VertexIndex (1));
00178   faces.push_back (vi);
00179   vi.clear ();
00180 
00181   for (unsigned int i=0; i<faces.size (); ++i)
00182   {
00183     ASSERT_TRUE (mesh.addFace (faces [i]).isValid ());
00184   }
00185 
00186   ASSERT_TRUE (hasFaces (mesh, faces));
00187 
00188   mesh.deleteFace (FaceIndex (1));
00189   mesh.cleanUp ();
00190 
00191   std::vector <std::vector <int> > expected;
00192   std::vector <int> tmp;
00193   tmp.push_back (0);
00194   tmp.push_back (1);
00195   tmp.push_back (2);
00196   expected.push_back (tmp);
00197   tmp.clear ();
00198 
00199   tmp.push_back (0);
00200   tmp.push_back (4);
00201   tmp.push_back (5);
00202   tmp.push_back (6);
00203   tmp.push_back (1);
00204   expected.push_back (tmp);
00205   tmp.clear ();
00206 
00207   ASSERT_TRUE (hasFaces (mesh, expected));
00208   std::vector <int> expected_boundary;
00209   expected_boundary.push_back (2);
00210   expected_boundary.push_back (1);
00211   expected_boundary.push_back (6);
00212   expected_boundary.push_back (5);
00213   expected_boundary.push_back (4);
00214   expected_boundary.push_back (0);
00215   ASSERT_EQ (expected_boundary, getBoundaryVertices (mesh, 0));
00216 }
00217 
00219 
00220 int
00221 main (int argc, char** argv)
00222 {
00223   testing::InitGoogleTest (&argc, argv);
00224   return (RUN_ALL_TESTS ());
00225 }


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