gim_basic_geometry_operations.h
Go to the documentation of this file.
00001 #ifndef GIM_BASIC_GEOMETRY_OPERATIONS_H_INCLUDED
00002 #define GIM_BASIC_GEOMETRY_OPERATIONS_H_INCLUDED
00003 
00009 /*
00010 -----------------------------------------------------------------------------
00011 This source file is part of GIMPACT Library.
00012 
00013 For the latest info, see http://gimpact.sourceforge.net/
00014 
00015 Copyright (c) 2006 Francisco Leon Najera. C.C. 80087371.
00016 email: projectileman@yahoo.com
00017 
00018  This library is free software; you can redistribute it and/or
00019  modify it under the terms of EITHER:
00020    (1) The GNU Lesser General Public License as published by the Free
00021        Software Foundation; either version 2.1 of the License, or (at
00022        your option) any later version. The text of the GNU Lesser
00023        General Public License is included with this library in the
00024        file GIMPACT-LICENSE-LGPL.TXT.
00025    (2) The BSD-style license that is included with this library in
00026        the file GIMPACT-LICENSE-BSD.TXT.
00027    (3) The zlib/libpng license that is included with this library in
00028        the file GIMPACT-LICENSE-ZLIB.TXT.
00029 
00030  This library is distributed in the hope that it will be useful,
00031  but WITHOUT ANY WARRANTY; without even the implied warranty of
00032  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the files
00033  GIMPACT-LICENSE-LGPL.TXT, GIMPACT-LICENSE-ZLIB.TXT and GIMPACT-LICENSE-BSD.TXT for more details.
00034 
00035 -----------------------------------------------------------------------------
00036 */
00037 
00038 
00039 #include "gim_linear_math.h"
00040 
00041 
00042 
00043 
00044 
00045 #define PLANEDIREPSILON 0.0000001f
00046 #define PARALELENORMALS 0.000001f
00047 
00048 
00049 #define TRIANGLE_NORMAL(v1,v2,v3,n)\
00050 {\
00051         vec3f _dif1,_dif2;\
00052     VEC_DIFF(_dif1,v2,v1);\
00053     VEC_DIFF(_dif2,v3,v1);\
00054     VEC_CROSS(n,_dif1,_dif2);\
00055     VEC_NORMALIZE(n);\
00056 }\
00057 
00058 #define TRIANGLE_NORMAL_FAST(v1,v2,v3,n){\
00059     vec3f _dif1,_dif2; \
00060     VEC_DIFF(_dif1,v2,v1); \
00061     VEC_DIFF(_dif2,v3,v1); \
00062     VEC_CROSS(n,_dif1,_dif2); \
00063 }\
00064 
00065 
00066 #define TRIANGLE_PLANE(v1,v2,v3,plane) {\
00067     TRIANGLE_NORMAL(v1,v2,v3,plane);\
00068     plane[3] = VEC_DOT(v1,plane);\
00069 }\
00070 
00071 
00072 #define TRIANGLE_PLANE_FAST(v1,v2,v3,plane) {\
00073     TRIANGLE_NORMAL_FAST(v1,v2,v3,plane);\
00074     plane[3] = VEC_DOT(v1,plane);\
00075 }\
00076 
00077 
00078 #define EDGE_PLANE(e1,e2,n,plane) {\
00079     vec3f _dif; \
00080     VEC_DIFF(_dif,e2,e1); \
00081     VEC_CROSS(plane,_dif,n); \
00082     VEC_NORMALIZE(plane); \
00083     plane[3] = VEC_DOT(e1,plane);\
00084 }\
00085 
00086 #define DISTANCE_PLANE_POINT(plane,point) (VEC_DOT(plane,point) - plane[3])
00087 
00088 #define PROJECT_POINT_PLANE(point,plane,projected) {\
00089         GREAL _dis;\
00090         _dis = DISTANCE_PLANE_POINT(plane,point);\
00091         VEC_SCALE(projected,-_dis,plane);\
00092         VEC_SUM(projected,projected,point);     \
00093 }\
00094 
00095 
00096 template<typename CLASS_POINT,typename CLASS_PLANE>
00097 SIMD_FORCE_INLINE bool POINT_IN_HULL(
00098         const CLASS_POINT& point,const CLASS_PLANE * planes,GUINT plane_count)
00099 {
00100         GREAL _dis;
00101         for (GUINT _i = 0;_i< plane_count;++_i)
00102         {
00103                 _dis = DISTANCE_PLANE_POINT(planes[_i],point);
00104             if(_dis>0.0f) return false;
00105         }
00106         return true;
00107 }
00108 
00109 template<typename CLASS_POINT,typename CLASS_PLANE>
00110 SIMD_FORCE_INLINE void PLANE_CLIP_SEGMENT(
00111         const CLASS_POINT& s1,
00112         const CLASS_POINT &s2,const CLASS_PLANE &plane,CLASS_POINT &clipped)
00113 {
00114         GREAL _dis1,_dis2;
00115         _dis1 = DISTANCE_PLANE_POINT(plane,s1);
00116         VEC_DIFF(clipped,s2,s1);
00117         _dis2 = VEC_DOT(clipped,plane);
00118         VEC_SCALE(clipped,-_dis1/_dis2,clipped);
00119         VEC_SUM(clipped,clipped,s1);
00120 }
00121 
00122 enum ePLANE_INTERSECTION_TYPE
00123 {
00124         G_BACK_PLANE = 0,
00125         G_COLLIDE_PLANE,
00126         G_FRONT_PLANE
00127 };
00128 
00129 enum eLINE_PLANE_INTERSECTION_TYPE
00130 {
00131         G_FRONT_PLANE_S1 = 0,
00132         G_FRONT_PLANE_S2,
00133         G_BACK_PLANE_S1,
00134         G_BACK_PLANE_S2,
00135         G_COLLIDE_PLANE_S1,
00136         G_COLLIDE_PLANE_S2
00137 };
00138 
00140 
00152 template<typename CLASS_POINT,typename CLASS_PLANE>
00153 SIMD_FORCE_INLINE eLINE_PLANE_INTERSECTION_TYPE PLANE_CLIP_SEGMENT2(
00154         const CLASS_POINT& s1,
00155         const CLASS_POINT &s2,
00156         const CLASS_PLANE &plane,CLASS_POINT &clipped)
00157 {
00158         GREAL _dis1 = DISTANCE_PLANE_POINT(plane,s1);
00159         GREAL _dis2 = DISTANCE_PLANE_POINT(plane,s2);
00160         if(_dis1 >-G_EPSILON && _dis2 >-G_EPSILON)
00161         {
00162             if(_dis1<_dis2) return G_FRONT_PLANE_S1;
00163             return G_FRONT_PLANE_S2;
00164         }
00165         else if(_dis1 <G_EPSILON && _dis2 <G_EPSILON)
00166         {
00167             if(_dis1>_dis2) return G_BACK_PLANE_S1;
00168             return G_BACK_PLANE_S2;
00169         }
00170 
00171         VEC_DIFF(clipped,s2,s1);
00172         _dis2 = VEC_DOT(clipped,plane);
00173         VEC_SCALE(clipped,-_dis1/_dis2,clipped);
00174         VEC_SUM(clipped,clipped,s1);
00175         if(_dis1<_dis2) return G_COLLIDE_PLANE_S1;
00176         return G_COLLIDE_PLANE_S2;
00177 }
00178 
00180 
00194 template<typename CLASS_POINT,typename CLASS_PLANE>
00195 SIMD_FORCE_INLINE eLINE_PLANE_INTERSECTION_TYPE PLANE_CLIP_SEGMENT_CLOSEST(
00196         const CLASS_POINT& s1,
00197         const CLASS_POINT &s2,
00198         const CLASS_PLANE &plane,
00199         CLASS_POINT &clipped1,CLASS_POINT &clipped2)
00200 {
00201         eLINE_PLANE_INTERSECTION_TYPE intersection_type = PLANE_CLIP_SEGMENT2(s1,s2,plane,clipped1);
00202         switch(intersection_type)
00203         {
00204         case G_FRONT_PLANE_S1:
00205                 VEC_COPY(clipped1,s1);
00206             VEC_COPY(clipped2,s2);
00207                 break;
00208         case G_FRONT_PLANE_S2:
00209                 VEC_COPY(clipped1,s2);
00210             VEC_COPY(clipped2,s1);
00211                 break;
00212         case G_BACK_PLANE_S1:
00213                 VEC_COPY(clipped1,s1);
00214             VEC_COPY(clipped2,s2);
00215                 break;
00216         case G_BACK_PLANE_S2:
00217                 VEC_COPY(clipped1,s2);
00218             VEC_COPY(clipped2,s1);
00219                 break;
00220         case G_COLLIDE_PLANE_S1:
00221                 VEC_COPY(clipped2,s1);
00222                 break;
00223         case G_COLLIDE_PLANE_S2:
00224                 VEC_COPY(clipped2,s2);
00225                 break;
00226         }
00227         return intersection_type;
00228 }
00229 
00230 
00232 #define PLANE_MINOR_AXES(plane, i0, i1) VEC_MINOR_AXES(plane, i0, i1)
00233 
00235 
00239 template<typename T,typename CLASS_POINT,typename CLASS_PLANE>
00240 SIMD_FORCE_INLINE bool RAY_PLANE_COLLISION(
00241         const CLASS_PLANE & plane,
00242         const CLASS_POINT & vDir,
00243         const CLASS_POINT & vPoint,
00244         CLASS_POINT & pout,T &tparam)
00245 {
00246         GREAL _dis,_dotdir;
00247         _dotdir = VEC_DOT(plane,vDir);
00248         if(_dotdir<PLANEDIREPSILON)
00249         {
00250             return false;
00251         }
00252         _dis = DISTANCE_PLANE_POINT(plane,vPoint);
00253         tparam = -_dis/_dotdir;
00254         VEC_SCALE(pout,tparam,vDir);
00255         VEC_SUM(pout,vPoint,pout);
00256         return true;
00257 }
00258 
00260 
00266 template<typename T,typename CLASS_POINT,typename CLASS_PLANE>
00267 SIMD_FORCE_INLINE GUINT LINE_PLANE_COLLISION(
00268         const CLASS_PLANE & plane,
00269         const CLASS_POINT & vDir,
00270         const CLASS_POINT & vPoint,
00271         CLASS_POINT & pout,
00272         T &tparam,
00273         T tmin, T tmax)
00274 {
00275         GREAL _dis,_dotdir;
00276         _dotdir = VEC_DOT(plane,vDir);
00277         if(btFabs(_dotdir)<PLANEDIREPSILON)
00278         {
00279                 tparam = tmax;
00280             return 0;
00281         }
00282         _dis = DISTANCE_PLANE_POINT(plane,vPoint);
00283         char returnvalue = _dis<0.0f?2:1;
00284         tparam = -_dis/_dotdir;
00285 
00286         if(tparam<tmin)
00287         {
00288                 returnvalue = 0;
00289                 tparam = tmin;
00290         }
00291         else if(tparam>tmax)
00292         {
00293                 returnvalue = 0;
00294                 tparam = tmax;
00295         }
00296 
00297         VEC_SCALE(pout,tparam,vDir);
00298         VEC_SUM(pout,vPoint,pout);
00299         return returnvalue;
00300 }
00301 
00312 template<typename CLASS_POINT,typename CLASS_PLANE>
00313 SIMD_FORCE_INLINE bool INTERSECT_PLANES(
00314                 const CLASS_PLANE &p1,
00315                 const CLASS_PLANE &p2,
00316                 CLASS_POINT &p,
00317                 CLASS_POINT &d)
00318 {
00319         VEC_CROSS(d,p1,p2);
00320         GREAL denom = VEC_DOT(d, d);
00321         if(GIM_IS_ZERO(denom)) return false;
00322         vec3f _n;
00323         _n[0]=p1[3]*p2[0] - p2[3]*p1[0];
00324         _n[1]=p1[3]*p2[1] - p2[3]*p1[1];
00325         _n[2]=p1[3]*p2[2] - p2[3]*p1[2];
00326         VEC_CROSS(p,_n,d);
00327         p[0]/=denom;
00328         p[1]/=denom;
00329         p[2]/=denom;
00330         return true;
00331 }
00332 
00333 //***************** SEGMENT and LINE FUNCTIONS **********************************///
00334 
00337 template<typename CLASS_POINT>
00338 SIMD_FORCE_INLINE void CLOSEST_POINT_ON_SEGMENT(
00339         CLASS_POINT & cp, const CLASS_POINT & v,
00340         const CLASS_POINT &e1,const CLASS_POINT &e2)
00341 {
00342     vec3f _n;
00343     VEC_DIFF(_n,e2,e1);
00344     VEC_DIFF(cp,v,e1);
00345         GREAL _scalar = VEC_DOT(cp, _n);
00346         _scalar/= VEC_DOT(_n, _n);
00347         if(_scalar <0.0f)
00348         {
00349             VEC_COPY(cp,e1);
00350         }
00351         else if(_scalar >1.0f)
00352         {
00353             VEC_COPY(cp,e2);
00354         }
00355         else
00356         {
00357         VEC_SCALE(cp,_scalar,_n);
00358         VEC_SUM(cp,cp,e1);
00359         }
00360 }
00361 
00362 
00374 template<typename T,typename CLASS_POINT>
00375 SIMD_FORCE_INLINE bool LINE_INTERSECTION_PARAMS(
00376         const CLASS_POINT & dir1,
00377         CLASS_POINT & point1,
00378         const CLASS_POINT & dir2,
00379         CLASS_POINT &  point2,
00380         T& t1,T& t2)
00381 {
00382     GREAL det;
00383         GREAL e1e1 = VEC_DOT(dir1,dir1);
00384         GREAL e1e2 = VEC_DOT(dir1,dir2);
00385         GREAL e2e2 = VEC_DOT(dir2,dir2);
00386         vec3f p1p2;
00387     VEC_DIFF(p1p2,point1,point2);
00388     GREAL p1p2e1 = VEC_DOT(p1p2,dir1);
00389         GREAL p1p2e2 = VEC_DOT(p1p2,dir2);
00390         det = e1e2*e1e2 - e1e1*e2e2;
00391         if(GIM_IS_ZERO(det)) return false;
00392         t1 = (e1e2*p1p2e2 - e2e2*p1p2e1)/det;
00393         t2 = (e1e1*p1p2e2 - e1e2*p1p2e1)/det;
00394         return true;
00395 }
00396 
00398 template<typename CLASS_POINT>
00399 SIMD_FORCE_INLINE void SEGMENT_COLLISION(
00400         const CLASS_POINT & vA1,
00401         const CLASS_POINT & vA2,
00402         const CLASS_POINT & vB1,
00403         const CLASS_POINT & vB2,
00404         CLASS_POINT & vPointA,
00405         CLASS_POINT & vPointB)
00406 {
00407     CLASS_POINT _AD,_BD,_N;
00408     vec4f _M;//plane
00409     VEC_DIFF(_AD,vA2,vA1);
00410     VEC_DIFF(_BD,vB2,vB1);
00411     VEC_CROSS(_N,_AD,_BD);
00412     GREAL _tp = VEC_DOT(_N,_N);
00413     if(_tp<G_EPSILON)//ARE PARALELE
00414     {
00415         //project B over A
00416         bool invert_b_order = false;
00417         _M[0] = VEC_DOT(vB1,_AD);
00418         _M[1] = VEC_DOT(vB2,_AD);
00419         if(_M[0]>_M[1])
00420         {
00421                 invert_b_order  = true;
00422                 GIM_SWAP_NUMBERS(_M[0],_M[1]);
00423         }
00424         _M[2] = VEC_DOT(vA1,_AD);
00425         _M[3] = VEC_DOT(vA2,_AD);
00426         //mid points
00427         _N[0] = (_M[0]+_M[1])*0.5f;
00428         _N[1] = (_M[2]+_M[3])*0.5f;
00429 
00430         if(_N[0]<_N[1])
00431         {
00432                 if(_M[1]<_M[2])
00433                 {
00434                         vPointB = invert_b_order?vB1:vB2;
00435                         vPointA = vA1;
00436                 }
00437                 else if(_M[1]<_M[3])
00438                 {
00439                         vPointB = invert_b_order?vB1:vB2;
00440                         CLOSEST_POINT_ON_SEGMENT(vPointA,vPointB,vA1,vA2);
00441                 }
00442                 else
00443                 {
00444                         vPointA = vA2;
00445                         CLOSEST_POINT_ON_SEGMENT(vPointB,vPointA,vB1,vB2);
00446                 }
00447         }
00448         else
00449         {
00450                 if(_M[3]<_M[0])
00451                 {
00452                         vPointB = invert_b_order?vB2:vB1;
00453                         vPointA = vA2;
00454                 }
00455                 else if(_M[3]<_M[1])
00456                 {
00457                         vPointA = vA2;
00458                         CLOSEST_POINT_ON_SEGMENT(vPointB,vPointA,vB1,vB2);
00459                 }
00460                 else
00461                 {
00462                         vPointB = invert_b_order?vB1:vB2;
00463                         CLOSEST_POINT_ON_SEGMENT(vPointA,vPointB,vA1,vA2);
00464                 }
00465         }
00466         return;
00467     }
00468 
00469 
00470     VEC_CROSS(_M,_N,_BD);
00471     _M[3] = VEC_DOT(_M,vB1);
00472 
00473     LINE_PLANE_COLLISION(_M,_AD,vA1,vPointA,_tp,btScalar(0), btScalar(1));
00474     /*Closest point on segment*/
00475     VEC_DIFF(vPointB,vPointA,vB1);
00476         _tp = VEC_DOT(vPointB, _BD);
00477         _tp/= VEC_DOT(_BD, _BD);
00478         _tp = GIM_CLAMP(_tp,0.0f,1.0f);
00479     VEC_SCALE(vPointB,_tp,_BD);
00480     VEC_SUM(vPointB,vPointB,vB1);
00481 }
00482 
00483 
00484 
00485 
00487 
00497 template<typename T>
00498 SIMD_FORCE_INLINE bool BOX_AXIS_INTERSECT(T pos, T dir,T bmin, T bmax, T & tfirst, T & tlast)
00499 {
00500         if(GIM_IS_ZERO(dir))
00501         {
00502         return !(pos < bmin || pos > bmax);
00503         }
00504         GREAL a0 = (bmin - pos) / dir;
00505         GREAL a1 = (bmax - pos) / dir;
00506         if(a0 > a1)   GIM_SWAP_NUMBERS(a0, a1);
00507         tfirst = GIM_MAX(a0, tfirst);
00508         tlast = GIM_MIN(a1, tlast);
00509         if (tlast < tfirst) return false;
00510         return true;
00511 }
00512 
00513 
00515 template<typename T>
00516 SIMD_FORCE_INLINE void SORT_3_INDICES(
00517                 const T * values,
00518                 GUINT * order_indices)
00519 {
00520         //get minimum
00521         order_indices[0] = values[0] < values[1] ? (values[0] < values[2] ? 0 : 2) : (values[1] < values[2] ? 1 : 2);
00522 
00523         //get second and third
00524         GUINT i0 = (order_indices[0] + 1)%3;
00525         GUINT i1 = (i0 + 1)%3;
00526 
00527         if(values[i0] < values[i1])
00528         {
00529                 order_indices[1] = i0;
00530                 order_indices[2] = i1;
00531         }
00532         else
00533         {
00534                 order_indices[1] = i1;
00535                 order_indices[2] = i0;
00536         }
00537 }
00538 
00539 
00540 
00541 
00542 
00543 #endif // GIM_VECTOR_H_INCLUDED
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Defines


bullet
Author(s): Erwin Coumans, ROS package maintained by Tully Foote
autogenerated on Wed Oct 31 2012 07:54:31