Bullet Collision Detection & Physics Library
btConvexConvexAlgorithm.cpp
Go to the documentation of this file.
1 /*
2 Bullet Continuous Collision Detection and Physics Library
3 Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/
4 
5 This software is provided 'as-is', without any express or implied warranty.
6 In no event will the authors be held liable for any damages arising from the use of this software.
7 Permission is granted to anyone to use this software for any purpose,
8 including commercial applications, and to alter it and redistribute it freely,
9 subject to the following restrictions:
10 
11 1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required.
12 2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software.
13 3. This notice may not be removed or altered from any source distribution.
14 */
15 
19 //#define BT_DISABLE_CAPSULE_CAPSULE_COLLIDER 1
20 //#define ZERO_MARGIN
21 
23 
24 //#include <stdio.h>
32 
33 
34 
40 
45 
46 
47 
50 
52 
57 
59 
60 
61 
63  btVector3& ptsVector,
64  btVector3& offsetA,
65  btVector3& offsetB,
66  btScalar& tA, btScalar& tB,
67  const btVector3& translation,
68  const btVector3& dirA, btScalar hlenA,
69  const btVector3& dirB, btScalar hlenB )
70 {
71  // compute the parameters of the closest points on each line segment
72 
73  btScalar dirA_dot_dirB = btDot(dirA,dirB);
74  btScalar dirA_dot_trans = btDot(dirA,translation);
75  btScalar dirB_dot_trans = btDot(dirB,translation);
76 
77  btScalar denom = 1.0f - dirA_dot_dirB * dirA_dot_dirB;
78 
79  if ( denom == 0.0f ) {
80  tA = 0.0f;
81  } else {
82  tA = ( dirA_dot_trans - dirB_dot_trans * dirA_dot_dirB ) / denom;
83  if ( tA < -hlenA )
84  tA = -hlenA;
85  else if ( tA > hlenA )
86  tA = hlenA;
87  }
88 
89  tB = tA * dirA_dot_dirB - dirB_dot_trans;
90 
91  if ( tB < -hlenB ) {
92  tB = -hlenB;
93  tA = tB * dirA_dot_dirB + dirA_dot_trans;
94 
95  if ( tA < -hlenA )
96  tA = -hlenA;
97  else if ( tA > hlenA )
98  tA = hlenA;
99  } else if ( tB > hlenB ) {
100  tB = hlenB;
101  tA = tB * dirA_dot_dirB + dirA_dot_trans;
102 
103  if ( tA < -hlenA )
104  tA = -hlenA;
105  else if ( tA > hlenA )
106  tA = hlenA;
107  }
108 
109  // compute the closest points relative to segment centers.
110 
111  offsetA = dirA * tA;
112  offsetB = dirB * tB;
113 
114  ptsVector = translation - offsetA + offsetB;
115 }
116 
117 
119  btVector3& normalOnB,
120  btVector3& pointOnB,
121  btScalar capsuleLengthA,
122  btScalar capsuleRadiusA,
123  btScalar capsuleLengthB,
124  btScalar capsuleRadiusB,
125  int capsuleAxisA,
126  int capsuleAxisB,
127  const btTransform& transformA,
128  const btTransform& transformB,
129  btScalar distanceThreshold )
130 {
131  btVector3 directionA = transformA.getBasis().getColumn(capsuleAxisA);
132  btVector3 translationA = transformA.getOrigin();
133  btVector3 directionB = transformB.getBasis().getColumn(capsuleAxisB);
134  btVector3 translationB = transformB.getOrigin();
135 
136  // translation between centers
137 
138  btVector3 translation = translationB - translationA;
139 
140  // compute the closest points of the capsule line segments
141 
142  btVector3 ptsVector; // the vector between the closest points
143 
144  btVector3 offsetA, offsetB; // offsets from segment centers to their closest points
145  btScalar tA, tB; // parameters on line segment
146 
147  segmentsClosestPoints( ptsVector, offsetA, offsetB, tA, tB, translation,
148  directionA, capsuleLengthA, directionB, capsuleLengthB );
149 
150  btScalar distance = ptsVector.length() - capsuleRadiusA - capsuleRadiusB;
151 
152  if ( distance > distanceThreshold )
153  return distance;
154 
155  btScalar lenSqr = ptsVector.length2();
156  if (lenSqr<= (SIMD_EPSILON*SIMD_EPSILON))
157  {
158  //degenerate case where 2 capsules are likely at the same location: take a vector tangential to 'directionA'
159  btVector3 q;
160  btPlaneSpace1(directionA,normalOnB,q);
161  } else
162  {
163  // compute the contact normal
164  normalOnB = ptsVector*-btRecipSqrt(lenSqr);
165  }
166  pointOnB = transformB.getOrigin()+offsetB + normalOnB * capsuleRadiusB;
167 
168  return distance;
169 }
170 
171 
172 
173 
174 
175 
176 
178 
179 
180 
181 
182 
184 {
187  m_pdSolver = pdSolver;
188 }
189 
191 {
192 }
193 
194 btConvexConvexAlgorithm::btConvexConvexAlgorithm(btPersistentManifold* mf,const btCollisionAlgorithmConstructionInfo& ci,const btCollisionObjectWrapper* body0Wrap,const btCollisionObjectWrapper* body1Wrap,btConvexPenetrationDepthSolver* pdSolver,int numPerturbationIterations, int minimumPointsPerturbationThreshold)
195 : btActivatingCollisionAlgorithm(ci,body0Wrap,body1Wrap),
196 m_pdSolver(pdSolver),
197 m_ownManifold (false),
198 m_manifoldPtr(mf),
199 m_lowLevelOfDetail(false),
200 #ifdef USE_SEPDISTANCE_UTIL2
201 m_sepDistance((static_cast<btConvexShape*>(body0->getCollisionShape()))->getAngularMotionDisc(),
202  (static_cast<btConvexShape*>(body1->getCollisionShape()))->getAngularMotionDisc()),
203 #endif
204 m_numPerturbationIterations(numPerturbationIterations),
205 m_minimumPointsPerturbationThreshold(minimumPointsPerturbationThreshold)
206 {
207  (void)body0Wrap;
208  (void)body1Wrap;
209 }
210 
211 
212 
213 
215 {
216  if (m_ownManifold)
217  {
218  if (m_manifoldPtr)
220  }
221 }
222 
224 {
225  m_lowLevelOfDetail = useLowLevel;
226 }
227 
228 
230 {
237 
238 
239  btPerturbedContactResult(btManifoldResult* originalResult,const btTransform& transformA,const btTransform& transformB,const btTransform& unPerturbedTransform,bool perturbA,btIDebugDraw* debugDrawer)
240  :m_originalManifoldResult(originalResult),
241  m_transformA(transformA),
242  m_transformB(transformB),
243  m_unPerturbedTransform(unPerturbedTransform),
244  m_perturbA(perturbA),
245  m_debugDrawer(debugDrawer)
246  {
247  }
249  {
250  }
251 
252  virtual void addContactPoint(const btVector3& normalOnBInWorld,const btVector3& pointInWorld,btScalar orgDepth)
253  {
254  btVector3 endPt,startPt;
255  btScalar newDepth;
256  btVector3 newNormal;
257 
258  if (m_perturbA)
259  {
260  btVector3 endPtOrg = pointInWorld + normalOnBInWorld*orgDepth;
261  endPt = (m_unPerturbedTransform*m_transformA.inverse())(endPtOrg);
262  newDepth = (endPt - pointInWorld).dot(normalOnBInWorld);
263  startPt = endPt - normalOnBInWorld*newDepth;
264  } else
265  {
266  endPt = pointInWorld + normalOnBInWorld*orgDepth;
267  startPt = (m_unPerturbedTransform*m_transformB.inverse())(pointInWorld);
268  newDepth = (endPt - startPt).dot(normalOnBInWorld);
269 
270  }
271 
272 //#define DEBUG_CONTACTS 1
273 #ifdef DEBUG_CONTACTS
274  m_debugDrawer->drawLine(startPt,endPt,btVector3(1,0,0));
275  m_debugDrawer->drawSphere(startPt,0.05,btVector3(0,1,0));
276  m_debugDrawer->drawSphere(endPt,0.05,btVector3(0,0,1));
277 #endif //DEBUG_CONTACTS
278 
279 
280  m_originalManifoldResult->addContactPoint(normalOnBInWorld,startPt,newDepth);
281  }
282 
283 };
284 
286 
287 
288 //
289 // Convex-Convex collision algorithm
290 //
292 {
293 
294  if (!m_manifoldPtr)
295  {
296  //swapped?
298  m_ownManifold = true;
299  }
301 
302  //comment-out next line to test multi-contact generation
303  //resultOut->getPersistentManifold()->clearManifold();
304 
305 
306  const btConvexShape* min0 = static_cast<const btConvexShape*>(body0Wrap->getCollisionShape());
307  const btConvexShape* min1 = static_cast<const btConvexShape*>(body1Wrap->getCollisionShape());
308 
309  btVector3 normalOnB;
310  btVector3 pointOnBWorld;
311 #ifndef BT_DISABLE_CAPSULE_CAPSULE_COLLIDER
313  {
314  //m_manifoldPtr->clearManifold();
315 
316  btCapsuleShape* capsuleA = (btCapsuleShape*) min0;
317  btCapsuleShape* capsuleB = (btCapsuleShape*) min1;
318 
320 
321  btScalar dist = capsuleCapsuleDistance(normalOnB, pointOnBWorld,capsuleA->getHalfHeight(),capsuleA->getRadius(),
322  capsuleB->getHalfHeight(),capsuleB->getRadius(),capsuleA->getUpAxis(),capsuleB->getUpAxis(),
323  body0Wrap->getWorldTransform(),body1Wrap->getWorldTransform(),threshold);
324 
325  if (dist<threshold)
326  {
327  btAssert(normalOnB.length2()>=(SIMD_EPSILON*SIMD_EPSILON));
328  resultOut->addContactPoint(normalOnB,pointOnBWorld,dist);
329  }
330  resultOut->refreshContactPoints();
331  return;
332  }
333 
335  {
336  //m_manifoldPtr->clearManifold();
337 
338  btCapsuleShape* capsuleA = (btCapsuleShape*) min0;
339  btSphereShape* capsuleB = (btSphereShape*) min1;
340 
342 
343  btScalar dist = capsuleCapsuleDistance(normalOnB, pointOnBWorld,capsuleA->getHalfHeight(),capsuleA->getRadius(),
344  0.,capsuleB->getRadius(),capsuleA->getUpAxis(),1,
345  body0Wrap->getWorldTransform(),body1Wrap->getWorldTransform(),threshold);
346 
347  if (dist<threshold)
348  {
349  btAssert(normalOnB.length2()>=(SIMD_EPSILON*SIMD_EPSILON));
350  resultOut->addContactPoint(normalOnB,pointOnBWorld,dist);
351  }
352  resultOut->refreshContactPoints();
353  return;
354  }
355 
357  {
358  //m_manifoldPtr->clearManifold();
359 
360  btSphereShape* capsuleA = (btSphereShape*) min0;
361  btCapsuleShape* capsuleB = (btCapsuleShape*) min1;
362 
364 
365  btScalar dist = capsuleCapsuleDistance(normalOnB, pointOnBWorld,0.,capsuleA->getRadius(),
366  capsuleB->getHalfHeight(),capsuleB->getRadius(),1,capsuleB->getUpAxis(),
367  body0Wrap->getWorldTransform(),body1Wrap->getWorldTransform(),threshold);
368 
369  if (dist<threshold)
370  {
371  btAssert(normalOnB.length2()>=(SIMD_EPSILON*SIMD_EPSILON));
372  resultOut->addContactPoint(normalOnB,pointOnBWorld,dist);
373  }
374  resultOut->refreshContactPoints();
375  return;
376  }
377 #endif //BT_DISABLE_CAPSULE_CAPSULE_COLLIDER
378 
379 
380 
381 
382 #ifdef USE_SEPDISTANCE_UTIL2
383  if (dispatchInfo.m_useConvexConservativeDistanceUtil)
384  {
385  m_sepDistance.updateSeparatingDistance(body0->getWorldTransform(),body1->getWorldTransform());
386  }
387 
388  if (!dispatchInfo.m_useConvexConservativeDistanceUtil || m_sepDistance.getConservativeSeparatingDistance()<=0.f)
389 #endif //USE_SEPDISTANCE_UTIL2
390 
391  {
392 
393 
395  btVoronoiSimplexSolver simplexSolver;
396  btGjkPairDetector gjkPairDetector( min0, min1, &simplexSolver, m_pdSolver );
397  //TODO: if (dispatchInfo.m_useContinuous)
398  gjkPairDetector.setMinkowskiA(min0);
399  gjkPairDetector.setMinkowskiB(min1);
400 
401 #ifdef USE_SEPDISTANCE_UTIL2
402  if (dispatchInfo.m_useConvexConservativeDistanceUtil)
403  {
405  } else
406 #endif //USE_SEPDISTANCE_UTIL2
407  {
408  //if (dispatchInfo.m_convexMaxDistanceUseCPT)
409  //{
410  // input.m_maximumDistanceSquared = min0->getMargin() + min1->getMargin() + m_manifoldPtr->getContactProcessingThreshold();
411  //} else
412  //{
414 // }
415 
417  }
418 
419  input.m_transformA = body0Wrap->getWorldTransform();
420  input.m_transformB = body1Wrap->getWorldTransform();
421 
422 
423 
424 
425 
426 #ifdef USE_SEPDISTANCE_UTIL2
427  btScalar sepDist = 0.f;
428  if (dispatchInfo.m_useConvexConservativeDistanceUtil)
429  {
430  sepDist = gjkPairDetector.getCachedSeparatingDistance();
431  if (sepDist>SIMD_EPSILON)
432  {
433  sepDist += dispatchInfo.m_convexConservativeDistanceThreshold;
434  //now perturbe directions to get multiple contact points
435 
436  }
437  }
438 #endif //USE_SEPDISTANCE_UTIL2
439 
440  if (min0->isPolyhedral() && min1->isPolyhedral())
441  {
442 
443 
444  struct btDummyResult : public btDiscreteCollisionDetectorInterface::Result
445  {
446  btVector3 m_normalOnBInWorld;
447  btVector3 m_pointInWorld;
448  btScalar m_depth;
449  bool m_hasContact;
450 
451 
452  btDummyResult()
453  : m_hasContact(false)
454  {
455  }
456 
457 
458  virtual void setShapeIdentifiersA(int partId0,int index0){}
459  virtual void setShapeIdentifiersB(int partId1,int index1){}
460  virtual void addContactPoint(const btVector3& normalOnBInWorld,const btVector3& pointInWorld,btScalar depth)
461  {
462  m_hasContact = true;
463  m_normalOnBInWorld = normalOnBInWorld;
464  m_pointInWorld = pointInWorld;
465  m_depth = depth;
466  }
467  };
468 
469 
470  struct btWithoutMarginResult : public btDiscreteCollisionDetectorInterface::Result
471  {
473  btVector3 m_reportedNormalOnWorld;
474  btScalar m_marginOnA;
475  btScalar m_marginOnB;
476  btScalar m_reportedDistance;
477 
478  bool m_foundResult;
479  btWithoutMarginResult(btDiscreteCollisionDetectorInterface::Result* result, btScalar marginOnA, btScalar marginOnB)
480  :m_originalResult(result),
481  m_marginOnA(marginOnA),
482  m_marginOnB(marginOnB),
483  m_foundResult(false)
484  {
485  }
486 
487  virtual void setShapeIdentifiersA(int partId0,int index0){}
488  virtual void setShapeIdentifiersB(int partId1,int index1){}
489  virtual void addContactPoint(const btVector3& normalOnBInWorld,const btVector3& pointInWorldOrg,btScalar depthOrg)
490  {
491  m_reportedDistance = depthOrg;
492  m_reportedNormalOnWorld = normalOnBInWorld;
493 
494  btVector3 adjustedPointB = pointInWorldOrg - normalOnBInWorld*m_marginOnB;
495  m_reportedDistance = depthOrg+(m_marginOnA+m_marginOnB);
496  if (m_reportedDistance<0.f)
497  {
498  m_foundResult = true;
499  }
500  m_originalResult->addContactPoint(normalOnBInWorld,adjustedPointB,m_reportedDistance);
501  }
502  };
503 
504 
505  btDummyResult dummy;
506 
508 
509  btScalar min0Margin = min0->getShapeType()==BOX_SHAPE_PROXYTYPE? 0.f : min0->getMargin();
510  btScalar min1Margin = min1->getShapeType()==BOX_SHAPE_PROXYTYPE? 0.f : min1->getMargin();
511 
512  btWithoutMarginResult withoutMargin(resultOut, min0Margin,min1Margin);
513 
514  btPolyhedralConvexShape* polyhedronA = (btPolyhedralConvexShape*) min0;
515  btPolyhedralConvexShape* polyhedronB = (btPolyhedralConvexShape*) min1;
516  if (polyhedronA->getConvexPolyhedron() && polyhedronB->getConvexPolyhedron())
517  {
518 
519 
520 
521 
523 
524  btScalar minDist = -1e30f;
525  btVector3 sepNormalWorldSpace;
526  bool foundSepAxis = true;
527 
528  if (dispatchInfo.m_enableSatConvex)
529  {
531  *polyhedronA->getConvexPolyhedron(), *polyhedronB->getConvexPolyhedron(),
532  body0Wrap->getWorldTransform(),
533  body1Wrap->getWorldTransform(),
534  sepNormalWorldSpace,*resultOut);
535  } else
536  {
537 #ifdef ZERO_MARGIN
538  gjkPairDetector.setIgnoreMargin(true);
539  gjkPairDetector.getClosestPoints(input,*resultOut,dispatchInfo.m_debugDraw);
540 #else
541 
542 
543  gjkPairDetector.getClosestPoints(input,withoutMargin,dispatchInfo.m_debugDraw);
544  //gjkPairDetector.getClosestPoints(input,dummy,dispatchInfo.m_debugDraw);
545 #endif //ZERO_MARGIN
546  //btScalar l2 = gjkPairDetector.getCachedSeparatingAxis().length2();
547  //if (l2>SIMD_EPSILON)
548  {
549  sepNormalWorldSpace = withoutMargin.m_reportedNormalOnWorld;//gjkPairDetector.getCachedSeparatingAxis()*(1.f/l2);
550  //minDist = -1e30f;//gjkPairDetector.getCachedSeparatingDistance();
551  minDist = withoutMargin.m_reportedDistance;//gjkPairDetector.getCachedSeparatingDistance()+min0->getMargin()+min1->getMargin();
552 
553 #ifdef ZERO_MARGIN
554  foundSepAxis = true;//gjkPairDetector.getCachedSeparatingDistance()<0.f;
555 #else
556  foundSepAxis = withoutMargin.m_foundResult && minDist<0;//-(min0->getMargin()+min1->getMargin());
557 #endif
558  }
559  }
560  if (foundSepAxis)
561  {
562 
563 // printf("sepNormalWorldSpace=%f,%f,%f\n",sepNormalWorldSpace.getX(),sepNormalWorldSpace.getY(),sepNormalWorldSpace.getZ());
564 
565  worldVertsB1.resize(0);
566  btPolyhedralContactClipping::clipHullAgainstHull(sepNormalWorldSpace, *polyhedronA->getConvexPolyhedron(), *polyhedronB->getConvexPolyhedron(),
567  body0Wrap->getWorldTransform(),
568  body1Wrap->getWorldTransform(), minDist-threshold, threshold, worldVertsB1,worldVertsB2,
569  *resultOut);
570 
571  }
572  if (m_ownManifold)
573  {
574  resultOut->refreshContactPoints();
575  }
576  return;
577 
578  } else
579  {
580 
581 
582  //we can also deal with convex versus triangle (without connectivity data)
583  if (dispatchInfo.m_enableSatConvex && polyhedronA->getConvexPolyhedron() && polyhedronB->getShapeType()==TRIANGLE_SHAPE_PROXYTYPE)
584  {
585 
586 
587  btVertexArray worldSpaceVertices;
588  btTriangleShape* tri = (btTriangleShape*)polyhedronB;
589  worldSpaceVertices.push_back( body1Wrap->getWorldTransform()*tri->m_vertices1[0]);
590  worldSpaceVertices.push_back( body1Wrap->getWorldTransform()*tri->m_vertices1[1]);
591  worldSpaceVertices.push_back( body1Wrap->getWorldTransform()*tri->m_vertices1[2]);
592 
593  //tri->initializePolyhedralFeatures();
594 
596 
597  btVector3 sepNormalWorldSpace;
598  btScalar minDist =-1e30f;
599  btScalar maxDist = threshold;
600 
601  bool foundSepAxis = false;
602  bool useSatSepNormal = true;
603 
604  if (useSatSepNormal)
605  {
606 #if 0
607  if (0)
608  {
609  //initializePolyhedralFeatures performs a convex hull computation, not needed for a single triangle
610  polyhedronB->initializePolyhedralFeatures();
611  } else
612 #endif
613  {
614 
615  btVector3 uniqueEdges[3] = {tri->m_vertices1[1]-tri->m_vertices1[0],
616  tri->m_vertices1[2]-tri->m_vertices1[1],
617  tri->m_vertices1[0]-tri->m_vertices1[2]};
618 
619  uniqueEdges[0].normalize();
620  uniqueEdges[1].normalize();
621  uniqueEdges[2].normalize();
622 
623  btConvexPolyhedron polyhedron;
624  polyhedron.m_vertices.push_back(tri->m_vertices1[2]);
625  polyhedron.m_vertices.push_back(tri->m_vertices1[0]);
626  polyhedron.m_vertices.push_back(tri->m_vertices1[1]);
627 
628 
629  {
630  btFace combinedFaceA;
631  combinedFaceA.m_indices.push_back(0);
632  combinedFaceA.m_indices.push_back(1);
633  combinedFaceA.m_indices.push_back(2);
634  btVector3 faceNormal = uniqueEdges[0].cross(uniqueEdges[1]);
635  faceNormal.normalize();
636  btScalar planeEq=1e30f;
637  for (int v=0;v<combinedFaceA.m_indices.size();v++)
638  {
639  btScalar eq = tri->m_vertices1[combinedFaceA.m_indices[v]].dot(faceNormal);
640  if (planeEq>eq)
641  {
642  planeEq=eq;
643  }
644  }
645  combinedFaceA.m_plane[0] = faceNormal[0];
646  combinedFaceA.m_plane[1] = faceNormal[1];
647  combinedFaceA.m_plane[2] = faceNormal[2];
648  combinedFaceA.m_plane[3] = -planeEq;
649  polyhedron.m_faces.push_back(combinedFaceA);
650  }
651  {
652  btFace combinedFaceB;
653  combinedFaceB.m_indices.push_back(0);
654  combinedFaceB.m_indices.push_back(2);
655  combinedFaceB.m_indices.push_back(1);
656  btVector3 faceNormal = -uniqueEdges[0].cross(uniqueEdges[1]);
657  faceNormal.normalize();
658  btScalar planeEq=1e30f;
659  for (int v=0;v<combinedFaceB.m_indices.size();v++)
660  {
661  btScalar eq = tri->m_vertices1[combinedFaceB.m_indices[v]].dot(faceNormal);
662  if (planeEq>eq)
663  {
664  planeEq=eq;
665  }
666  }
667 
668  combinedFaceB.m_plane[0] = faceNormal[0];
669  combinedFaceB.m_plane[1] = faceNormal[1];
670  combinedFaceB.m_plane[2] = faceNormal[2];
671  combinedFaceB.m_plane[3] = -planeEq;
672  polyhedron.m_faces.push_back(combinedFaceB);
673  }
674 
675 
676  polyhedron.m_uniqueEdges.push_back(uniqueEdges[0]);
677  polyhedron.m_uniqueEdges.push_back(uniqueEdges[1]);
678  polyhedron.m_uniqueEdges.push_back(uniqueEdges[2]);
679  polyhedron.initialize2();
680 
681  polyhedronB->setPolyhedralFeatures(polyhedron);
682  }
683 
684 
685 
687  *polyhedronA->getConvexPolyhedron(), *polyhedronB->getConvexPolyhedron(),
688  body0Wrap->getWorldTransform(),
689  body1Wrap->getWorldTransform(),
690  sepNormalWorldSpace,*resultOut);
691  // printf("sepNormalWorldSpace=%f,%f,%f\n",sepNormalWorldSpace.getX(),sepNormalWorldSpace.getY(),sepNormalWorldSpace.getZ());
692 
693  }
694  else
695  {
696 #ifdef ZERO_MARGIN
697  gjkPairDetector.setIgnoreMargin(true);
698  gjkPairDetector.getClosestPoints(input,*resultOut,dispatchInfo.m_debugDraw);
699 #else
700  gjkPairDetector.getClosestPoints(input,dummy,dispatchInfo.m_debugDraw);
701 #endif//ZERO_MARGIN
702 
703  if (dummy.m_hasContact && dummy.m_depth<0)
704  {
705 
706  if (foundSepAxis)
707  {
708  if (dummy.m_normalOnBInWorld.dot(sepNormalWorldSpace)<0.99)
709  {
710  printf("?\n");
711  }
712  } else
713  {
714  printf("!\n");
715  }
716  sepNormalWorldSpace.setValue(0,0,1);// = dummy.m_normalOnBInWorld;
717  //minDist = dummy.m_depth;
718  foundSepAxis = true;
719  }
720 #if 0
721  btScalar l2 = gjkPairDetector.getCachedSeparatingAxis().length2();
722  if (l2>SIMD_EPSILON)
723  {
724  sepNormalWorldSpace = gjkPairDetector.getCachedSeparatingAxis()*(1.f/l2);
725  //minDist = gjkPairDetector.getCachedSeparatingDistance();
726  //maxDist = threshold;
727  minDist = gjkPairDetector.getCachedSeparatingDistance()-min0->getMargin()-min1->getMargin();
728  foundSepAxis = true;
729  }
730 #endif
731  }
732 
733 
734  if (foundSepAxis)
735  {
736  worldVertsB2.resize(0);
737  btPolyhedralContactClipping::clipFaceAgainstHull(sepNormalWorldSpace, *polyhedronA->getConvexPolyhedron(),
738  body0Wrap->getWorldTransform(), worldSpaceVertices, worldVertsB2,minDist-threshold, maxDist, *resultOut);
739  }
740 
741 
742  if (m_ownManifold)
743  {
744  resultOut->refreshContactPoints();
745  }
746 
747  return;
748  }
749 
750 
751  }
752 
753 
754  }
755 
756  gjkPairDetector.getClosestPoints(input,*resultOut,dispatchInfo.m_debugDraw);
757 
758  //now perform 'm_numPerturbationIterations' collision queries with the perturbated collision objects
759 
760  //perform perturbation when more then 'm_minimumPointsPerturbationThreshold' points
762  {
763 
764  int i;
765  btVector3 v0,v1;
766  btVector3 sepNormalWorldSpace;
767  btScalar l2 = gjkPairDetector.getCachedSeparatingAxis().length2();
768 
769  if (l2>SIMD_EPSILON)
770  {
771  sepNormalWorldSpace = gjkPairDetector.getCachedSeparatingAxis()*(1.f/l2);
772 
773  btPlaneSpace1(sepNormalWorldSpace,v0,v1);
774 
775 
776  bool perturbeA = true;
777  const btScalar angleLimit = 0.125f * SIMD_PI;
778  btScalar perturbeAngle;
779  btScalar radiusA = min0->getAngularMotionDisc();
780  btScalar radiusB = min1->getAngularMotionDisc();
781  if (radiusA < radiusB)
782  {
783  perturbeAngle = gContactBreakingThreshold /radiusA;
784  perturbeA = true;
785  } else
786  {
787  perturbeAngle = gContactBreakingThreshold / radiusB;
788  perturbeA = false;
789  }
790  if ( perturbeAngle > angleLimit )
791  perturbeAngle = angleLimit;
792 
793  btTransform unPerturbedTransform;
794  if (perturbeA)
795  {
796  unPerturbedTransform = input.m_transformA;
797  } else
798  {
799  unPerturbedTransform = input.m_transformB;
800  }
801 
802  for ( i=0;i<m_numPerturbationIterations;i++)
803  {
804  if (v0.length2()>SIMD_EPSILON)
805  {
806  btQuaternion perturbeRot(v0,perturbeAngle);
807  btScalar iterationAngle = i*(SIMD_2_PI/btScalar(m_numPerturbationIterations));
808  btQuaternion rotq(sepNormalWorldSpace,iterationAngle);
809 
810 
811  if (perturbeA)
812  {
813  input.m_transformA.setBasis( btMatrix3x3(rotq.inverse()*perturbeRot*rotq)*body0Wrap->getWorldTransform().getBasis());
814  input.m_transformB = body1Wrap->getWorldTransform();
815  #ifdef DEBUG_CONTACTS
816  dispatchInfo.m_debugDraw->drawTransform(input.m_transformA,10.0);
817  #endif //DEBUG_CONTACTS
818  } else
819  {
820  input.m_transformA = body0Wrap->getWorldTransform();
821  input.m_transformB.setBasis( btMatrix3x3(rotq.inverse()*perturbeRot*rotq)*body1Wrap->getWorldTransform().getBasis());
822  #ifdef DEBUG_CONTACTS
823  dispatchInfo.m_debugDraw->drawTransform(input.m_transformB,10.0);
824  #endif
825  }
826 
827  btPerturbedContactResult perturbedResultOut(resultOut,input.m_transformA,input.m_transformB,unPerturbedTransform,perturbeA,dispatchInfo.m_debugDraw);
828  gjkPairDetector.getClosestPoints(input,perturbedResultOut,dispatchInfo.m_debugDraw);
829  }
830  }
831  }
832  }
833 
834 
835 
836 #ifdef USE_SEPDISTANCE_UTIL2
837  if (dispatchInfo.m_useConvexConservativeDistanceUtil && (sepDist>SIMD_EPSILON))
838  {
839  m_sepDistance.initSeparatingDistance(gjkPairDetector.getCachedSeparatingAxis(),sepDist,body0->getWorldTransform(),body1->getWorldTransform());
840  }
841 #endif //USE_SEPDISTANCE_UTIL2
842 
843 
844  }
845 
846  if (m_ownManifold)
847  {
848  resultOut->refreshContactPoints();
849  }
850 
851 }
852 
853 
854 
855 bool disableCcd = false;
857 {
858  (void)resultOut;
859  (void)dispatchInfo;
861 
864  btScalar resultFraction = btScalar(1.);
865 
866 
867  btScalar squareMot0 = (col0->getInterpolationWorldTransform().getOrigin() - col0->getWorldTransform().getOrigin()).length2();
868  btScalar squareMot1 = (col1->getInterpolationWorldTransform().getOrigin() - col1->getWorldTransform().getOrigin()).length2();
869 
870  if (squareMot0 < col0->getCcdSquareMotionThreshold() &&
871  squareMot1 < col1->getCcdSquareMotionThreshold())
872  return resultFraction;
873 
874  if (disableCcd)
875  return btScalar(1.);
876 
877 
878  //An adhoc way of testing the Continuous Collision Detection algorithms
879  //One object is approximated as a sphere, to simplify things
880  //Starting in penetration should report no time of impact
881  //For proper CCD, better accuracy and handling of 'allowed' penetration should be added
882  //also the mainloop of the physics should have a kind of toi queue (something like Brian Mirtich's application of Timewarp for Rigidbodies)
883 
884 
886  {
887  btConvexShape* convex0 = static_cast<btConvexShape*>(col0->getCollisionShape());
888 
889  btSphereShape sphere1(col1->getCcdSweptSphereRadius()); //todo: allow non-zero sphere sizes, for better approximation
891  btVoronoiSimplexSolver voronoiSimplex;
892  //SubsimplexConvexCast ccd0(&sphere,min0,&voronoiSimplex);
894  btGjkConvexCast ccd1( convex0 ,&sphere1,&voronoiSimplex);
895  //ContinuousConvexCollision ccd(min0,min1,&voronoiSimplex,0);
897  col1->getWorldTransform(),col1->getInterpolationWorldTransform(),result))
898  {
899 
900  //store result.m_fraction in both bodies
901 
902  if (col0->getHitFraction()> result.m_fraction)
903  col0->setHitFraction( result.m_fraction );
904 
905  if (col1->getHitFraction() > result.m_fraction)
906  col1->setHitFraction( result.m_fraction);
907 
908  if (resultFraction > result.m_fraction)
909  resultFraction = result.m_fraction;
910 
911  }
912 
913 
914 
915 
916  }
917 
919  {
920  btConvexShape* convex1 = static_cast<btConvexShape*>(col1->getCollisionShape());
921 
922  btSphereShape sphere0(col0->getCcdSweptSphereRadius()); //todo: allow non-zero sphere sizes, for better approximation
924  btVoronoiSimplexSolver voronoiSimplex;
925  //SubsimplexConvexCast ccd0(&sphere,min0,&voronoiSimplex);
927  btGjkConvexCast ccd1(&sphere0,convex1,&voronoiSimplex);
928  //ContinuousConvexCollision ccd(min0,min1,&voronoiSimplex,0);
930  col1->getWorldTransform(),col1->getInterpolationWorldTransform(),result))
931  {
932 
933  //store result.m_fraction in both bodies
934 
935  if (col0->getHitFraction() > result.m_fraction)
936  col0->setHitFraction( result.m_fraction);
937 
938  if (col1->getHitFraction() > result.m_fraction)
939  col1->setHitFraction( result.m_fraction);
940 
941  if (resultFraction > result.m_fraction)
942  resultFraction = result.m_fraction;
943 
944  }
945  }
946 
947  return resultFraction;
948 
949 }
950 
virtual void releaseManifold(btPersistentManifold *manifold)=0
#define SIMD_EPSILON
Definition: btScalar.h:521
const btPersistentManifold * getPersistentManifold() const
btAlignedObjectArray< btVector3 > m_vertices
btPersistentManifold is a contact point cache, it stays persistent as long as objects are overlapping...
void push_back(const T &_Val)
int getShapeType() const
#define BT_LARGE_FLOAT
Definition: btScalar.h:294
btScalar getCcdSweptSphereRadius() const
Swept sphere radius (0.0 by default), see btConvexConvexAlgorithm::
void setValue(const btScalar &_x, const btScalar &_y, const btScalar &_z)
Definition: btVector3.h:652
btScalar getContactBreakingThreshold() const
ConvexPenetrationDepthSolver provides an interface for penetration depth calculation.
virtual void processCollision(const btCollisionObjectWrapper *body0Wrap, const btCollisionObjectWrapper *body1Wrap, const btDispatcherInfo &dispatchInfo, btManifoldResult *resultOut)
static void clipFaceAgainstHull(const btVector3 &separatingNormal, const btConvexPolyhedron &hullA, const btTransform &transA, btVertexArray &worldVertsB1, btVertexArray &worldVertsB2, const btScalar minDist, btScalar maxDist, btDiscreteCollisionDetectorInterface::Result &resultOut)
btScalar getCachedSeparatingDistance() const
void setMinkowskiB(const btConvexShape *minkB)
btScalar m_convexConservativeDistanceThreshold
Definition: btDispatcher.h:65
void setBasis(const btMatrix3x3 &basis)
Set the rotational element by btMatrix3x3.
Definition: btTransform.h:159
virtual void drawLine(const btVector3 &from, const btVector3 &to, const btVector3 &color)=0
void setPersistentManifold(btPersistentManifold *manifoldPtr)
The btCapsuleShape represents a capsule around the Y axis, there is also the btCapsuleShapeX aligned ...
static void segmentsClosestPoints(btVector3 &ptsVector, btVector3 &offsetA, btVector3 &offsetB, btScalar &tA, btScalar &tB, const btVector3 &translation, const btVector3 &dirA, btScalar hlenA, const btVector3 &dirB, btScalar hlenB)
Specialized capsule-capsule collision algorithm has been added for Bullet 2.75 release to increase ra...
void btPlaneSpace1(const T &n, T &p, T &q)
Definition: btVector3.h:1284
#define btAssert(x)
Definition: btScalar.h:131
This class is not enabled yet (work-in-progress) to more aggressively activate objects.
void setHitFraction(btScalar hitFraction)
void setMinkowskiA(const btConvexShape *minkA)
static btScalar capsuleCapsuleDistance(btVector3 &normalOnB, btVector3 &pointOnB, btScalar capsuleLengthA, btScalar capsuleRadiusA, btScalar capsuleLengthB, btScalar capsuleRadiusB, int capsuleAxisA, int capsuleAxisB, const btTransform &transformA, const btTransform &transformB, btScalar distanceThreshold)
#define SIMD_FORCE_INLINE
Definition: btScalar.h:81
The btSphereShape implements an implicit sphere, centered around a local origin with radius...
Definition: btSphereShape.h:22
btPersistentManifold * m_manifoldPtr
btAlignedObjectArray< btVector3 > m_uniqueEdges
btScalar getRadius() const
bool m_useConvexConservativeDistanceUtil
Definition: btDispatcher.h:64
btManifoldResult is a helper class to manage contact results.
btVector3 getColumn(int i) const
Get a column of the matrix as a vector.
Definition: btMatrix3x3.h:134
class btIDebugDraw * m_debugDraw
Definition: btDispatcher.h:59
btConvexConvexAlgorithm(btPersistentManifold *mf, const btCollisionAlgorithmConstructionInfo &ci, const btCollisionObjectWrapper *body0Wrap, const btCollisionObjectWrapper *body1Wrap, btConvexPenetrationDepthSolver *pdSolver, int numPerturbationIterations, int minimumPointsPerturbationThreshold)
cache separating vector to speedup collision detection
int getUpAxis() const
btScalar dot(const btVector3 &v) const
Return the dot product.
Definition: btVector3.h:235
btVector3 & normalize()
Normalize this vector x^2 + y^2 + z^2 = 1.
Definition: btVector3.h:309
virtual void addContactPoint(const btVector3 &normalOnBInWorld, const btVector3 &pointInWorld, btScalar orgDepth)
btScalar getCcdSquareMotionThreshold() const
The btConvexShape is an abstract shape interface, implemented by all convex shapes such as btBoxShape...
Definition: btConvexShape.h:31
const btTransform & getInterpolationWorldTransform() const
GjkConvexCast performs a raycast on a convex object using support mapping.
const btVector3 & getCachedSeparatingAxis() const
void setLowLevelOfDetail(bool useLowLevel)
virtual void addContactPoint(const btVector3 &normalOnBInWorld, const btVector3 &pointInWorld, btScalar depth)
virtual bool calcTimeOfImpact(const btTransform &fromA, const btTransform &toA, const btTransform &fromB, const btTransform &toB, CastResult &result)
cast a convex against another convex object
#define SIMD_PI
Definition: btScalar.h:504
btTransform & getWorldTransform()
RayResult stores the closest result alternatively, add a callback method to decide about closest/all ...
Definition: btConvexCast.h:36
btScalar m_closestPointDistanceThreshold
#define SIMD_2_PI
Definition: btScalar.h:505
btAlignedObjectArray< int > m_indices
int size() const
return the number of elements in the array
btVector3 & getOrigin()
Return the origin vector translation.
Definition: btTransform.h:117
btVoronoiSimplexSolver is an implementation of the closest point distance algorithm from a 1-4 points...
btAlignedObjectArray< btFace > m_faces
const btConvexPolyhedron * getConvexPolyhedron() const
virtual bool initializePolyhedralFeatures(int shiftVerticesByMargin=0)
optional method mainly used to generate multiple contact points by clipping polyhedral features (face...
btScalar gContactBreakingThreshold
btVector3 cross(const btVector3 &v) const
Return the cross product between this and another vector.
Definition: btVector3.h:389
const btTransform & getWorldTransform() const
btCollisionObject can be used to manage collision detection objects.
btMatrix3x3 & getBasis()
Return the basis matrix for the rotation.
Definition: btTransform.h:112
The btPolyhedralConvexShape is an internal interface class for polyhedral convex shapes.
#define btRecipSqrt(x)
Definition: btScalar.h:510
The btIDebugDraw interface class allows hooking up a debug renderer to visually debug simulations...
Definition: btIDebugDraw.h:29
btScalar length() const
Return the length of the vector.
Definition: btVector3.h:263
virtual btPersistentManifold * getNewManifold(const btCollisionObject *b0, const btCollisionObject *b1)=0
btTransform inverse() const
Return the inverse of this transform.
Definition: btTransform.h:188
CreateFunc(btConvexPenetrationDepthSolver *pdSolver)
virtual btScalar getMargin() const =0
btPerturbedContactResult(btManifoldResult *originalResult, const btTransform &transformA, const btTransform &transformB, const btTransform &unPerturbedTransform, bool perturbA, btIDebugDraw *debugDrawer)
const btCollisionShape * getCollisionShape() const
virtual btScalar getAngularMotionDisc() const
getAngularMotionDisc returns the maximum radius needed for Conservative Advancement to handle time-of...
btScalar getHitFraction() const
btVector3 can be used to represent 3D points and vectors.
Definition: btVector3.h:83
btScalar length2() const
Return the length of the vector squared.
Definition: btVector3.h:257
The btTransform class supports rigid transforms with only translation and rotation and no scaling/she...
Definition: btTransform.h:34
virtual void addContactPoint(const btVector3 &normalOnBInWorld, const btVector3 &pointInWorld, btScalar depth)=0
bool isPolyhedral() const
virtual btScalar calculateTimeOfImpact(btCollisionObject *body0, btCollisionObject *body1, const btDispatcherInfo &dispatchInfo, btManifoldResult *resultOut)
btScalar m_plane[4]
virtual void drawTransform(const btTransform &transform, btScalar orthoLen)
Definition: btIDebugDraw.h:166
void resize(int newsize, const T &fillData=T())
static bool findSeparatingAxis(const btConvexPolyhedron &hullA, const btConvexPolyhedron &hullB, const btTransform &transA, const btTransform &transB, btVector3 &sep, btDiscreteCollisionDetectorInterface::Result &resultOut)
btGjkPairDetector uses GJK to implement the btDiscreteCollisionDetectorInterface
static void clipHullAgainstHull(const btVector3 &separatingNormal1, const btConvexPolyhedron &hullA, const btConvexPolyhedron &hullB, const btTransform &transA, const btTransform &transB, const btScalar minDist, btScalar maxDist, btVertexArray &worldVertsB1, btVertexArray &worldVertsB2, btDiscreteCollisionDetectorInterface::Result &resultOut)
btConvexPenetrationDepthSolver * m_pdSolver
btScalar getRadius() const
Definition: btSphereShape.h:50
The btMatrix3x3 class implements a 3x3 rotation matrix, to perform linear algebra in combination with...
Definition: btMatrix3x3.h:48
btScalar dot(const btQuaternion &q1, const btQuaternion &q2)
Calculate the dot product between two quaternions.
Definition: btQuaternion.h:898
The btQuaternion implements quaternion to perform linear algebra rotations in combination with btMatr...
Definition: btQuaternion.h:55
btScalar btDot(const btVector3 &v1, const btVector3 &v2)
Return the dot product between two vectors.
Definition: btVector3.h:903
btManifoldResult * m_originalManifoldResult
btScalar getHalfHeight() const
const btCollisionShape * getCollisionShape() const
virtual void drawSphere(btScalar radius, const btTransform &transform, const btVector3 &color)
Definition: btIDebugDraw.h:93
btVector3 m_vertices1[3]
virtual void setPolyhedralFeatures(btConvexPolyhedron &polyhedron)
btConvexPenetrationDepthSolver * m_pdSolver
float btScalar
The btScalar type abstracts floating point numbers, to easily switch between double and single floati...
Definition: btScalar.h:292
virtual void getClosestPoints(const ClosestPointInput &input, Result &output, class btIDebugDraw *debugDraw, bool swapResults=false)
const btCollisionObject * getCollisionObject() const
void setIgnoreMargin(bool ignoreMargin)
don&#39;t use setIgnoreMargin, it&#39;s for Bullet&#39;s internal use