test_mesh_indices.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 <string>
00042 #include <sstream>
00043 
00044 #include <gtest/gtest.h>
00045 
00046 #include <pcl/geometry/mesh_indices.h>
00047 
00049 
00050 typedef pcl::geometry::VertexIndex   VertexIndex;
00051 typedef pcl::geometry::HalfEdgeIndex HalfEdgeIndex;
00052 typedef pcl::geometry::EdgeIndex     EdgeIndex;
00053 typedef pcl::geometry::FaceIndex     FaceIndex;
00054 
00056 
00057 template <class MeshIndexT>
00058 class TestMeshIndicesTyped : public testing::Test
00059 {
00060   protected:
00061     typedef MeshIndexT MeshIndex;
00062 };
00063 
00064 typedef testing::Types <VertexIndex, HalfEdgeIndex, EdgeIndex, FaceIndex> MeshIndexTypes;
00065 
00066 TYPED_TEST_CASE (TestMeshIndicesTyped, MeshIndexTypes);
00067 
00069 
00070 TYPED_TEST (TestMeshIndicesTyped, General)
00071 {
00072   typedef typename TestFixture::MeshIndex MeshIndex;
00073   MeshIndex vi0, vi1 (-5), vi2 (0), vi3 (5), vi4 (5), vi5 (6);
00074 
00075   EXPECT_FALSE (vi0.isValid ());
00076   EXPECT_FALSE (vi1.isValid ());
00077   EXPECT_TRUE  (vi2.isValid ());
00078   EXPECT_TRUE  (vi3.isValid ());
00079   EXPECT_TRUE  (vi4.isValid ());
00080   vi2.invalidate ();
00081   EXPECT_FALSE (vi2.isValid ());
00082 
00083   EXPECT_LT (vi4, vi5);
00084   EXPECT_EQ (vi3, vi4);
00085 
00086   EXPECT_EQ (5, vi3.get ());
00087   vi3.set (2);
00088   EXPECT_EQ (2, vi3.get ());
00089 
00090   EXPECT_EQ (3, (++vi3).get ());
00091   EXPECT_EQ (2, (--vi3).get ());
00092   EXPECT_EQ (9, (vi3 += MeshIndex (7)).get ());
00093   EXPECT_EQ (2, (vi3 -= MeshIndex (7)).get ());
00094 }
00095 
00097 
00098 TEST (TestMeshIndices, Conversions)
00099 {
00100   HalfEdgeIndex he0, he1 (-9), he2 (4), he3 (5);
00101   EdgeIndex     e0 , e1  (-9), e2  (4), e3  (5);
00102 
00103   EXPECT_FALSE (pcl::geometry::toEdgeIndex (he0).isValid ());
00104   EXPECT_FALSE (pcl::geometry::toEdgeIndex (he1).isValid ());
00105   EXPECT_EQ (2, pcl::geometry::toEdgeIndex (he2).get ());
00106   EXPECT_EQ (2, pcl::geometry::toEdgeIndex (he3).get ());
00107 
00108   EXPECT_FALSE  (pcl::geometry::toHalfEdgeIndex (e0).isValid ());
00109   EXPECT_FALSE  (pcl::geometry::toHalfEdgeIndex (e1).isValid ());
00110   EXPECT_EQ (8 , pcl::geometry::toHalfEdgeIndex (e2).get ());
00111   EXPECT_EQ (10, pcl::geometry::toHalfEdgeIndex (e3).get ());
00112   EXPECT_EQ (9 , pcl::geometry::toHalfEdgeIndex (e2, false).get ());
00113   EXPECT_EQ (11, pcl::geometry::toHalfEdgeIndex (e3, false).get ());
00114 }
00115 
00117 
00118 TEST (TestMeshIndices, Streams)
00119 {
00120   // Output
00121   std::ostringstream oss;
00122   oss << "VertexIndex "   << VertexIndex   (1) << " "
00123       << "HalfEdgeIndex " << HalfEdgeIndex (2) << " "
00124       << "EdgeIndex "     << EdgeIndex     (3) << " "
00125       << "FaceIndex "     << FaceIndex     (4) << ".";
00126 
00127   EXPECT_EQ ("VertexIndex 1 HalfEdgeIndex 2 EdgeIndex 3 FaceIndex 4.", oss.str ());
00128 
00129   // Input
00130   VertexIndex   vi;
00131   HalfEdgeIndex hei;
00132   EdgeIndex     ei;
00133   FaceIndex     fi;
00134   std::istringstream iss ("1 2 3 4");
00135   EXPECT_TRUE (iss >> vi >> hei >> ei >> fi);
00136 
00137   EXPECT_EQ (1, vi.get  ());
00138   EXPECT_EQ (2, hei.get ());
00139   EXPECT_EQ (3, ei.get  ());
00140   EXPECT_EQ (4, fi.get  ());
00141 
00142   EXPECT_FALSE (iss.good ());
00143 }
00144 
00146 
00147 int
00148 main (int argc, char** argv)
00149 {
00150   testing::InitGoogleTest (&argc, argv);
00151   return (RUN_ALL_TESTS ());
00152 }


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