1 #ifndef GIM_BOX_COLLISION_H_INCLUDED     2 #define GIM_BOX_COLLISION_H_INCLUDED   100 #ifndef TEST_CROSS_EDGE_BOX_MCR   102 #define TEST_CROSS_EDGE_BOX_MCR(edge,absolute_edge,pointa,pointb,_extend,i_dir_0,i_dir_1,i_comp_0,i_comp_1)\   104         const btScalar dir0 = -edge[i_dir_0];\   105         const btScalar dir1 = edge[i_dir_1];\   106         btScalar pmin = pointa[i_comp_0]*dir0 + pointa[i_comp_1]*dir1;\   107         btScalar pmax = pointb[i_comp_0]*dir0 + pointb[i_comp_1]*dir1;\   110                 GIM_SWAP_NUMBERS(pmin,pmax); \   112         const btScalar abs_dir0 = absolute_edge[i_dir_0];\   113         const btScalar abs_dir1 = absolute_edge[i_dir_1];\   114         const btScalar rad = _extend[i_comp_0] * abs_dir0 + _extend[i_comp_1] * abs_dir1;\   115         if(pmin>rad || -rad>pmax) return false;\   120 #define TEST_CROSS_EDGE_BOX_X_AXIS_MCR(edge,absolute_edge,pointa,pointb,_extend)\   122         TEST_CROSS_EDGE_BOX_MCR(edge,absolute_edge,pointa,pointb,_extend,2,1,1,2);\   125 #define TEST_CROSS_EDGE_BOX_Y_AXIS_MCR(edge,absolute_edge,pointa,pointb,_extend)\   127         TEST_CROSS_EDGE_BOX_MCR(edge,absolute_edge,pointa,pointb,_extend,0,2,2,0);\   130 #define TEST_CROSS_EDGE_BOX_Z_AXIS_MCR(edge,absolute_edge,pointa,pointb,_extend)\   132         TEST_CROSS_EDGE_BOX_MCR(edge,absolute_edge,pointa,pointb,_extend,1,0,0,1);\   147                 static const btVector3 vepsi(1e-6f,1e-6f,1e-6f);
   148                 m_AR[0] = vepsi + m_R1to0[0].
absolute();
   149                 m_AR[1] = vepsi + m_R1to0[1].
absolute();
   150                 m_AR[2] = vepsi + m_R1to0[2].
absolute();
   170                 m_T1to0 = m_R1to0 * (-trans0.
getOrigin());
   182                 m_T1to0 = m_R1to0 * (-trans0.
getOrigin());
   192         return point.
dot3(m_R1to0[0], m_R1to0[1], m_R1to0[2]) + 
m_T1to0;
   196 #ifndef BOX_PLANE_EPSILON   197 #define BOX_PLANE_EPSILON 0.000001f   215                 m_min[0] = 
GIM_MIN3(V1[0],V2[0],V3[0]);
   216                 m_min[1] = 
GIM_MIN3(V1[1],V2[1],V3[1]);
   217                 m_min[2] = 
GIM_MIN3(V1[2],V2[2],V3[2]);
   219                 m_max[0] = 
GIM_MAX3(V1[0],V2[0],V3[0]);
   220                 m_max[1] = 
GIM_MAX3(V1[1],V2[1],V3[1]);
   221                 m_max[2] = 
GIM_MAX3(V1[2],V2[2],V3[2]);
   229                 m_min[0] = 
GIM_MIN3(V1[0],V2[0],V3[0]);
   230                 m_min[1] = 
GIM_MIN3(V1[1],V2[1],V3[1]);
   231                 m_min[2] = 
GIM_MIN3(V1[2],V2[2],V3[2]);
   233                 m_max[0] = 
GIM_MAX3(V1[0],V2[0],V3[0]);
   234                 m_max[1] = 
GIM_MAX3(V1[1],V2[1],V3[1]);
   235                 m_max[2] = 
GIM_MAX3(V1[2],V2[2],V3[2]);
   246                 m_min(other.m_min),m_max(other.m_max)
   251                 m_min(other.m_min),m_max(other.m_max)
   283                 m_min[0] = other.
m_min[0] - margin;
   284                 m_min[1] = other.
m_min[1] - margin;
   285                 m_min[2] = other.
m_min[2] - margin;
   287                 m_max[0] = other.
m_max[0] + margin;
   288                 m_max[1] = other.
m_max[1] + margin;
   289                 m_max[2] = other.
m_max[2] + margin;
   292         template<
typename CLASS_POINT>
   294                                                         const CLASS_POINT & V1,
   295                                                         const CLASS_POINT & V2,
   296                                                         const CLASS_POINT & V3)
   298                 m_min[0] = 
GIM_MIN3(V1[0],V2[0],V3[0]);
   299                 m_min[1] = 
GIM_MIN3(V1[1],V2[1],V3[1]);
   300                 m_min[2] = 
GIM_MIN3(V1[2],V2[2],V3[2]);
   302                 m_max[0] = 
GIM_MAX3(V1[0],V2[0],V3[0]);
   303                 m_max[1] = 
GIM_MAX3(V1[1],V2[1],V3[1]);
   304                 m_max[2] = 
GIM_MAX3(V1[2],V2[2],V3[2]);
   307         template<
typename CLASS_POINT>
   309                                                         const CLASS_POINT & V1,
   310                                                         const CLASS_POINT & V2,
   311                                                         const CLASS_POINT & V3, 
btScalar margin)
   313                 m_min[0] = 
GIM_MIN3(V1[0],V2[0],V3[0]);
   314                 m_min[1] = 
GIM_MIN3(V1[1],V2[1],V3[1]);
   315                 m_min[2] = 
GIM_MIN3(V1[2],V2[2],V3[2]);
   317                 m_max[0] = 
GIM_MAX3(V1[0],V2[0],V3[0]);
   318                 m_max[1] = 
GIM_MAX3(V1[1],V2[1],V3[1]);
   319                 m_max[2] = 
GIM_MAX3(V1[2],V2[2],V3[2]);
   335                 center = trans(center);
   341                 m_min = center - textends;
   342                 m_max = center + textends;
   358         template<
typename CLASS_POINT>
   361                 m_min[0] = 
GIM_MIN(m_min[0],point[0]);
   362                 m_min[1] = 
GIM_MIN(m_min[1],point[1]);
   363                 m_min[2] = 
GIM_MIN(m_min[2],point[2]);
   365                 m_max[0] = 
GIM_MAX(m_max[0],point[0]);
   366                 m_max[1] = 
GIM_MAX(m_max[1],point[1]);
   367                 m_max[2] = 
GIM_MAX(m_max[2],point[2]);
   373                 center = (m_max+m_min)*0.5f;
   374                 extend = m_max - center;
   392                 if(m_min[0] > other.
m_max[0] ||
   393                    m_max[0] < other.
m_min[0] ||
   394                    m_min[1] > other.
m_max[1] ||
   395                    m_max[1] < other.
m_min[1] ||
   396                    m_min[2] > other.
m_max[2] ||
   397                    m_max[2] < other.
m_min[2])
   412                 this->get_center_extend(center,extents);;
   414                 btScalar Dx = vorigin[0] - center[0];
   415                 if(
GIM_GREATER(Dx, extents[0]) && Dx*vdir[0]>=0.0f)     
return false;
   416                 btScalar Dy = vorigin[1] - center[1];
   417                 if(
GIM_GREATER(Dy, extents[1]) && Dy*vdir[1]>=0.0f)     
return false;
   418                 btScalar Dz = vorigin[2] - center[2];
   419                 if(
GIM_GREATER(Dz, extents[2]) && Dz*vdir[2]>=0.0f)     
return false;
   422                 btScalar f = vdir[1] * Dz - vdir[2] * Dy;
   424                 f = vdir[2] * Dx - vdir[0] * Dz;
   426                 f = vdir[0] * Dy - vdir[1] * Dx;
   439                 vmin = _fOrigin - _fMaximumExtent;
   440                 vmax = _fOrigin + _fMaximumExtent;
   446                 this->projection_interval(plane,_fmin,_fmax);
   464                 return has_collision(tbox);
   475                 get_center_extend(ca,ea);
   486                         T[i] =  transcache.
m_R1to0[i].dot(cb) + transcache.
m_T1to0[i] - ca[i];
   487                         t = transcache.
m_AR[i].dot(eb) + ea[i];
   511                                         t = T[n]*transcache.
m_R1to0[m][j] - T[m]*transcache.
m_R1to0[n][j];
   512                                         t2 = ea[o]*transcache.
m_AR[p][j] + ea[p]*transcache.
m_AR[o][j] +
   513                                                 eb[r]*transcache.
m_AR[i][q] + eb[q]*transcache.
m_AR[i][r];
   536                 if(!collide_plane(triangle_plane)) 
return false;
   539                 this->get_center_extend(center,extends);
   578 #ifndef BT_BOX_COLLISION_H_INCLUDED   593 #endif // GIM_BOX_COLLISION_H_INCLUDED btMatrix3x3 inverse() const 
Return the inverse of the matrix. 
ePLANE_INTERSECTION_TYPE plane_classify(const btVector4 &plane) const 
void calc_from_triangle_margin(const CLASS_POINT &V1, const CLASS_POINT &V2, const CLASS_POINT &V3, btScalar margin)
void find_intersection(const GIM_AABB &other, GIM_AABB &intersection) const 
Finds the intersecting box between this box and the other. 
void get_center_extend(btVector3 ¢er, btVector3 &extend) const 
Gets the extend and center. 
#define TEST_CROSS_EDGE_BOX_X_AXIS_MCR(edge, absolute_edge, pointa, pointb, _extend)
#define GIM_GREATER(x, y)
btVector3 absolute() const 
Return a vector with the absolute values of each element. 
bool has_collision(const GIM_AABB &other) const 
#define SIMD_FORCE_INLINE
const btVector3 & getRow(int i) const 
Get a row of the matrix as a vector. 
GIM_AABB(const GIM_AABB &other)
btScalar dot(const btVector3 &v) const 
Return the dot product. 
void copy_with_margin(const GIM_AABB &other, btScalar margin)
bool overlapping_trans_conservative(const GIM_AABB &box, btTransform &trans1_to_0)
bool collide_ray(const btVector3 &vorigin, const btVector3 &vdir)
Finds the Ray intersection parameter. 
void calc_from_triangle(const CLASS_POINT &V1, const CLASS_POINT &V2, const CLASS_POINT &V3)
btMatrix3x3 absolute() const 
Return the matrix with all values non negative. 
#define BOX_PLANE_EPSILON
#define TEST_CROSS_EDGE_BOX_Y_AXIS_MCR(edge, absolute_edge, pointa, pointb, _extend)
bool collide_plane(const btVector4 &plane)
Simple test for planes. 
GIM_AABB(const GIM_AABB &other, btScalar margin)
#define GIM_MIN3(a, b, c)
btVector3 can be used to represent 3D points and vectors. 
bool overlapping_trans_cache(const GIM_AABB &box, const GIM_BOX_BOX_TRANSFORM_CACHE &transcache, bool fulltest)
transcache is the transformation cache from box to this AABB 
GREAL mat4f[4][4]
Matrix 4D, row ordered. 
GIM_AABB(const btVector3 &V1, const btVector3 &V2, const btVector3 &V3)
bool btCompareTransformsEqual(const btTransform &t1, const btTransform &t2)
Compairison of transformation objects. 
btMatrix3x3 transpose() const 
Return the transpose of the matrix. 
void merge_point(const CLASS_POINT &point)
Merges a point. 
void appy_transform(const btTransform &trans)
Apply a transform to an AABB. 
btVector3 dot3(const btVector3 &v0, const btVector3 &v1, const btVector3 &v2) const 
#define MAT_GET_TRANSLATION(mat, vec3)
Get the triple(3) col of a transform matrix. 
#define COPY_MATRIX_3X3(b, a)
#define TEST_CROSS_EDGE_BOX_Z_AXIS_MCR(edge, absolute_edge, pointa, pointb, _extend)
The btMatrix3x3 class implements a 3x3 rotation matrix, to perform linear algebra in combination with...
bool collide_triangle_exact(const btVector3 &p1, const btVector3 &p2, const btVector3 &p3, const btVector4 &triangle_plane)
test for a triangle, with edges 
void projection_interval(const btVector3 &direction, btScalar &vmin, btScalar &vmax) const 
#define GIM_MAX3(a, b, c)
GIM_AABB(const btVector3 &V1, const btVector3 &V2, const btVector3 &V3, GREAL margin)
#define MAT_DOT_COL(mat, vec3, colindex)
Returns the dot product between a vec3f and the col of a matrix. 
void increment_margin(btScalar margin)
void merge(const GIM_AABB &box)
Merges a Box. 
float btScalar
The btScalar type abstracts floating point numbers, to easily switch between double and single floati...
btScalar btFabs(btScalar x)