aabb_binary_tree.cpp
Go to the documentation of this file.
00001 /****************************************************************************
00002 * VCGLib                                                            o o     *
00003 * Visual and Computer Graphics Library                            o     o   *
00004 *                                                                _   O  _   *
00005 * Copyright(C) 2004-2012                                           \/)\/    *
00006 * Visual Computing Lab                                            /\/|      *
00007 * ISTI - Italian National Research Council                           |      *
00008 *                                                                    \      *
00009 * All rights reserved.                                                      *
00010 *                                                                           *
00011 * This program is free software; you can redistribute it and/or modify      *
00012 * it under the terms of the GNU General Public License as published by      *
00013 * the Free Software Foundation; either version 2 of the License, or         *
00014 * (at your option) any later version.                                       *
00015 *                                                                           *
00016 * This program is distributed in the hope that it will be useful,           *
00017 * but WITHOUT ANY WARRANTY; without even the implied warranty of            *
00018 * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the             *
00019 * GNU General Public License (http://www.gnu.org/licenses/gpl.txt)          *
00020 * for more details.                                                         *
00021 *                                                                           *
00022 ****************************************************************************/
00023 #include <stdio.h>
00024 
00025 #include<vcg/complex/complex.h>
00026 #include<vcg/simplex/face/distance.h>
00027 #include<vcg/simplex/face/component_ep.h>
00028 #include <vcg/complex/algorithms/create/platonic.h>
00029 #include <vcg/complex/algorithms/update/normal.h>
00030 #include <vcg/complex/algorithms/update/component_ep.h>
00031 #include <vcg/complex/algorithms/update/flag.h>
00032 #include <vcg/space/intersection3.h>
00033 #include <vcg/space/index/aabb_binary_tree/aabb_binary_tree.h>
00034 
00035 typedef float AScalarType;
00036 
00037 using namespace vcg;
00038 
00039 class AVertex;
00040 class AFace;
00041 
00042 struct MyUsedTypes : public vcg::UsedTypes<     vcg::Use<AVertex>               ::AsVertexType,
00043                                                                                         vcg::Use<AFace>                 ::AsFaceType>{};
00044 
00045 class AVertex     : public Vertex< MyUsedTypes, vertex::Normal3f, vertex::Coord3f,vertex::BitFlags >{};
00046 class AFace       : public Face<   MyUsedTypes, face::VertexRef, face::Normal3f, face::EdgePlane, face::BitFlags> {};
00047 class AMesh     : public vcg::tri::TriMesh< std::vector<AVertex>, std::vector<AFace> > { };
00048 
00049 typedef vcg::AABBBinaryTreeIndex<AFace, AScalarType, vcg::EmptyClass> AIndex;
00050 
00051 static AMesh gMesh;
00052 static AIndex gIndex;
00053 
00054 static void CreateMesh(void) {
00055         vcg::tri::Dodecahedron<AMesh>(gMesh);
00056 
00057         vcg::tri::UpdateFlags<AMesh>::Clear(gMesh);
00058         vcg::tri::UpdateNormal<AMesh>::PerVertexNormalized(gMesh);
00059         vcg::tri::UpdateComponentEP<AMesh>::Set(gMesh);
00060 }
00061 
00062 static void SetIndex(void) {
00063         gIndex.Set(gMesh.face.begin(), gMesh.face.end());
00064 }
00065 
00066 static void TestClosest(void) {
00067         vcg::face::PointDistanceEPFunctor<AIndex::ScalarType> getPtDist;
00068         const AIndex::CoordType queryPoint((AIndex::ScalarType)0, (AIndex::ScalarType)0, (AIndex::ScalarType)0);
00069         const AIndex::ScalarType maxDist = std::numeric_limits<AIndex::ScalarType>::max();
00070 
00071         AIndex::ObjPtr closestFace;
00072         AIndex::ScalarType closestDist;
00073         AIndex::CoordType closestPoint;
00074 
00075         vcg::EmptyClass a;
00076         closestFace = gIndex.GetClosest(getPtDist, a, queryPoint, maxDist, closestDist, closestPoint);
00077 
00078         printf("GetClosest Test:\n");
00079 
00080         if (closestFace != 0) {
00081                 printf("\tface     : 0x%p\n", closestFace);
00082                 printf("\tdistance : %f\n", closestDist);
00083                 printf("\tpoint    : [%f, %f, %f]\n", closestPoint[0], closestPoint[1], closestPoint[2]);
00084         }
00085         else {
00086                 printf("\tno object found (index is probably empty).\n");
00087         }
00088 }
00089 
00090 static void TestKClosest(void) {
00091         vcg::face::PointDistanceEPFunctor<AIndex::ScalarType> getPtDist;
00092         const unsigned int k = 10;
00093         const AIndex::CoordType queryPoint((AIndex::ScalarType)0, (AIndex::ScalarType)0, (AIndex::ScalarType)0);
00094         const AIndex::ScalarType maxDist = std::numeric_limits<AIndex::ScalarType>::max();
00095 
00096         std::vector<AIndex::ObjPtr> closestObjects;
00097         std::vector<AIndex::ScalarType> closestDistances;
00098         std::vector<AIndex::CoordType> closestPoints;
00099 
00100         vcg::EmptyClass a;
00101         unsigned int rk = gIndex.GetKClosest(getPtDist, a, k, queryPoint, maxDist, closestObjects, closestDistances, closestPoints);
00102 
00103         printf("GetKClosest Test:\n");
00104         printf("\tfound %d objects\n", rk);
00105 }
00106 
00107 static void TestRay(void) {
00108         const bool TEST_BACK_FACES = true;
00109 
00110         vcg::RayTriangleIntersectionFunctor<TEST_BACK_FACES> rayIntersector;
00111         const AIndex::ScalarType maxDist = std::numeric_limits<AIndex::ScalarType>::max();
00112         const AIndex::CoordType rayOrigin((AIndex::ScalarType)0, (AIndex::ScalarType)0, (AIndex::ScalarType)0);
00113         const AIndex::CoordType rayDirection((AIndex::ScalarType)1, (AIndex::ScalarType)0, (AIndex::ScalarType)0);
00114         const vcg::Ray3<AIndex::ScalarType, false> ray(rayOrigin, rayDirection);
00115 
00116         AIndex::ObjPtr isectFace;
00117         AIndex::ScalarType rayT;
00118         AIndex::CoordType isectPt;
00119 
00120         vcg::EmptyClass a;
00121         isectFace = gIndex.DoRay(rayIntersector, a , ray, maxDist, rayT);
00122 
00123         printf("DoRay Test:\n");
00124         if (isectFace != 0) {
00125                 printf("\tface  : 0x%p\n", isectFace);
00126                 printf("\tray t : %f\n", rayT);
00127         }
00128         else {
00129                 printf("\tno object found (index is probably empty).\n");
00130         }
00131 }
00132 
00133 int main (int /*argc*/, char ** /*argv*/) {
00134         CreateMesh();
00135 
00136         SetIndex();
00137 
00138         printf("Spatial Index Tests\n");
00139         printf("---\n");
00140         TestClosest();
00141         printf("---\n");
00142         TestKClosest();
00143         printf("---\n");
00144         TestRay();
00145         printf("---\n");
00146 
00147         return (0);
00148 }


shape_reconstruction
Author(s): Roberto Martín-Martín
autogenerated on Sat Jun 8 2019 18:28:51