OPC_SphereCollider.cpp
Go to the documentation of this file.
00001 
00002 /*
00003  *      OPCODE - Optimized Collision Detection
00004  *      Copyright (C) 2001 Pierre Terdiman
00005  *      Homepage: http://www.codercorner.com/Opcode.htm
00006  */
00008 
00010 
00016 
00017 
00019 
00031 
00032 
00034 // Precompiled Header
00035 #include "Stdafx.h"
00036 
00037 using namespace Opcode;
00038 
00039 #include "OPC_SphereAABBOverlap.h"
00040 #include "OPC_SphereTriOverlap.h"
00041 
00042 #define SET_CONTACT(prim_index, flag)                                                                   \
00043         /* Set contact status */                                                                                        \
00044         mFlags |= flag;                                                                                                         \
00045         mTouchedPrimitives->Add(prim_index);
00046 
00048 #define SPHERE_PRIM(prim_index, flag)                                                                   \
00049         /* Request vertices from the app */                                                                     \
00050         VertexPointers VP;      mIMesh->GetTriangle(VP, prim_index);                    \
00051                                                                                                                                                 \
00052         /* Perform sphere-tri overlap test */                                                           \
00053         if(SphereTriOverlap(*VP.Vertex[0], *VP.Vertex[1], *VP.Vertex[2]))       \
00054         {                                                                                                                                       \
00055                 SET_CONTACT(prim_index, flag)                                                                   \
00056         }
00057 
00059 
00062 
00063 SphereCollider::SphereCollider()
00064 {
00065         mCenter.Zero();
00066         mRadius2 = 0.0f;
00067 }
00068 
00070 
00073 
00074 SphereCollider::~SphereCollider()
00075 {
00076 }
00077 
00079 
00093 
00094 bool SphereCollider::Collide(SphereCache& cache, const Sphere& sphere, const Model& model, const Matrix4x4* worlds, const Matrix4x4* worldm)
00095 {
00096         // Checkings
00097         if(!Setup(&model))      return false;
00098 
00099         // Init collision query
00100         if(InitQuery(cache, sphere, worlds, worldm))    return true;
00101 
00102         if(!model.HasLeafNodes())
00103         {
00104                 if(model.IsQuantized())
00105                 {
00106                         const AABBQuantizedNoLeafTree* Tree = (const AABBQuantizedNoLeafTree*)model.GetTree();
00107 
00108                         // Setup dequantization coeffs
00109                         mCenterCoeff    = Tree->mCenterCoeff;
00110                         mExtentsCoeff   = Tree->mExtentsCoeff;
00111 
00112                         // Perform collision query
00113                         if(SkipPrimitiveTests())        _CollideNoPrimitiveTest(Tree->GetNodes());
00114                         else                                            _Collide(Tree->GetNodes());
00115                 }
00116                 else
00117                 {
00118                         const AABBNoLeafTree* Tree = (const AABBNoLeafTree*)model.GetTree();
00119 
00120                         // Perform collision query
00121                         if(SkipPrimitiveTests())        _CollideNoPrimitiveTest(Tree->GetNodes());
00122                         else                                            _Collide(Tree->GetNodes());
00123                 }
00124         }
00125         else
00126         {
00127                 if(model.IsQuantized())
00128                 {
00129                         const AABBQuantizedTree* Tree = (const AABBQuantizedTree*)model.GetTree();
00130 
00131                         // Setup dequantization coeffs
00132                         mCenterCoeff    = Tree->mCenterCoeff;
00133                         mExtentsCoeff   = Tree->mExtentsCoeff;
00134 
00135                         // Perform collision query
00136                         if(SkipPrimitiveTests())        _CollideNoPrimitiveTest(Tree->GetNodes());
00137                         else                                            _Collide(Tree->GetNodes());
00138                 }
00139                 else
00140                 {
00141                         const AABBCollisionTree* Tree = (const AABBCollisionTree*)model.GetTree();
00142 
00143                         // Perform collision query
00144                         if(SkipPrimitiveTests())        _CollideNoPrimitiveTest(Tree->GetNodes());
00145                         else                                            _Collide(Tree->GetNodes());
00146                 }
00147         }
00148         return true;
00149 }
00150 
00152 
00165 
00166 BOOL SphereCollider::InitQuery(SphereCache& cache, const Sphere& sphere, const Matrix4x4* worlds, const Matrix4x4* worldm)
00167 {
00168         // 1) Call the base method
00169         VolumeCollider::InitQuery();
00170 
00171         // 2) Compute sphere in model space:
00172         // - Precompute R^2
00173         mRadius2 = sphere.mRadius * sphere.mRadius;
00174         // - Compute center position
00175         mCenter = sphere.mCenter;
00176         // -> to world space
00177         if(worlds)      mCenter *= *worlds;
00178         // -> to model space
00179         if(worldm)
00180         {
00181                 // Invert model matrix
00182                 Matrix4x4 InvWorldM;
00183                 InvertPRMatrix(InvWorldM, *worldm);
00184 
00185                 mCenter *= InvWorldM;
00186         }
00187 
00188         // 3) Setup destination pointer
00189         mTouchedPrimitives = &cache.TouchedPrimitives;
00190 
00191         // 4) Special case: 1-triangle meshes [Opcode 1.3]
00192         if(mCurrentModel && mCurrentModel->HasSingleNode())
00193         {
00194                 if(!SkipPrimitiveTests())
00195                 {
00196                         // We simply perform the BV-Prim overlap test each time. We assume single triangle has index 0.
00197                         mTouchedPrimitives->Reset();
00198 
00199                         // Perform overlap test between the unique triangle and the sphere (and set contact status if needed)
00200                         SPHERE_PRIM(udword(0), OPC_CONTACT)
00201 
00202                         // Return immediately regardless of status
00203                         return TRUE;
00204                 }
00205         }
00206 
00207         // 5) Check temporal coherence :
00208         if(TemporalCoherenceEnabled())
00209         {
00210                 // Here we use temporal coherence
00211                 // => check results from previous frame before performing the collision query
00212                 if(FirstContactEnabled())
00213                 {
00214                         // We're only interested in the first contact found => test the unique previously touched face
00215                         if(mTouchedPrimitives->GetNbEntries())
00216                         {
00217                                 // Get index of previously touched face = the first entry in the array
00218                                 udword PreviouslyTouchedFace = mTouchedPrimitives->GetEntry(0);
00219 
00220                                 // Then reset the array:
00221                                 // - if the overlap test below is successful, the index we'll get added back anyway
00222                                 // - if it isn't, then the array should be reset anyway for the normal query
00223                                 mTouchedPrimitives->Reset();
00224 
00225                                 // Perform overlap test between the cached triangle and the sphere (and set contact status if needed)
00226                                 SPHERE_PRIM(PreviouslyTouchedFace, OPC_TEMPORAL_CONTACT)
00227 
00228                                 // Return immediately if possible
00229                                 if(GetContactStatus())  return TRUE;
00230                         }
00231                         // else no face has been touched during previous query
00232                         // => we'll have to perform a normal query
00233                 }
00234                 else
00235                 {
00236                         // We're interested in all contacts =>test the new real sphere N(ew) against the previous fat sphere P(revious):
00237                         float r = sqrtf(cache.FatRadius2) - sphere.mRadius;
00238                         if(IsCacheValid(cache) && cache.Center.SquareDistance(mCenter) < r*r)
00239                         {
00240                                 // - if N is included in P, return previous list
00241                                 // => we simply leave the list (mTouchedFaces) unchanged
00242 
00243                                 // Set contact status if needed
00244                                 if(mTouchedPrimitives->GetNbEntries())  mFlags |= OPC_TEMPORAL_CONTACT;
00245 
00246                                 // In any case we don't need to do a query
00247                                 return TRUE;
00248                         }
00249                         else
00250                         {
00251                                 // - else do the query using a fat N
00252 
00253                                 // Reset cache since we'll about to perform a real query
00254                                 mTouchedPrimitives->Reset();
00255 
00256                                 // Make a fat sphere so that coherence will work for subsequent frames
00257                                 mRadius2 *= cache.FatCoeff;
00258 //                              mRadius2 = (sphere.mRadius * cache.FatCoeff)*(sphere.mRadius * cache.FatCoeff);
00259 
00260                                 // Update cache with query data (signature for cached faces)
00261                                 cache.Center = mCenter;
00262                                 cache.FatRadius2 = mRadius2;
00263                         }
00264                 }
00265         }
00266         else
00267         {
00268                 // Here we don't use temporal coherence => do a normal query
00269                 mTouchedPrimitives->Reset();
00270         }
00271 
00272         return FALSE;
00273 }
00274 
00276 
00283 
00284 bool SphereCollider::Collide(SphereCache& cache, const Sphere& sphere, const AABBTree* tree)
00285 {
00286         // This is typically called for a scene tree, full of -AABBs-, not full of triangles.
00287         // So we don't really have "primitives" to deal with. Hence it doesn't work with
00288         // "FirstContact" + "TemporalCoherence".
00289         ASSERT( !(FirstContactEnabled() && TemporalCoherenceEnabled()) );
00290 
00291         // Checkings
00292         if(!tree)       return false;
00293 
00294         // Init collision query
00295         if(InitQuery(cache, sphere))    return true;
00296 
00297         // Perform collision query
00298         _Collide(tree);
00299 
00300         return true;
00301 }
00302 
00304 
00310 
00311 inline_ BOOL SphereCollider::SphereContainsBox(const Point& bc, const Point& be)
00312 {
00313         // I assume if all 8 box vertices are inside the sphere, so does the whole box.
00314         // Sounds ok but maybe there's a better way?
00315         Point p;
00316         p.x=bc.x+be.x; p.y=bc.y+be.y; p.z=bc.z+be.z;    if(mCenter.SquareDistance(p)>=mRadius2) return FALSE;
00317         p.x=bc.x-be.x;                                                                  if(mCenter.SquareDistance(p)>=mRadius2) return FALSE;
00318         p.x=bc.x+be.x; p.y=bc.y-be.y;                                   if(mCenter.SquareDistance(p)>=mRadius2) return FALSE;
00319         p.x=bc.x-be.x;                                                                  if(mCenter.SquareDistance(p)>=mRadius2) return FALSE;
00320         p.x=bc.x+be.x; p.y=bc.y+be.y; p.z=bc.z-be.z;    if(mCenter.SquareDistance(p)>=mRadius2) return FALSE;
00321         p.x=bc.x-be.x;                                                                  if(mCenter.SquareDistance(p)>=mRadius2) return FALSE;
00322         p.x=bc.x+be.x; p.y=bc.y-be.y;                                   if(mCenter.SquareDistance(p)>=mRadius2) return FALSE;
00323         p.x=bc.x-be.x;                                                                  if(mCenter.SquareDistance(p)>=mRadius2) return FALSE;
00324 
00325         return TRUE;
00326 }
00327 
00328 #define TEST_BOX_IN_SPHERE(center, extents)     \
00329         if(SphereContainsBox(center, extents))  \
00330         {                                                                               \
00331                 /* Set contact status */                        \
00332                 mFlags |= OPC_CONTACT;                          \
00333                 _Dump(node);                                            \
00334                 return;                                                         \
00335         }
00336 
00338 
00342 
00343 void SphereCollider::_Collide(const AABBCollisionNode* node)
00344 {
00345         // Perform Sphere-AABB overlap test
00346         if(!SphereAABBOverlap(node->mAABB.mCenter, node->mAABB.mExtents))       return;
00347 
00348         TEST_BOX_IN_SPHERE(node->mAABB.mCenter, node->mAABB.mExtents)
00349 
00350         if(node->IsLeaf())
00351         {
00352                 SPHERE_PRIM(node->GetPrimitive(), OPC_CONTACT)
00353         }
00354         else
00355         {
00356                 _Collide(node->GetPos());
00357 
00358                 if(ContactFound()) return;
00359 
00360                 _Collide(node->GetNeg());
00361         }
00362 }
00363 
00365 
00369 
00370 void SphereCollider::_CollideNoPrimitiveTest(const AABBCollisionNode* node)
00371 {
00372         // Perform Sphere-AABB overlap test
00373         if(!SphereAABBOverlap(node->mAABB.mCenter, node->mAABB.mExtents))       return;
00374 
00375         TEST_BOX_IN_SPHERE(node->mAABB.mCenter, node->mAABB.mExtents)
00376 
00377         if(node->IsLeaf())
00378         {
00379                 SET_CONTACT(node->GetPrimitive(), OPC_CONTACT)
00380         }
00381         else
00382         {
00383                 _CollideNoPrimitiveTest(node->GetPos());
00384 
00385                 if(ContactFound()) return;
00386 
00387                 _CollideNoPrimitiveTest(node->GetNeg());
00388         }
00389 }
00390 
00392 
00396 
00397 void SphereCollider::_Collide(const AABBQuantizedNode* node)
00398 {
00399         // Dequantize box
00400         const QuantizedAABB& Box = node->mAABB;
00401         const Point Center(float(Box.mCenter[0]) * mCenterCoeff.x, float(Box.mCenter[1]) * mCenterCoeff.y, float(Box.mCenter[2]) * mCenterCoeff.z);
00402         const Point Extents(float(Box.mExtents[0]) * mExtentsCoeff.x, float(Box.mExtents[1]) * mExtentsCoeff.y, float(Box.mExtents[2]) * mExtentsCoeff.z);
00403 
00404         // Perform Sphere-AABB overlap test
00405         if(!SphereAABBOverlap(Center, Extents)) return;
00406 
00407         TEST_BOX_IN_SPHERE(Center, Extents)
00408 
00409         if(node->IsLeaf())
00410         {
00411                 SPHERE_PRIM(node->GetPrimitive(), OPC_CONTACT)
00412         }
00413         else
00414         {
00415                 _Collide(node->GetPos());
00416 
00417                 if(ContactFound()) return;
00418 
00419                 _Collide(node->GetNeg());
00420         }
00421 }
00422 
00424 
00428 
00429 void SphereCollider::_CollideNoPrimitiveTest(const AABBQuantizedNode* node)
00430 {
00431         // Dequantize box
00432         const QuantizedAABB& Box = node->mAABB;
00433         const Point Center(float(Box.mCenter[0]) * mCenterCoeff.x, float(Box.mCenter[1]) * mCenterCoeff.y, float(Box.mCenter[2]) * mCenterCoeff.z);
00434         const Point Extents(float(Box.mExtents[0]) * mExtentsCoeff.x, float(Box.mExtents[1]) * mExtentsCoeff.y, float(Box.mExtents[2]) * mExtentsCoeff.z);
00435 
00436         // Perform Sphere-AABB overlap test
00437         if(!SphereAABBOverlap(Center, Extents)) return;
00438 
00439         TEST_BOX_IN_SPHERE(Center, Extents)
00440 
00441         if(node->IsLeaf())
00442         {
00443                 SET_CONTACT(node->GetPrimitive(), OPC_CONTACT)
00444         }
00445         else
00446         {
00447                 _CollideNoPrimitiveTest(node->GetPos());
00448 
00449                 if(ContactFound()) return;
00450 
00451                 _CollideNoPrimitiveTest(node->GetNeg());
00452         }
00453 }
00454 
00456 
00460 
00461 void SphereCollider::_Collide(const AABBNoLeafNode* node)
00462 {
00463         // Perform Sphere-AABB overlap test
00464         if(!SphereAABBOverlap(node->mAABB.mCenter, node->mAABB.mExtents))       return;
00465 
00466         TEST_BOX_IN_SPHERE(node->mAABB.mCenter, node->mAABB.mExtents)
00467 
00468         if(node->HasPosLeaf())  { SPHERE_PRIM(node->GetPosPrimitive(), OPC_CONTACT) }
00469         else                                    _Collide(node->GetPos());
00470 
00471         if(ContactFound()) return;
00472 
00473         if(node->HasNegLeaf())  { SPHERE_PRIM(node->GetNegPrimitive(), OPC_CONTACT) }
00474         else                                    _Collide(node->GetNeg());
00475 }
00476 
00478 
00482 
00483 void SphereCollider::_CollideNoPrimitiveTest(const AABBNoLeafNode* node)
00484 {
00485         // Perform Sphere-AABB overlap test
00486         if(!SphereAABBOverlap(node->mAABB.mCenter, node->mAABB.mExtents))       return;
00487 
00488         TEST_BOX_IN_SPHERE(node->mAABB.mCenter, node->mAABB.mExtents)
00489 
00490         if(node->HasPosLeaf())  { SET_CONTACT(node->GetPosPrimitive(), OPC_CONTACT) }
00491         else                                    _CollideNoPrimitiveTest(node->GetPos());
00492 
00493         if(ContactFound()) return;
00494 
00495         if(node->HasNegLeaf())  { SET_CONTACT(node->GetNegPrimitive(), OPC_CONTACT) }
00496         else                                    _CollideNoPrimitiveTest(node->GetNeg());
00497 }
00498 
00500 
00504 
00505 void SphereCollider::_Collide(const AABBQuantizedNoLeafNode* node)
00506 {
00507         // Dequantize box
00508         const QuantizedAABB& Box = node->mAABB;
00509         const Point Center(float(Box.mCenter[0]) * mCenterCoeff.x, float(Box.mCenter[1]) * mCenterCoeff.y, float(Box.mCenter[2]) * mCenterCoeff.z);
00510         const Point Extents(float(Box.mExtents[0]) * mExtentsCoeff.x, float(Box.mExtents[1]) * mExtentsCoeff.y, float(Box.mExtents[2]) * mExtentsCoeff.z);
00511 
00512         // Perform Sphere-AABB overlap test
00513         if(!SphereAABBOverlap(Center, Extents)) return;
00514 
00515         TEST_BOX_IN_SPHERE(Center, Extents)
00516 
00517         if(node->HasPosLeaf())  { SPHERE_PRIM(node->GetPosPrimitive(), OPC_CONTACT) }
00518         else                                    _Collide(node->GetPos());
00519 
00520         if(ContactFound()) return;
00521 
00522         if(node->HasNegLeaf())  { SPHERE_PRIM(node->GetNegPrimitive(), OPC_CONTACT) }
00523         else                                    _Collide(node->GetNeg());
00524 }
00525 
00527 
00531 
00532 void SphereCollider::_CollideNoPrimitiveTest(const AABBQuantizedNoLeafNode* node)
00533 {
00534         // Dequantize box
00535         const QuantizedAABB& Box = node->mAABB;
00536         const Point Center(float(Box.mCenter[0]) * mCenterCoeff.x, float(Box.mCenter[1]) * mCenterCoeff.y, float(Box.mCenter[2]) * mCenterCoeff.z);
00537         const Point Extents(float(Box.mExtents[0]) * mExtentsCoeff.x, float(Box.mExtents[1]) * mExtentsCoeff.y, float(Box.mExtents[2]) * mExtentsCoeff.z);
00538 
00539         // Perform Sphere-AABB overlap test
00540         if(!SphereAABBOverlap(Center, Extents)) return;
00541 
00542         TEST_BOX_IN_SPHERE(Center, Extents)
00543 
00544         if(node->HasPosLeaf())  { SET_CONTACT(node->GetPosPrimitive(), OPC_CONTACT) }
00545         else                                    _CollideNoPrimitiveTest(node->GetPos());
00546 
00547         if(ContactFound()) return;
00548 
00549         if(node->HasNegLeaf())  { SET_CONTACT(node->GetNegPrimitive(), OPC_CONTACT) }
00550         else                                    _CollideNoPrimitiveTest(node->GetNeg());
00551 }
00552 
00554 
00558 
00559 void SphereCollider::_Collide(const AABBTreeNode* node)
00560 {
00561         // Perform Sphere-AABB overlap test
00562         Point Center, Extents;
00563         node->GetAABB()->GetCenter(Center);
00564         node->GetAABB()->GetExtents(Extents);
00565         if(!SphereAABBOverlap(Center, Extents)) return;
00566 
00567         if(node->IsLeaf() || SphereContainsBox(Center, Extents))
00568         {
00569                 mFlags |= OPC_CONTACT;
00570                 mTouchedPrimitives->Add(node->GetPrimitives(), node->GetNbPrimitives());
00571         }
00572         else
00573         {
00574                 _Collide(node->GetPos());
00575                 _Collide(node->GetNeg());
00576         }
00577 }
00578 
00579 
00580 
00581 
00582 
00583 
00584 
00586 
00589 
00590 HybridSphereCollider::HybridSphereCollider()
00591 {
00592 }
00593 
00595 
00598 
00599 HybridSphereCollider::~HybridSphereCollider()
00600 {
00601 }
00602 
00603 bool HybridSphereCollider::Collide(SphereCache& cache, const Sphere& sphere, const HybridModel& model, const Matrix4x4* worlds, const Matrix4x4* worldm)
00604 {
00605         // We don't want primitive tests here!
00606         mFlags |= OPC_NO_PRIMITIVE_TESTS;
00607 
00608         // Checkings
00609         if(!Setup(&model))      return false;
00610 
00611         // Init collision query
00612         if(InitQuery(cache, sphere, worlds, worldm))    return true;
00613 
00614         // Special case for 1-leaf trees
00615         if(mCurrentModel && mCurrentModel->HasSingleNode())
00616         {
00617                 // Here we're supposed to perform a normal query, except our tree has a single node, i.e. just a few triangles
00618                 udword Nb = mIMesh->GetNbTriangles();
00619 
00620                 // Loop through all triangles
00621                 for(udword i=0;i<Nb;i++)
00622                 {
00623                         SPHERE_PRIM(i, OPC_CONTACT)
00624                 }
00625                 return true;
00626         }
00627 
00628         // Override destination array since we're only going to get leaf boxes here
00629         mTouchedBoxes.Reset();
00630         mTouchedPrimitives = &mTouchedBoxes;
00631 
00632         // Now, do the actual query against leaf boxes
00633         if(!model.HasLeafNodes())
00634         {
00635                 if(model.IsQuantized())
00636                 {
00637                         const AABBQuantizedNoLeafTree* Tree = (const AABBQuantizedNoLeafTree*)model.GetTree();
00638 
00639                         // Setup dequantization coeffs
00640                         mCenterCoeff    = Tree->mCenterCoeff;
00641                         mExtentsCoeff   = Tree->mExtentsCoeff;
00642 
00643                         // Perform collision query - we don't want primitive tests here!
00644                         _CollideNoPrimitiveTest(Tree->GetNodes());
00645                 }
00646                 else
00647                 {
00648                         const AABBNoLeafTree* Tree = (const AABBNoLeafTree*)model.GetTree();
00649 
00650                         // Perform collision query - we don't want primitive tests here!
00651                         _CollideNoPrimitiveTest(Tree->GetNodes());
00652                 }
00653         }
00654         else
00655         {
00656                 if(model.IsQuantized())
00657                 {
00658                         const AABBQuantizedTree* Tree = (const AABBQuantizedTree*)model.GetTree();
00659 
00660                         // Setup dequantization coeffs
00661                         mCenterCoeff    = Tree->mCenterCoeff;
00662                         mExtentsCoeff   = Tree->mExtentsCoeff;
00663 
00664                         // Perform collision query - we don't want primitive tests here!
00665                         _CollideNoPrimitiveTest(Tree->GetNodes());
00666                 }
00667                 else
00668                 {
00669                         const AABBCollisionTree* Tree = (const AABBCollisionTree*)model.GetTree();
00670 
00671                         // Perform collision query - we don't want primitive tests here!
00672                         _CollideNoPrimitiveTest(Tree->GetNodes());
00673                 }
00674         }
00675 
00676         // We only have a list of boxes so far
00677         if(GetContactStatus())
00678         {
00679                 // Reset contact status, since it currently only reflects collisions with leaf boxes
00680                 Collider::InitQuery();
00681 
00682                 // Change dest container so that we can use built-in overlap tests and get collided primitives
00683                 cache.TouchedPrimitives.Reset();
00684                 mTouchedPrimitives = &cache.TouchedPrimitives;
00685 
00686                 // Read touched leaf boxes
00687                 udword Nb = mTouchedBoxes.GetNbEntries();
00688                 const udword* Touched = mTouchedBoxes.GetEntries();
00689 
00690                 const LeafTriangles* LT = model.GetLeafTriangles();
00691                 const udword* Indices = model.GetIndices();
00692 
00693                 // Loop through touched leaves
00694                 while(Nb--)
00695                 {
00696                         const LeafTriangles& CurrentLeaf = LT[*Touched++];
00697 
00698                         // Each leaf box has a set of triangles
00699                         udword NbTris = CurrentLeaf.GetNbTriangles();
00700                         if(Indices)
00701                         {
00702                                 const udword* T = &Indices[CurrentLeaf.GetTriangleIndex()];
00703 
00704                                 // Loop through triangles and test each of them
00705                                 while(NbTris--)
00706                                 {
00707                                         udword TriangleIndex = *T++;
00708                                         SPHERE_PRIM(TriangleIndex, OPC_CONTACT)
00709                                 }
00710                         }
00711                         else
00712                         {
00713                                 udword BaseIndex = CurrentLeaf.GetTriangleIndex();
00714 
00715                                 // Loop through triangles and test each of them
00716                                 while(NbTris--)
00717                                 {
00718                                         udword TriangleIndex = BaseIndex++;
00719                                         SPHERE_PRIM(TriangleIndex, OPC_CONTACT)
00720                                 }
00721                         }
00722                 }
00723         }
00724 
00725         return true;
00726 }


openhrp3
Author(s): AIST, General Robotix Inc., Nakamura Lab of Dept. of Mechano Informatics at University of Tokyo
autogenerated on Thu Apr 11 2019 03:30:18