test_quad_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/quad_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::QuadMesh <MeshTraits <true > > ManifoldQuadMesh;
00072 typedef pcl::geometry::QuadMesh <MeshTraits <false> > NonManifoldQuadMesh;
00073 
00074 typedef testing::Types <ManifoldQuadMesh, NonManifoldQuadMesh> QuadMeshTypes;
00075 
00076 template <class MeshT>
00077 class TestQuadMesh : public testing::Test
00078 {
00079   protected:
00080     typedef MeshT Mesh;
00081 };
00082 
00083 TYPED_TEST_CASE (TestQuadMesh, QuadMeshTypes);
00084 
00086 
00087 TYPED_TEST (TestQuadMesh, CorrectMeshTag)
00088 {
00089   typedef typename TestFixture::Mesh Mesh;
00090   typedef typename Mesh::MeshTag     MeshTag;
00091 
00092   ASSERT_EQ (typeid (pcl::geometry::QuadMeshTag), typeid (MeshTag));
00093 }
00094 
00096 
00097 TYPED_TEST (TestQuadMesh, CorrectNumberOfVertices)
00098 {
00099   // Make sure that only quads can be added
00100   typedef typename TestFixture::Mesh Mesh;
00101 
00102   for (unsigned int n=1; n<=5; ++n)
00103   {
00104     Mesh mesh;
00105     VertexIndices vi;
00106     for (unsigned int i=0; i<n; ++i)
00107     {
00108       vi.push_back (VertexIndex (i));
00109       mesh.addVertex (i);
00110     }
00111 
00112     const FaceIndex index = mesh.addFace (vi);
00113     if (n==4) EXPECT_TRUE  (index.isValid ()) << "Number of vertices in the face: " << n;
00114     else      EXPECT_FALSE (index.isValid ()) << "Number of vertices in the face: " << n;
00115   }
00116 }
00117 
00119 
00120 TYPED_TEST (TestQuadMesh, OneQuad)
00121 {
00122   typedef typename TestFixture::Mesh Mesh;
00123 
00124   // 3 - 2 //
00125   // |   | //
00126   // 0 - 1 //
00127   Mesh mesh;
00128   VertexIndices vi;
00129   for (unsigned int i=0; i<4; ++i) vi.push_back (mesh.addVertex (i));
00130 
00131   const FaceIndex fi = mesh.addFace (vi);
00132   ASSERT_TRUE (fi.isValid ());
00133 
00134   const HalfEdgeIndex he_10 = mesh.getOutgoingHalfEdgeIndex (vi [1]);
00135   const HalfEdgeIndex he_21 = mesh.getOutgoingHalfEdgeIndex (vi [2]);
00136   const HalfEdgeIndex he_32 = mesh.getOutgoingHalfEdgeIndex (vi [3]);
00137   const HalfEdgeIndex he_03 = mesh.getOutgoingHalfEdgeIndex (vi [0]);
00138 
00139   const HalfEdgeIndex he_01 = mesh.getOppositeHalfEdgeIndex (he_10);
00140   const HalfEdgeIndex he_12 = mesh.getOppositeHalfEdgeIndex (he_21);
00141   const HalfEdgeIndex he_23 = mesh.getOppositeHalfEdgeIndex (he_32);
00142   const HalfEdgeIndex he_30 = mesh.getOppositeHalfEdgeIndex (he_03);
00143 
00144   EXPECT_TRUE (checkHalfEdge (mesh, he_10, vi [1], vi[0]));
00145   EXPECT_TRUE (checkHalfEdge (mesh, he_21, vi [2], vi[1]));
00146   EXPECT_TRUE (checkHalfEdge (mesh, he_32, vi [3], vi[2]));
00147   EXPECT_TRUE (checkHalfEdge (mesh, he_03, vi [0], vi[3]));
00148 
00149   EXPECT_TRUE (checkHalfEdge (mesh, he_01, vi [0], vi[1]));
00150   EXPECT_TRUE (checkHalfEdge (mesh, he_12, vi [1], vi[2]));
00151   EXPECT_TRUE (checkHalfEdge (mesh, he_23, vi [2], vi[3]));
00152   EXPECT_TRUE (checkHalfEdge (mesh, he_30, vi [3], vi[0]));
00153 
00154   EXPECT_EQ (he_01, mesh.getIncomingHalfEdgeIndex (vi [1]));
00155   EXPECT_EQ (he_12, mesh.getIncomingHalfEdgeIndex (vi [2]));
00156   EXPECT_EQ (he_23, mesh.getIncomingHalfEdgeIndex (vi [3]));
00157   EXPECT_EQ (he_30, mesh.getIncomingHalfEdgeIndex (vi [0]));
00158 
00159   EXPECT_EQ (he_12, mesh.getNextHalfEdgeIndex (he_01));
00160   EXPECT_EQ (he_23, mesh.getNextHalfEdgeIndex (he_12));
00161   EXPECT_EQ (he_30, mesh.getNextHalfEdgeIndex (he_23));
00162   EXPECT_EQ (he_01, mesh.getNextHalfEdgeIndex (he_30));
00163 
00164   EXPECT_EQ (he_30, mesh.getPrevHalfEdgeIndex (he_01));
00165   EXPECT_EQ (he_01, mesh.getPrevHalfEdgeIndex (he_12));
00166   EXPECT_EQ (he_12, mesh.getPrevHalfEdgeIndex (he_23));
00167   EXPECT_EQ (he_23, mesh.getPrevHalfEdgeIndex (he_30));
00168 
00169   EXPECT_EQ (he_03, mesh.getNextHalfEdgeIndex (he_10));
00170   EXPECT_EQ (he_32, mesh.getNextHalfEdgeIndex (he_03));
00171   EXPECT_EQ (he_21, mesh.getNextHalfEdgeIndex (he_32));
00172   EXPECT_EQ (he_10, mesh.getNextHalfEdgeIndex (he_21));
00173 
00174   EXPECT_EQ (he_21, mesh.getPrevHalfEdgeIndex (he_10));
00175   EXPECT_EQ (he_10, mesh.getPrevHalfEdgeIndex (he_03));
00176   EXPECT_EQ (he_03, mesh.getPrevHalfEdgeIndex (he_32));
00177   EXPECT_EQ (he_32, mesh.getPrevHalfEdgeIndex (he_21));
00178 
00179   EXPECT_EQ (fi, mesh.getFaceIndex (he_01));
00180   EXPECT_EQ (fi, mesh.getFaceIndex (he_12));
00181   EXPECT_EQ (fi, mesh.getFaceIndex (he_23));
00182   EXPECT_EQ (fi, mesh.getFaceIndex (he_30));
00183 
00184   EXPECT_FALSE (mesh.getOppositeFaceIndex (he_01).isValid ());
00185   EXPECT_FALSE (mesh.getOppositeFaceIndex (he_12).isValid ());
00186   EXPECT_FALSE (mesh.getOppositeFaceIndex (he_23).isValid ());
00187   EXPECT_FALSE (mesh.getOppositeFaceIndex (he_30).isValid ());
00188 
00189   EXPECT_FALSE (mesh.getFaceIndex (he_10).isValid ());
00190   EXPECT_FALSE (mesh.getFaceIndex (he_21).isValid ());
00191   EXPECT_FALSE (mesh.getFaceIndex (he_32).isValid ());
00192   EXPECT_FALSE (mesh.getFaceIndex (he_03).isValid ());
00193 
00194   EXPECT_EQ (fi, mesh.getOppositeFaceIndex (he_10));
00195   EXPECT_EQ (fi, mesh.getOppositeFaceIndex (he_21));
00196   EXPECT_EQ (fi, mesh.getOppositeFaceIndex (he_32));
00197   EXPECT_EQ (fi, mesh.getOppositeFaceIndex (he_03));
00198 
00199   EXPECT_EQ (he_30, mesh.getInnerHalfEdgeIndex (fi));
00200   EXPECT_EQ (he_03, mesh.getOuterHalfEdgeIndex (fi));
00201 
00202   EXPECT_FALSE (mesh.isBoundary (he_01));
00203   EXPECT_FALSE (mesh.isBoundary (he_12));
00204   EXPECT_FALSE (mesh.isBoundary (he_23));
00205   EXPECT_FALSE (mesh.isBoundary (he_30));
00206 
00207   EXPECT_TRUE (mesh.isBoundary (he_10));
00208   EXPECT_TRUE (mesh.isBoundary (he_21));
00209   EXPECT_TRUE (mesh.isBoundary (he_32));
00210   EXPECT_TRUE (mesh.isBoundary (he_03));
00211 
00212   EXPECT_TRUE (mesh.isBoundary (vi [0]));
00213   EXPECT_TRUE (mesh.isBoundary (vi [1]));
00214   EXPECT_TRUE (mesh.isBoundary (vi [2]));
00215   EXPECT_TRUE (mesh.isBoundary (vi [3]));
00216 
00217   EXPECT_TRUE (mesh.isBoundary (fi));
00218 }
00219 
00221 
00222 TYPED_TEST (TestQuadMesh, NineQuads)
00223 {
00224   typedef typename TestFixture::Mesh Mesh;
00225   const int int_max = std::numeric_limits <int>::max ();
00226 
00227   // Order
00228   //    -   -   -   //
00229   //  | 0 | 1 | 2 | //
00230   //    -   -   -   //
00231   //  | 3 | 4 | 5 | //
00232   //    -   -   -   //
00233   //  | 6 | 7 | 8 | //
00234   //    -   -   -   //
00235 
00236   // Add the configuration in different orders. Some of them create non-manifold states.
00237   std::vector <std::vector <int> > order_vec;
00238   std::vector <int> non_manifold; // When is the first non-manifold quad added?
00239   std::vector <int> order_tmp;
00240 
00241   // Configuration 0
00242   order_tmp.push_back (0);
00243   order_tmp.push_back (1);
00244   order_tmp.push_back (2);
00245   order_tmp.push_back (3);
00246   order_tmp.push_back (5);
00247   order_tmp.push_back (4);
00248   order_tmp.push_back (7);
00249   order_tmp.push_back (6);
00250   order_tmp.push_back (8);
00251   order_vec.push_back (order_tmp);
00252   non_manifold.push_back (int_max);
00253   order_tmp.clear ();
00254 
00255   // Configuration 1
00256   order_tmp.push_back (0);
00257   order_tmp.push_back (1);
00258   order_tmp.push_back (6);
00259   order_tmp.push_back (8);
00260   order_tmp.push_back (2);
00261   order_tmp.push_back (3);
00262   order_tmp.push_back (7);
00263   order_tmp.push_back (5);
00264   order_tmp.push_back (4);
00265   order_vec.push_back (order_tmp);
00266   non_manifold.push_back (int_max);
00267   order_tmp.clear ();
00268 
00269   // Configuration 2
00270   order_tmp.push_back (0);
00271   order_tmp.push_back (1);
00272   order_tmp.push_back (6);
00273   order_tmp.push_back (8);
00274   order_tmp.push_back (5);
00275   order_tmp.push_back (2);
00276   order_tmp.push_back (3);
00277   order_tmp.push_back (7);
00278   order_tmp.push_back (4);
00279   order_vec.push_back (order_tmp);
00280   non_manifold.push_back (4);
00281   order_tmp.clear ();
00282 
00283   // Configuration 3
00284   order_tmp.push_back (1);
00285   order_tmp.push_back (3);
00286   order_tmp.push_back (5);
00287   order_tmp.push_back (7);
00288   order_tmp.push_back (4);
00289   order_tmp.push_back (0);
00290   order_tmp.push_back (2);
00291   order_tmp.push_back (6);
00292   order_tmp.push_back (8);
00293   order_vec.push_back (order_tmp);
00294   non_manifold.push_back (1);
00295   order_tmp.clear ();
00296 
00297   // Configuration 4
00298   order_tmp.push_back (1);
00299   order_tmp.push_back (3);
00300   order_tmp.push_back (5);
00301   order_tmp.push_back (7);
00302   order_tmp.push_back (0);
00303   order_tmp.push_back (2);
00304   order_tmp.push_back (6);
00305   order_tmp.push_back (8);
00306   order_tmp.push_back (4);
00307   order_vec.push_back (order_tmp);
00308   non_manifold.push_back (1);
00309   order_tmp.clear ();
00310 
00311   // Configuration 5
00312   order_tmp.push_back (0);
00313   order_tmp.push_back (4);
00314   order_tmp.push_back (8);
00315   order_tmp.push_back (2);
00316   order_tmp.push_back (6);
00317   order_tmp.push_back (1);
00318   order_tmp.push_back (7);
00319   order_tmp.push_back (5);
00320   order_tmp.push_back (3);
00321   order_vec.push_back (order_tmp);
00322   non_manifold.push_back (1);
00323   order_tmp.clear ();
00324 
00325   // 00 - 01 - 02 - 03 //
00326   //  |    |    |    | //
00327   // 04 - 05 - 06 - 07 //
00328   //  |    |    |    | //
00329   // 08 - 09 - 10 - 11 //
00330   //  |    |    |    | //
00331   // 12 - 13 - 14 - 15 //
00332   typedef VertexIndex VI;
00333   std::vector <VertexIndices> faces;
00334   VertexIndices vi;
00335   vi.push_back (VI ( 0)); vi.push_back (VI ( 4)); vi.push_back (VI ( 5)); vi.push_back (VI ( 1)); faces.push_back (vi); vi.clear ();
00336   vi.push_back (VI ( 1)); vi.push_back (VI ( 5)); vi.push_back (VI ( 6)); vi.push_back (VI ( 2)); faces.push_back (vi); vi.clear ();
00337   vi.push_back (VI ( 2)); vi.push_back (VI ( 6)); vi.push_back (VI ( 7)); vi.push_back (VI ( 3)); faces.push_back (vi); vi.clear ();
00338   vi.push_back (VI ( 4)); vi.push_back (VI ( 8)); vi.push_back (VI ( 9)); vi.push_back (VI ( 5)); faces.push_back (vi); vi.clear ();
00339   vi.push_back (VI ( 5)); vi.push_back (VI ( 9)); vi.push_back (VI (10)); vi.push_back (VI ( 6)); faces.push_back (vi); vi.clear ();
00340   vi.push_back (VI ( 6)); vi.push_back (VI (10)); vi.push_back (VI (11)); vi.push_back (VI ( 7)); faces.push_back (vi); vi.clear ();
00341   vi.push_back (VI ( 8)); vi.push_back (VI (12)); vi.push_back (VI (13)); vi.push_back (VI ( 9)); faces.push_back (vi); vi.clear ();
00342   vi.push_back (VI ( 9)); vi.push_back (VI (13)); vi.push_back (VI (14)); vi.push_back (VI (10)); faces.push_back (vi); vi.clear ();
00343   vi.push_back (VI (10)); vi.push_back (VI (14)); vi.push_back (VI (15)); vi.push_back (VI (11)); faces.push_back (vi); vi.clear ();
00344 
00345   ASSERT_EQ (order_vec.size (), non_manifold.size ());
00346   ASSERT_EQ (9, faces.size ());
00347   for (unsigned int i=0; i<order_vec.size (); ++i)
00348   {
00349     std::stringstream ss;
00350     ss << "Configuration " << i;
00351     SCOPED_TRACE (ss.str ());
00352 
00353     const std::vector <int> order = order_vec [i];
00354 
00355     EXPECT_EQ (9, order.size ()); // No assert so the other cases can run as well
00356     if (9 != order.size ()) continue;
00357 
00358     Mesh mesh;
00359     for (unsigned int j=0; j<16; ++j) mesh.addVertex (j);
00360 
00361     std::vector <VertexIndices> ordered_faces;
00362 
00363     for (unsigned int j=0; j<faces.size (); ++j)
00364     {
00365       ordered_faces.push_back (faces [order [j]]);
00366     }
00367     bool check_has_faces = true;
00368     for (unsigned int j=0; j<faces.size (); ++j)
00369     {
00370       const FaceIndex index = mesh.addFace (ordered_faces [j]);
00371 
00372       if (j < non_manifold [i] || !Mesh::IsManifold::value)
00373       {
00374         EXPECT_TRUE (index.isValid ());
00375       }
00376       else
00377       {
00378         EXPECT_FALSE (index.isValid ());
00379         check_has_faces = false;
00380         break;
00381       }
00382     }
00383     if (check_has_faces)
00384     {
00385       EXPECT_TRUE (hasFaces (mesh, ordered_faces));
00386     }
00387   }
00388 }
00389 
00391 
00392 int
00393 main (int argc, char** argv)
00394 {
00395   testing::InitGoogleTest (&argc, argv);
00396   return (RUN_ALL_TESTS ());
00397 }


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