aabb_binary_tree.h
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                                                \/)\/    *
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 
00024 /****************************************************************************
00025 History
00026 
00027 $Log: not supported by cvs2svn $
00028 Revision 1.5  2005/09/29 22:18:16  m_di_benedetto
00029 Added frustum culling methods, renamed some parameters.
00030 
00031 Revision 1.4  2005/09/28 21:23:03  m_di_benedetto
00032 Added Import() to box and barycenter functors
00033 to handle tree and objects with different ScalarType.
00034 
00035 Revision 1.3  2005/09/28 20:10:41  m_di_benedetto
00036 First Commit.
00037 
00038 
00039 ****************************************************************************/
00040 
00041 #ifndef __VCGLIB_AABBBINARYTREEINDEX_H
00042 #define __VCGLIB_AABBBINARYTREEINDEX_H
00043 
00044 // vcg headers
00045 #include <vcg/space/index/base.h>
00046 #include <vcg/space/index/aabb_binary_tree/base.h>
00047 #include <vcg/space/index/aabb_binary_tree/closest.h>
00048 #include <vcg/space/index/aabb_binary_tree/frustum_cull.h>
00049 #include <vcg/space/index/aabb_binary_tree/kclosest.h>
00050 #include <vcg/space/index/aabb_binary_tree/ray.h>
00051 #include <wrap/utils.h>
00052 
00053 /***************************************************************************/
00054 
00055 namespace vcg {
00056 
00057 template <class OBJTYPE, class SCALARTYPE, class NODEAUXDATA = EmptyClass>
00058 class AABBBinaryTreeIndex : public SpatialIndex<OBJTYPE, SCALARTYPE> {
00059 public:
00060         typedef AABBBinaryTreeIndex<OBJTYPE, SCALARTYPE, NODEAUXDATA> ClassType;
00061         typedef OBJTYPE ObjType;
00062         typedef SCALARTYPE ScalarType;
00063         typedef NODEAUXDATA NodeAuxData;
00064         typedef ObjType * ObjPtr;
00065         typedef Point3<ScalarType> CoordType;
00066         typedef AABBBinaryTree<ObjType, ScalarType, NodeAuxData> TreeType;
00067 
00068         inline TreeType & Tree(void) {
00069                 return (this->tree);
00070         }
00071 
00072         inline const TreeType & Tree(void) const {
00073                 return (this->tree);
00074         }
00075 
00076         bool Empty()
00077         {
00078                 return (this->tree.pRoot == 0);
00079         }
00080 
00081         void Clear(void)
00082         {
00083                 this->tree.Clear();
00084         }
00085 
00086         template <class OBJITER>
00087         inline void Set(const OBJITER & _oBegin, const OBJITER & _oEnd) {
00088                 GetPointerFunctor getPtr;
00089                 GetBox3Functor getBox;
00090                 GetBarycenter3Functor getBarycenter;
00091                 //const unsigned int divs = 100;
00092                 //const unsigned int size = (unsigned int)(std::distance(_oBegin, _oEnd));
00093                 //const unsigned int maxObjectsPerLeaf = (size < divs) ? (size) : ((unsigned int)((float)(std::distance(_oBegin, _oEnd)) / (float)divs));
00094                 const unsigned int maxObjectsPerLeaf = 10;
00095                 const ScalarType leafBoxMaxVolume = ((ScalarType)0);
00096                 const bool useVariance = true;
00097 
00098                 (void)(this->tree.Set(_oBegin, _oEnd, getPtr, getBox, getBarycenter, maxObjectsPerLeaf, leafBoxMaxVolume, useVariance));
00099         }
00100 
00101         template <class OBJITERATOR, class OBJITERATORPTRFUNCT, class OBJBOXFUNCT, class OBJBARYCENTERFUNCT>
00102         inline bool Set(const OBJITERATOR & _oBegin, const OBJITERATOR & _oEnd, OBJITERATORPTRFUNCT & _objPtr, OBJBOXFUNCT & _objBox, OBJBARYCENTERFUNCT & _objBarycenter, const unsigned int _maxElemsPerLeaf = 1, const ScalarType & _leafBoxMaxVolume = ((ScalarType)0), const bool _useVariance = true) {
00103                 return (this->tree.Set(_oBegin, _oEnd, _objPtr, _objBox, _objBarycenter, _maxElemsPerLeaf, _leafBoxMaxVolume, _useVariance));
00104         }
00105 
00106         template <class OBJPOINTDISTFUNCTOR, class OBJMARKER>
00107         inline ObjPtr GetClosest(
00108                 OBJPOINTDISTFUNCTOR & _getPointDistance, OBJMARKER & _marker, 
00109                 const typename OBJPOINTDISTFUNCTOR::QueryType & _p, const ScalarType & _maxDist,
00110                 ScalarType & _minDist, CoordType & _closestPt) {
00111                 (void)_marker;
00112                 return (AABBBinaryTreeClosest<TreeType>::Closest(this->tree, _getPointDistance, _p, _maxDist, _minDist, _closestPt));
00113         }
00114 
00115         template <class OBJPOINTDISTFUNCTOR, class OBJMARKER, class OBJPTRCONTAINER, class DISTCONTAINER, class POINTCONTAINER>
00116         inline unsigned int GetKClosest(
00117                 OBJPOINTDISTFUNCTOR & _getPointDistance, OBJMARKER & _marker, const unsigned int _k, const CoordType & _p, const ScalarType & _maxDist,
00118                 OBJPTRCONTAINER & _objectPtrs, DISTCONTAINER & _distances, POINTCONTAINER & _points) {
00119                 (void)_marker;
00120                 return (AABBBinaryTreeKClosest<TreeType>::KClosest(this->tree, _getPointDistance, _k, _p, _maxDist, _objectPtrs, _distances, _points));
00121         }
00122 
00123         template <class OBJRAYISECTFUNCTOR, class OBJMARKER>
00124         inline ObjPtr DoRay(OBJRAYISECTFUNCTOR & _rayIntersector, OBJMARKER & _marker, const Ray3<ScalarType> & _ray, const ScalarType & _maxDist, ScalarType & _t) {
00125                 (void)_marker;
00126                 return (AABBBinaryTreeRay<TreeType>::Ray(this->tree, _rayIntersector, _ray, _maxDist, _t));
00127         }
00128 
00129         inline void InitializeFrustumCull(void) {
00130                 (void)(AABBBinaryTreeFrustumCull<TreeType>::Initialize(this->tree));
00131         }
00132 
00133         inline void FrustumCull(const Plane3<ScalarType> _frustumPlanes[6], const unsigned int _minNodeObjectsCount) {
00134                 (void)(AABBBinaryTreeFrustumCull<TreeType>::FrustumCull(this->tree, _frustumPlanes, _minNodeObjectsCount));
00135         }
00136 
00137 protected:
00138         TreeType tree;
00139 
00140 };
00141 
00142 }       // end namespace vcg
00143 
00144 #endif // #ifndef __VCGLIB_AABBBINARYTREEINDEX_H


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