00001 #ifndef GIM_TRI_COLLISION_H_INCLUDED
00002 #define GIM_TRI_COLLISION_H_INCLUDED
00003
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 #include "gim_box_collision.h"
00037 #include "gim_clip_polygon.h"
00038
00039
00040
00041
00042 #define MAX_TRI_CLIPPING 16
00043
00045 struct GIM_TRIANGLE_CONTACT_DATA
00046 {
00047 GREAL m_penetration_depth;
00048 GUINT m_point_count;
00049 btVector4 m_separating_normal;
00050 btVector3 m_points[MAX_TRI_CLIPPING];
00051
00052 SIMD_FORCE_INLINE void copy_from(const GIM_TRIANGLE_CONTACT_DATA& other)
00053 {
00054 m_penetration_depth = other.m_penetration_depth;
00055 m_separating_normal = other.m_separating_normal;
00056 m_point_count = other.m_point_count;
00057 GUINT i = m_point_count;
00058 while(i--)
00059 {
00060 m_points[i] = other.m_points[i];
00061 }
00062 }
00063
00064 GIM_TRIANGLE_CONTACT_DATA()
00065 {
00066 }
00067
00068 GIM_TRIANGLE_CONTACT_DATA(const GIM_TRIANGLE_CONTACT_DATA& other)
00069 {
00070 copy_from(other);
00071 }
00072
00073
00074
00075
00077 template<typename DISTANCE_FUNC,typename CLASS_PLANE>
00078 SIMD_FORCE_INLINE void mergepoints_generic(const CLASS_PLANE & plane,
00079 GREAL margin, const btVector3 * points, GUINT point_count, DISTANCE_FUNC distance_func)
00080 {
00081 m_point_count = 0;
00082 m_penetration_depth= -1000.0f;
00083
00084 GUINT point_indices[MAX_TRI_CLIPPING];
00085
00086 GUINT _k;
00087
00088 for(_k=0;_k<point_count;_k++)
00089 {
00090 GREAL _dist = -distance_func(plane,points[_k]) + margin;
00091
00092 if(_dist>=0.0f)
00093 {
00094 if(_dist>m_penetration_depth)
00095 {
00096 m_penetration_depth = _dist;
00097 point_indices[0] = _k;
00098 m_point_count=1;
00099 }
00100 else if((_dist+G_EPSILON)>=m_penetration_depth)
00101 {
00102 point_indices[m_point_count] = _k;
00103 m_point_count++;
00104 }
00105 }
00106 }
00107
00108 for( _k=0;_k<m_point_count;_k++)
00109 {
00110 m_points[_k] = points[point_indices[_k]];
00111 }
00112 }
00113
00115 SIMD_FORCE_INLINE void merge_points(const btVector4 & plane, GREAL margin,
00116 const btVector3 * points, GUINT point_count)
00117 {
00118 m_separating_normal = plane;
00119 mergepoints_generic(plane, margin, points, point_count, DISTANCE_PLANE_3D_FUNC());
00120 }
00121 };
00122
00123
00125 class GIM_TRIANGLE
00126 {
00127 public:
00128 btScalar m_margin;
00129 btVector3 m_vertices[3];
00130
00131 GIM_TRIANGLE():m_margin(0.1f)
00132 {
00133 }
00134
00135 SIMD_FORCE_INLINE GIM_AABB get_box() const
00136 {
00137 return GIM_AABB(m_vertices[0],m_vertices[1],m_vertices[2],m_margin);
00138 }
00139
00140 SIMD_FORCE_INLINE void get_normal(btVector3 &normal) const
00141 {
00142 TRIANGLE_NORMAL(m_vertices[0],m_vertices[1],m_vertices[2],normal);
00143 }
00144
00145 SIMD_FORCE_INLINE void get_plane(btVector4 &plane) const
00146 {
00147 TRIANGLE_PLANE(m_vertices[0],m_vertices[1],m_vertices[2],plane);;
00148 }
00149
00150 SIMD_FORCE_INLINE void apply_transform(const btTransform & trans)
00151 {
00152 m_vertices[0] = trans(m_vertices[0]);
00153 m_vertices[1] = trans(m_vertices[1]);
00154 m_vertices[2] = trans(m_vertices[2]);
00155 }
00156
00157 SIMD_FORCE_INLINE void get_edge_plane(GUINT edge_index,const btVector3 &triangle_normal,btVector4 &plane) const
00158 {
00159 const btVector3 & e0 = m_vertices[edge_index];
00160 const btVector3 & e1 = m_vertices[(edge_index+1)%3];
00161 EDGE_PLANE(e0,e1,triangle_normal,plane);
00162 }
00163
00165
00171 SIMD_FORCE_INLINE void get_triangle_transform(btTransform & triangle_transform) const
00172 {
00173 btMatrix3x3 & matrix = triangle_transform.getBasis();
00174
00175 btVector3 zaxis;
00176 get_normal(zaxis);
00177 MAT_SET_Z(matrix,zaxis);
00178
00179 btVector3 xaxis = m_vertices[1] - m_vertices[0];
00180 VEC_NORMALIZE(xaxis);
00181 MAT_SET_X(matrix,xaxis);
00182
00183
00184 xaxis = zaxis.cross(xaxis);
00185 MAT_SET_Y(matrix,xaxis);
00186
00187 triangle_transform.setOrigin(m_vertices[0]);
00188 }
00189
00190
00192
00196 bool collide_triangle_hard_test(
00197 const GIM_TRIANGLE & other,
00198 GIM_TRIANGLE_CONTACT_DATA & contact_data) const;
00199
00201
00206 SIMD_FORCE_INLINE bool collide_triangle(
00207 const GIM_TRIANGLE & other,
00208 GIM_TRIANGLE_CONTACT_DATA & contact_data) const
00209 {
00210
00211 GIM_AABB boxu(m_vertices[0],m_vertices[1],m_vertices[2],m_margin);
00212 GIM_AABB boxv(other.m_vertices[0],other.m_vertices[1],other.m_vertices[2],other.m_margin);
00213 if(!boxu.has_collision(boxv)) return false;
00214
00215
00216 return collide_triangle_hard_test(other,contact_data);
00217 }
00218
00247 SIMD_FORCE_INLINE bool get_uv_parameters(
00248 const btVector3 & point,
00249 const btVector3 & tri_plane,
00250 GREAL & u, GREAL & v) const
00251 {
00252 btVector3 _axe1 = m_vertices[1]-m_vertices[0];
00253 btVector3 _axe2 = m_vertices[2]-m_vertices[0];
00254 btVector3 _vecproj = point - m_vertices[0];
00255 GUINT _i1 = (tri_plane.closestAxis()+1)%3;
00256 GUINT _i2 = (_i1+1)%3;
00257 if(btFabs(_axe2[_i2])<G_EPSILON)
00258 {
00259 u = (_vecproj[_i2]*_axe2[_i1] - _vecproj[_i1]*_axe2[_i2]) /(_axe1[_i2]*_axe2[_i1] - _axe1[_i1]*_axe2[_i2]);
00260 v = (_vecproj[_i1] - u*_axe1[_i1])/_axe2[_i1];
00261 }
00262 else
00263 {
00264 u = (_vecproj[_i1]*_axe2[_i2] - _vecproj[_i2]*_axe2[_i1]) /(_axe1[_i1]*_axe2[_i2] - _axe1[_i2]*_axe2[_i1]);
00265 v = (_vecproj[_i2] - u*_axe1[_i2])/_axe2[_i2];
00266 }
00267
00268 if(u<-G_EPSILON)
00269 {
00270 return false;
00271 }
00272 else if(v<-G_EPSILON)
00273 {
00274 return false;
00275 }
00276 else
00277 {
00278 btScalar sumuv;
00279 sumuv = u+v;
00280 if(sumuv<-G_EPSILON)
00281 {
00282 return false;
00283 }
00284 else if(sumuv-1.0f>G_EPSILON)
00285 {
00286 return false;
00287 }
00288 }
00289 return true;
00290 }
00291
00293
00296 SIMD_FORCE_INLINE bool is_point_inside(const btVector3 & point, const btVector3 & tri_normal) const
00297 {
00298
00299 btVector4 edge_plane;
00300 this->get_edge_plane(0,tri_normal,edge_plane);
00301 GREAL dist = DISTANCE_PLANE_POINT(edge_plane,point);
00302 if(dist-m_margin>0.0f) return false;
00303
00304 this->get_edge_plane(1,tri_normal,edge_plane);
00305 dist = DISTANCE_PLANE_POINT(edge_plane,point);
00306 if(dist-m_margin>0.0f) return false;
00307
00308 this->get_edge_plane(2,tri_normal,edge_plane);
00309 dist = DISTANCE_PLANE_POINT(edge_plane,point);
00310 if(dist-m_margin>0.0f) return false;
00311 return true;
00312 }
00313
00314
00316 SIMD_FORCE_INLINE bool ray_collision(
00317 const btVector3 & vPoint,
00318 const btVector3 & vDir, btVector3 & pout, btVector3 & triangle_normal,
00319 GREAL & tparam, GREAL tmax = G_REAL_INFINITY)
00320 {
00321 btVector4 faceplane;
00322 {
00323 btVector3 dif1 = m_vertices[1] - m_vertices[0];
00324 btVector3 dif2 = m_vertices[2] - m_vertices[0];
00325 VEC_CROSS(faceplane,dif1,dif2);
00326 faceplane[3] = m_vertices[0].dot(faceplane);
00327 }
00328
00329 GUINT res = LINE_PLANE_COLLISION(faceplane,vDir,vPoint,pout,tparam, btScalar(0), tmax);
00330 if(res == 0) return false;
00331 if(! is_point_inside(pout,faceplane)) return false;
00332
00333 if(res==2)
00334 {
00335 triangle_normal.setValue(-faceplane[0],-faceplane[1],-faceplane[2]);
00336 }
00337 else
00338 {
00339 triangle_normal.setValue(faceplane[0],faceplane[1],faceplane[2]);
00340 }
00341
00342 VEC_NORMALIZE(triangle_normal);
00343
00344 return true;
00345 }
00346
00347
00349 SIMD_FORCE_INLINE bool ray_collision_front_side(
00350 const btVector3 & vPoint,
00351 const btVector3 & vDir, btVector3 & pout, btVector3 & triangle_normal,
00352 GREAL & tparam, GREAL tmax = G_REAL_INFINITY)
00353 {
00354 btVector4 faceplane;
00355 {
00356 btVector3 dif1 = m_vertices[1] - m_vertices[0];
00357 btVector3 dif2 = m_vertices[2] - m_vertices[0];
00358 VEC_CROSS(faceplane,dif1,dif2);
00359 faceplane[3] = m_vertices[0].dot(faceplane);
00360 }
00361
00362 GUINT res = LINE_PLANE_COLLISION(faceplane,vDir,vPoint,pout,tparam, btScalar(0), tmax);
00363 if(res != 1) return false;
00364
00365 if(!is_point_inside(pout,faceplane)) return false;
00366
00367 triangle_normal.setValue(faceplane[0],faceplane[1],faceplane[2]);
00368
00369 VEC_NORMALIZE(triangle_normal);
00370
00371 return true;
00372 }
00373
00374 };
00375
00376
00377
00378
00379 #endif // GIM_TRI_COLLISION_H_INCLUDED