ray.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.3  2005/10/05 01:40:56  m_di_benedetto
00029 Node children are now tested in ascending ray-T order.
00030 
00031 Revision 1.2  2005/09/28 19:48:31  m_di_benedetto
00032 Removed hit point parameter, #included aabbtree base.
00033 
00034 Revision 1.1  2005/09/26 18:33:16  m_di_benedetto
00035 First Commit.
00036 
00037 
00038 ****************************************************************************/
00039 
00040 #ifndef __VCGLIB_AABBBINARYTREE_RAY_H
00041 #define __VCGLIB_AABBBINARYTREE_RAY_H
00042 
00043 // vcg headers
00044 #include <vcg/space/ray3.h>
00045 #include <vcg/space/index/aabb_binary_tree/base.h>
00046 
00047 /***************************************************************************/
00048 
00049 namespace vcg {
00050 
00051 template <class TREETYPE>
00052 class AABBBinaryTreeRay {
00053 public:
00054         typedef AABBBinaryTreeRay<TREETYPE> ClassType;
00055         typedef TREETYPE TreeType;
00056         typedef typename TreeType::ScalarType ScalarType;
00057         typedef typename TreeType::CoordType CoordType;
00058         typedef typename TreeType::NodeType NodeType;
00059         typedef typename TreeType::ObjPtr ObjPtr;
00060 
00061         template <class OBJRAYISECTFUNCT>
00062         static inline ObjPtr Ray(TreeType & tree, OBJRAYISECTFUNCT & rayIntersection, const Ray3<ScalarType> & ray, const ScalarType & maxDist, ScalarType & t) {
00063                 typedef std::vector<NodeType *> NodePtrVector;
00064                 typedef typename NodePtrVector::const_iterator NodePtrVector_ci;
00065 
00066                 NodeType * pRoot = tree.pRoot;
00067 
00068                 if (pRoot == 0) {
00069                         return (0);
00070                 }
00071 
00072                 const CoordType & rayDirection = ray.Direction();
00073 
00074                 t = maxDist / rayDirection.Norm();
00075 
00076                 Ray3Ex rayex;
00077                 rayex.r = ray;
00078                 rayex.invDirection[0] = ((ScalarType)1) / rayDirection[0];
00079                 rayex.invDirection[1] = ((ScalarType)1) / rayDirection[1];
00080                 rayex.invDirection[2] = ((ScalarType)1) / rayDirection[2];
00081                 rayex.sign[0] = (rayex.invDirection[0] < ((ScalarType)0)) ? (1) : (0);
00082                 rayex.sign[1] = (rayex.invDirection[1] < ((ScalarType)0)) ? (1) : (0);
00083                 rayex.sign[2] = (rayex.invDirection[2] < ((ScalarType)0)) ? (1) : (0);
00084 
00085                 ObjPtr closestObj = 0;
00086                 ClassType::DepthFirstRayIsect(pRoot, rayIntersection, rayex, t, closestObj);
00087 
00088                 return (closestObj);
00089         }
00090 
00091 protected:
00092         class Ray3Ex {
00093         public:
00094                 Ray3<ScalarType> r;
00095                 CoordType invDirection;
00096                 unsigned char sign[3];
00097         };
00098 
00099         static inline bool IntersectionBoxRay(const CoordType & boxCenter, const CoordType & boxHalfDims, const Ray3Ex & ray, ScalarType & t0) {
00100                 const CoordType bounds[2] = {
00101                         boxCenter - boxHalfDims,
00102                         boxCenter + boxHalfDims
00103                 };
00104                 ScalarType tmin, tmax;
00105                 ScalarType tcmin, tcmax;
00106                 const CoordType & origin = ray.r.Origin();
00107 
00108                 tmin = (bounds[ray.sign[0]][0] - origin[0]) * ray.invDirection[0];
00109                 tmax = (bounds[1 - ray.sign[0]][0] - origin[0]) * ray.invDirection[0];
00110 
00111                 tcmin = (bounds[ray.sign[1]][1] - origin[1]) * ray.invDirection[1];
00112                 tcmax = (bounds[1 - ray.sign[1]][1] - origin[1]) * ray.invDirection[1];
00113 
00114                 if ((tmin > tcmax) || (tcmin > tmax)) { return (false); }
00115 
00116                 if (tcmin > tmin) { tmin = tcmin; }
00117                 if (tcmax < tmax) { tmax = tcmax; }
00118                 tcmin = (bounds[ray.sign[2]][2] - origin[2]) * ray.invDirection[2];
00119                 tcmax = (bounds[1-ray.sign[2]][2] - origin[2]) * ray.invDirection[2];
00120 
00121                 if ((tmin > tcmax) || (tcmin > tmax)) { return (false); }
00122 
00123                 if (tcmin > tmin) { tmin = tcmin; }
00124                 //if (tcmax < tmax) { tmax = tcmax; }
00125                 t0 = (tmin >= ((ScalarType)0)) ? (tmin) :((ScalarType)0);
00126 
00127                 return (true);
00128         }
00129 
00130         template <class OBJRAYISECTFUNCT>
00131         static inline void DepthFirstRayIsect(const NodeType * node, OBJRAYISECTFUNCT & rayIntersection, const Ray3Ex & ray, ScalarType & rayT, ObjPtr & closestObj) {
00132                 if (node == 0) {
00133                         return;
00134                 }
00135 
00136                 ScalarType rt;
00137                 if (!ClassType::IntersectionBoxRay(node->boxCenter, node->boxHalfDims, ray, rt)) {
00138                         return;
00139                 }
00140 
00141                 if (rt >= rayT) {
00142                         return;
00143                 }
00144 
00145                 if (node->IsLeaf()) {
00146                         for (typename TreeType::ObjPtrVectorConstIterator si=node->oBegin; si!=node->oEnd; ++si) {
00147                                 if (rayIntersection(*(*si), ray.r, rt)) {
00148                                         if (rt < rayT) {
00149                                                 rayT = rt;
00150                                                 closestObj = (*si);
00151                                         }
00152                                 }
00153                         }
00154                         return;
00155                 }
00156 
00157                 ClassType::DepthFirstRayIsect(node->children[0], rayIntersection, ray, rayT, closestObj);
00158                 ClassType::DepthFirstRayIsect(node->children[1], rayIntersection, ray, rayT, closestObj);
00159         }
00160 
00161 };
00162 
00163 }       // end namespace vcg
00164 
00165 #endif // #ifndef __VCGLIB_AABBBINARYTREE_RAY_H


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