00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037
00038
00039
00040
00041 #include <gtest/gtest.h>
00042
00043 #include <pcl/geometry/triangle_mesh.h>
00044 #include "test_mesh_common_functions.h"
00045
00047
00048 class TestMeshCirculators : public ::testing::Test
00049 {
00050 protected:
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 struct MeshTraits
00062 {
00063 typedef pcl::geometry::NoData VertexData;
00064 typedef pcl::geometry::NoData HalfEdgeData;
00065 typedef pcl::geometry::NoData EdgeData;
00066 typedef pcl::geometry::NoData FaceData;
00067 typedef boost::true_type IsManifold;
00068 };
00069
00070 typedef pcl::geometry::TriangleMesh <MeshTraits> Mesh;
00071 typedef Mesh::VertexAroundVertexCirculator VAVC;
00072 typedef Mesh::OutgoingHalfEdgeAroundVertexCirculator OHEAVC;
00073 typedef Mesh::IncomingHalfEdgeAroundVertexCirculator IHEAVC;
00074 typedef Mesh::FaceAroundVertexCirculator FAVC;
00075 typedef Mesh::VertexAroundFaceCirculator VAFC;
00076 typedef Mesh::InnerHalfEdgeAroundFaceCirculator IHEAFC;
00077 typedef Mesh::OuterHalfEdgeAroundFaceCirculator OHEAFC;
00078 typedef Mesh::FaceAroundFaceCirculator FAFC;
00079
00080
00081
00082
00083
00084
00085 void
00086 SetUp ()
00087 {
00088 for (int i=0; i<7; ++i) mesh_.addVertex ();
00089
00090 VertexIndices vi;
00091 typedef VertexIndex VI;
00092 vi.push_back (VI (0)); vi.push_back (VI (1)); vi.push_back (VI (2)); faces_.push_back (vi); vi.clear ();
00093 vi.push_back (VI (0)); vi.push_back (VI (2)); vi.push_back (VI (3)); faces_.push_back (vi); vi.clear ();
00094 vi.push_back (VI (0)); vi.push_back (VI (3)); vi.push_back (VI (4)); faces_.push_back (vi); vi.clear ();
00095 vi.push_back (VI (0)); vi.push_back (VI (4)); vi.push_back (VI (5)); faces_.push_back (vi); vi.clear ();
00096 vi.push_back (VI (0)); vi.push_back (VI (5)); vi.push_back (VI (6)); faces_.push_back (vi); vi.clear ();
00097 vi.push_back (VI (0)); vi.push_back (VI (6)); vi.push_back (VI (1)); faces_.push_back (vi); vi.clear ();
00098 for (int i=0; i<faces_.size (); ++i)
00099 {
00100 ASSERT_TRUE (mesh_.addFace (faces_ [i]).isValid ()) << "Face number " << i;
00101 }
00102 for (int i=1; i<=6; ++i)
00103 {
00104 expected_123456_.push_back (VertexIndex (i));
00105 expected_654321_.push_back (VertexIndex (7-i));
00106 }
00107 }
00108
00109 Mesh mesh_;
00110 std::vector <VertexIndices> faces_;
00111
00112
00113 VertexIndices expected_123456_;
00114 VertexIndices expected_654321_;
00115 public:
00116 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00117 };
00118
00120
00121 TEST_F (TestMeshCirculators, IsValid)
00122 {
00123 VAVC circ_0; EXPECT_FALSE (circ_0.isValid ());
00124 OHEAVC circ_1; EXPECT_FALSE (circ_1.isValid ());
00125 IHEAVC circ_2; EXPECT_FALSE (circ_2.isValid ());
00126 FAVC circ_3; EXPECT_FALSE (circ_3.isValid ());
00127 VAFC circ_4; EXPECT_FALSE (circ_4.isValid ());
00128 IHEAFC circ_5; EXPECT_FALSE (circ_5.isValid ());
00129 OHEAFC circ_6; EXPECT_FALSE (circ_6.isValid ());
00130 FAFC circ_7; EXPECT_FALSE (circ_7.isValid ());
00131 }
00132
00134
00135 TEST_F (TestMeshCirculators, VertexAroundVertexIncrement)
00136 {
00137 VertexIndices actual;
00138 VAVC circ = mesh_.getVertexAroundVertexCirculator (VertexIndex (0));
00139 const VAVC circ_end = circ;
00140 ASSERT_TRUE (circ.isValid ());
00141 ASSERT_EQ (circ, circ_end);
00142 int counter = 0;
00143 do
00144 {
00145 ASSERT_LE (++counter, 6);
00146 actual.push_back (circ.getTargetIndex ());
00147 } while (++circ != circ_end);
00148 EXPECT_TRUE (isCircularPermutation (expected_654321_, actual));
00149 }
00150
00152
00153 TEST_F (TestMeshCirculators, VertexAroundVertexDecrement)
00154 {
00155 VertexIndices actual;
00156 VAVC circ = mesh_.getVertexAroundVertexCirculator (VertexIndex (0));
00157 const VAVC circ_end = circ;
00158 ASSERT_TRUE (circ.isValid ());
00159 ASSERT_EQ (circ, circ_end);
00160 int counter = 0;
00161 do
00162 {
00163 ASSERT_LE (++counter, 6);
00164 actual.push_back (circ.getTargetIndex ());
00165 } while (--circ != circ_end);
00166 EXPECT_TRUE (isCircularPermutation (expected_123456_, actual));
00167 }
00168
00170
00171 TEST_F (TestMeshCirculators, OutgoingHalfEdgeAroundVertexIncrement)
00172 {
00173 VertexIndices actual;
00174 OHEAVC circ = mesh_.getOutgoingHalfEdgeAroundVertexCirculator (VertexIndex (0));
00175 const OHEAVC circ_end = circ;
00176 ASSERT_TRUE (circ.isValid ());
00177 ASSERT_EQ (circ, circ_end);
00178 int counter = 0;
00179 do
00180 {
00181 ASSERT_LE (++counter, 6);
00182 const HalfEdgeIndex he = circ.getTargetIndex ();
00183 EXPECT_EQ (VertexIndex (0), mesh_.getOriginatingVertexIndex (he));
00184 actual.push_back (mesh_.getTerminatingVertexIndex (he));
00185 } while (++circ != circ_end);
00186 EXPECT_TRUE (isCircularPermutation (expected_654321_, actual));
00187 }
00188
00190
00191 TEST_F (TestMeshCirculators, OutgoingHalfEdgeAroundVertexDecrement)
00192 {
00193 VertexIndices actual;
00194 OHEAVC circ = mesh_.getOutgoingHalfEdgeAroundVertexCirculator (VertexIndex (0));
00195 const OHEAVC circ_end = circ;
00196 ASSERT_TRUE (circ.isValid ());
00197 ASSERT_EQ (circ, circ_end);
00198 int counter = 0;
00199 do
00200 {
00201 ASSERT_LE (++counter, 6);
00202 const HalfEdgeIndex he = circ.getTargetIndex ();
00203 EXPECT_EQ (VertexIndex (0), mesh_.getOriginatingVertexIndex (he));
00204 actual.push_back (mesh_.getTerminatingVertexIndex (he));
00205 } while (--circ != circ_end);
00206 EXPECT_TRUE (isCircularPermutation (expected_123456_, actual));
00207 }
00208
00210
00211 TEST_F (TestMeshCirculators, IncomingHalfEdgeAroundVertexIncrement)
00212 {
00213 VertexIndices actual;
00214 IHEAVC circ = mesh_.getIncomingHalfEdgeAroundVertexCirculator (VertexIndex (0));
00215 const IHEAVC circ_end = circ;
00216 ASSERT_TRUE (circ.isValid ());
00217 ASSERT_EQ (circ, circ_end);
00218 int counter = 0;
00219 do
00220 {
00221 ASSERT_LE (++counter, 6);
00222 const HalfEdgeIndex he = circ.getTargetIndex ();
00223 EXPECT_EQ (VertexIndex (0), mesh_.getTerminatingVertexIndex (he));
00224 actual.push_back (mesh_.getOriginatingVertexIndex (he));
00225 } while (++circ != circ_end);
00226 EXPECT_TRUE (isCircularPermutation (expected_654321_, actual));
00227 }
00228
00230
00231 TEST_F (TestMeshCirculators, IncomingHalfEdgeAroundVertexDecrement)
00232 {
00233 VertexIndices actual;
00234 IHEAVC circ = mesh_.getIncomingHalfEdgeAroundVertexCirculator (VertexIndex (0));
00235 const IHEAVC circ_end = circ;
00236 ASSERT_TRUE (circ.isValid ());
00237 ASSERT_EQ (circ, circ_end);
00238 int counter = 0;
00239 do
00240 {
00241 ASSERT_LE (++counter, 6);
00242 const HalfEdgeIndex he = circ.getTargetIndex ();
00243 EXPECT_EQ (VertexIndex (0), mesh_.getTerminatingVertexIndex (he));
00244 actual.push_back (mesh_.getOriginatingVertexIndex (he));
00245 } while (--circ != circ_end);
00246 EXPECT_TRUE (isCircularPermutation (expected_123456_, actual));
00247 }
00248
00250
00251 TEST_F (TestMeshCirculators, FaceAroundVertexIncrement)
00252 {
00253 std::vector <VertexIndices> actual;
00254 FAVC circ_fav = mesh_.getFaceAroundVertexCirculator (VertexIndex (0));
00255 const FAVC circ_fav_end = circ_fav;
00256 ASSERT_TRUE (circ_fav.isValid ());
00257 ASSERT_EQ (circ_fav, circ_fav_end);
00258 int counter_v = 0;
00259 do
00260 {
00261 ASSERT_LE (++counter_v, 6);
00262 VAFC circ_vaf = mesh_.getVertexAroundFaceCirculator (circ_fav.getTargetIndex ());
00263 const VAFC circ_vaf_end = circ_vaf;
00264 ASSERT_TRUE (circ_vaf.isValid ());
00265 ASSERT_EQ (circ_vaf, circ_vaf_end);
00266 VertexIndices vi;
00267 int counter_f = 0;
00268 do
00269 {
00270 ASSERT_LE (++counter_f, 3);
00271 vi.push_back (circ_vaf.getTargetIndex ());
00272 } while (++circ_vaf != circ_vaf_end);
00273 actual.push_back (vi);
00274 } while (++circ_fav != circ_fav_end);
00275 EXPECT_TRUE (isCircularPermutationVec (std::vector <VertexIndices> (faces_.rbegin (), faces_.rend ()), actual));
00276 }
00277
00279
00280 TEST_F (TestMeshCirculators, FaceAroundVertexDecrement)
00281 {
00282 std::vector <VertexIndices> actual;
00283 FAVC circ_fav = mesh_.getFaceAroundVertexCirculator (VertexIndex (0));
00284 const FAVC circ_fav_end = circ_fav;
00285 ASSERT_TRUE (circ_fav.isValid ());
00286 ASSERT_EQ (circ_fav, circ_fav_end);
00287 int counter_v = 0;
00288 do
00289 {
00290 ASSERT_LE (++counter_v, 6);
00291 VAFC circ_vaf = mesh_.getVertexAroundFaceCirculator (circ_fav.getTargetIndex ());
00292 const VAFC circ_vaf_end = circ_vaf;
00293 ASSERT_TRUE (circ_vaf.isValid ());
00294 ASSERT_EQ (circ_vaf, circ_vaf_end);
00295 VertexIndices vi;
00296 int counter_f = 0;
00297 do
00298 {
00299 ASSERT_LE (++counter_f, 3);
00300 vi.push_back (circ_vaf.getTargetIndex ());
00301 } while (++circ_vaf != circ_vaf_end);
00302 actual.push_back (vi);
00303 } while (--circ_fav != circ_fav_end);
00304 EXPECT_TRUE (isCircularPermutationVec (faces_, actual));
00305 }
00306
00308
00309 TEST_F (TestMeshCirculators, VertexAroundFaceIncrement)
00310 {
00311 VertexIndices actual;
00312 for (unsigned int i=0; i<mesh_.sizeFaces (); ++i)
00313 {
00314 VAFC circ = mesh_.getVertexAroundFaceCirculator (FaceIndex (i));
00315 const VAFC circ_end = circ;
00316 ASSERT_TRUE (circ.isValid ());
00317 ASSERT_EQ (circ, circ_end);
00318 actual.clear ();
00319 int counter = 0;
00320 do
00321 {
00322 ASSERT_LE (++counter, 3);
00323 actual.push_back (circ.getTargetIndex ());
00324 } while (++circ != circ_end);
00325 EXPECT_TRUE (isCircularPermutation (faces_ [i], actual)) << "Face number " << i;
00326 }
00327 }
00328
00330
00331 TEST_F (TestMeshCirculators, VertexAroundFaceDecrement)
00332 {
00333 VertexIndices actual;
00334 for (unsigned int i=0; i<mesh_.sizeFaces (); ++i)
00335 {
00336 VAFC circ = mesh_.getVertexAroundFaceCirculator (FaceIndex (i));
00337 const VAFC circ_end = circ;
00338 ASSERT_TRUE (circ.isValid ());
00339 ASSERT_EQ (circ, circ_end);
00340 actual.clear ();
00341 int counter = 0;
00342 do
00343 {
00344 ASSERT_LE (++counter, 3);
00345 actual.push_back (circ.getTargetIndex ());
00346 } while (--circ != circ_end);
00347 EXPECT_TRUE (isCircularPermutation (VertexIndices (faces_ [i].rbegin (), faces_ [i].rend ()), actual)) << "Face number " << i;
00348 }
00349 }
00350
00352
00353 TEST_F (TestMeshCirculators, InnerHalfEdgeAroundFaceForAllFacesIncrement)
00354 {
00355 VertexIndices actual;
00356 for (unsigned int i=0; i<mesh_.sizeFaces (); ++i)
00357 {
00358 IHEAFC circ = mesh_.getInnerHalfEdgeAroundFaceCirculator (FaceIndex (i));
00359 const IHEAFC circ_end = circ;
00360 ASSERT_TRUE (circ.isValid ());
00361 ASSERT_EQ (circ, circ_end);
00362 actual.clear ();
00363 int counter = 0;
00364 do
00365 {
00366 ASSERT_LE (++counter, 3);
00367 EXPECT_FALSE (mesh_.isBoundary (circ.getTargetIndex ()));
00368 actual.push_back (mesh_.getTerminatingVertexIndex (circ.getTargetIndex ()));
00369 } while (++circ != circ_end);
00370 EXPECT_TRUE (isCircularPermutation (faces_ [i], actual)) << "Face number " << i;
00371 }
00372 }
00373
00375
00376 TEST_F (TestMeshCirculators, InnerHalfEdgeAroundFaceForAllFacesDecrement)
00377 {
00378 VertexIndices actual;
00379 for (unsigned int i=0; i<mesh_.sizeFaces (); ++i)
00380 {
00381 IHEAFC circ = mesh_.getInnerHalfEdgeAroundFaceCirculator (FaceIndex (i));
00382 const IHEAFC circ_end = circ;
00383 ASSERT_TRUE (circ.isValid ());
00384 ASSERT_EQ (circ, circ_end);
00385 actual.clear ();
00386 int counter = 0;
00387 do
00388 {
00389 ASSERT_LE (++counter, 3);
00390 EXPECT_FALSE (mesh_.isBoundary (circ.getTargetIndex ()));
00391 actual.push_back (mesh_.getTerminatingVertexIndex (circ.getTargetIndex ()));
00392 } while (--circ != circ_end);
00393 EXPECT_TRUE (isCircularPermutation (VertexIndices (faces_ [i].rbegin (), faces_ [i].rend ()), actual)) << "Face number " << i;
00394 }
00395 }
00396
00398
00399 TEST_F (TestMeshCirculators, InnerHalfEdgeAroundFaceForBoundaryIncrement)
00400 {
00401 VertexIndices actual;
00402 IHEAFC circ = mesh_.getInnerHalfEdgeAroundFaceCirculator (mesh_.getOutgoingHalfEdgeIndex (VertexIndex (1)));
00403 const IHEAFC circ_end = circ;
00404 ASSERT_TRUE (circ.isValid ());
00405 ASSERT_EQ (circ, circ_end);
00406 int counter = 0;
00407 do
00408 {
00409 ASSERT_LE (++counter, 6);
00410 EXPECT_TRUE (mesh_.isBoundary (circ.getTargetIndex ()));
00411 actual.push_back (mesh_.getTerminatingVertexIndex (circ.getTargetIndex ()));
00412 } while (++circ != circ_end);
00413 EXPECT_TRUE (isCircularPermutation (expected_654321_, actual));
00414 }
00415
00417
00418 TEST_F (TestMeshCirculators, InnerHalfEdgeAroundFaceForBoundaryDecrement)
00419 {
00420 VertexIndices actual;
00421 IHEAFC circ = mesh_.getInnerHalfEdgeAroundFaceCirculator (mesh_.getOutgoingHalfEdgeIndex (VertexIndex (1)));
00422 const IHEAFC circ_end = circ;
00423 ASSERT_TRUE (circ.isValid ());
00424 ASSERT_EQ (circ, circ_end);
00425 int counter = 0;
00426 do
00427 {
00428 ASSERT_LE (++counter, 6);
00429 EXPECT_TRUE (mesh_.isBoundary (circ.getTargetIndex ()));
00430 actual.push_back (mesh_.getTerminatingVertexIndex (circ.getTargetIndex ()));
00431 } while (--circ != circ_end);
00432 EXPECT_TRUE (isCircularPermutation (expected_123456_, actual));
00433 }
00434
00436
00437 TEST_F (TestMeshCirculators, OuterHalfEdgeAroundFaceIncrement)
00438 {
00439 VertexIndices actual;
00440 for (unsigned int i=0; i<mesh_.sizeFaces (); ++i)
00441 {
00442 OHEAFC circ = mesh_.getOuterHalfEdgeAroundFaceCirculator (FaceIndex (i));
00443 const OHEAFC circ_end = circ;
00444 ASSERT_TRUE (circ.isValid ());
00445 ASSERT_EQ (circ, circ_end);
00446 int num_boundary (0), num_not_boundary (0);
00447 actual.clear ();
00448 int counter = 0;
00449 do
00450 {
00451 ASSERT_LE (++counter, 3);
00452 if (mesh_.isBoundary (circ.getTargetIndex ())) num_boundary += 1;
00453 else num_not_boundary += 1;
00454 actual.push_back (mesh_.getTerminatingVertexIndex (circ.getTargetIndex ()));
00455 } while (++circ != circ_end);
00456 EXPECT_EQ (1, num_boundary) << "Face number " << i;
00457 EXPECT_EQ (2, num_not_boundary) << "Face number " << i;
00458 EXPECT_TRUE (isCircularPermutation (faces_ [i], actual)) << "Face number " << i;
00459 }
00460 }
00461
00463
00464 TEST_F (TestMeshCirculators, OuterHalfEdgeAroundFaceDecrement)
00465 {
00466 VertexIndices actual;
00467 for (unsigned int i=0; i<mesh_.sizeFaces (); ++i)
00468 {
00469 OHEAFC circ = mesh_.getOuterHalfEdgeAroundFaceCirculator (FaceIndex (i));
00470 const OHEAFC circ_end = circ;
00471 ASSERT_TRUE (circ.isValid ());
00472 ASSERT_EQ (circ, circ_end);
00473 int num_boundary (0), num_not_boundary (0);
00474 actual.clear ();
00475 int counter = 0;
00476 do
00477 {
00478 ASSERT_LE (++counter, 3);
00479 if (mesh_.isBoundary (circ.getTargetIndex ())) num_boundary += 1;
00480 else num_not_boundary += 1;
00481 actual.push_back (mesh_.getTerminatingVertexIndex (circ.getTargetIndex ()));
00482 } while (--circ != circ_end);
00483 EXPECT_EQ (1, num_boundary) << "Face number " << i;
00484 EXPECT_EQ (2, num_not_boundary) << "Face number " << i;
00485 EXPECT_TRUE (isCircularPermutation (VertexIndices (faces_ [i].rbegin (), faces_ [i].rend ()), actual)) << "Face number " << i;
00486 }
00487 }
00488
00490
00491 TEST_F (TestMeshCirculators, FaceAroundFaceIncrement)
00492 {
00493 FaceIndices expected, actual;
00494 const int n = static_cast<int> (mesh_.sizeFaces ());
00495 for (unsigned int i = 0; i < mesh_.sizeFaces (); ++i)
00496 {
00497 expected.clear ();
00498 expected.push_back (FaceIndex (i==(n-1) ? 0 : (i+1)));
00499 expected.push_back (FaceIndex (i== 0 ? (n-1) : (i-1)));
00500 expected.push_back (FaceIndex ());
00501
00502 FAFC circ = mesh_.getFaceAroundFaceCirculator (FaceIndex (i));
00503 const FAFC circ_end = circ;
00504 ASSERT_TRUE (circ.isValid ());
00505 ASSERT_EQ (circ, circ_end);
00506 actual.clear ();
00507 int counter = 0;
00508 do
00509 {
00510 ASSERT_LE (++counter, 3);
00511 actual.push_back (circ.getTargetIndex ());
00512 } while (++circ != circ_end);
00513 EXPECT_TRUE (isCircularPermutation (expected, actual)) << "Face number " << i;
00514 }
00515 }
00516
00518
00519 TEST_F (TestMeshCirculators, FaceAroundFaceDecrement)
00520 {
00521 FaceIndices expected, actual;
00522 const int n = static_cast<int> (mesh_.sizeFaces ());
00523 for (unsigned int i = 0; i < mesh_.sizeFaces (); ++i)
00524 {
00525 expected.clear ();
00526 expected.push_back (FaceIndex (i== 0 ? (n-1) : (i-1)));
00527 expected.push_back (FaceIndex (i==(n-1) ? 0 : (i+1)));
00528 expected.push_back (FaceIndex ());
00529
00530 FAFC circ = mesh_.getFaceAroundFaceCirculator (FaceIndex (i));
00531 const FAFC circ_end = circ;
00532 ASSERT_TRUE (circ.isValid ());
00533 ASSERT_EQ (circ, circ_end);
00534 actual.clear ();
00535 int counter = 0;
00536 do
00537 {
00538 ASSERT_LE (++counter, 3);
00539 actual.push_back (circ.getTargetIndex ());
00540 } while (--circ != circ_end);
00541 EXPECT_TRUE (isCircularPermutation (expected, actual)) << "Face number " << i;
00542 }
00543 }
00544
00546
00547 int
00548 main (int argc, char** argv)
00549 {
00550 testing::InitGoogleTest (&argc, argv);
00551 return (RUN_ALL_TESTS ());
00552 }