29 #include <BulletCollision/NarrowPhaseCollision/btDiscreteCollisionDetectorInterface.h>
30 #include <BulletCollision/BroadphaseCollision/btBroadphaseInterface.h>
31 #include <BulletCollision/CollisionDispatch/btCollisionObject.h>
32 #include <BulletCollision/CollisionShapes/btConvexShape.h>
33 #include <BulletCollision/CollisionShapes/btCapsuleShape.h>
34 #include <BulletCollision/CollisionShapes/btTriangleShape.h>
35 #include <BulletCollision/CollisionShapes/btConvexPolyhedron.h>
38 #include <BulletCollision/BroadphaseCollision/btBroadphaseProxy.h>
39 #include <BulletCollision/CollisionDispatch/btCollisionDispatcher.h>
40 #include <BulletCollision/CollisionShapes/btBoxShape.h>
41 #include <BulletCollision/CollisionDispatch/btManifoldResult.h>
43 #include <BulletCollision/NarrowPhaseCollision/btConvexPenetrationDepthSolver.h>
44 #include <BulletCollision/NarrowPhaseCollision/btContinuousConvexCollision.h>
45 #include <BulletCollision/NarrowPhaseCollision/btSubSimplexConvexCast.h>
46 #include <BulletCollision/NarrowPhaseCollision/btGjkConvexCast.h>
48 #include <BulletCollision/NarrowPhaseCollision/btVoronoiSimplexSolver.h>
49 #include <BulletCollision/CollisionShapes/btSphereShape.h>
51 #include <BulletCollision/NarrowPhaseCollision/btMinkowskiPenetrationDepthSolver.h>
53 #include <BulletCollision/NarrowPhaseCollision/btGjkEpa2.h>
54 #include <BulletCollision/NarrowPhaseCollision/btGjkEpaPenetrationDepthSolver.h>
55 #include <BulletCollision/NarrowPhaseCollision/btPolyhedralContactClipping.h>
56 #include <BulletCollision/CollisionDispatch/btCollisionObjectWrapper.h>
70 const btVector3& translation,
71 const btVector3& dirA,
73 const btVector3& dirB,
78 btScalar dirA_dot_dirB = btDot(dirA, dirB);
79 btScalar dirA_dot_trans = btDot(dirA, translation);
80 btScalar dirB_dot_trans = btDot(dirB, translation);
82 btScalar denom = btScalar(1.0) - (dirA_dot_dirB * dirA_dot_dirB);
84 if (denom == btScalar(0.0))
90 tA = (dirA_dot_trans - dirB_dot_trans * dirA_dot_dirB) / denom;
97 tB = tA * dirA_dot_dirB - dirB_dot_trans;
102 tA = tB * dirA_dot_dirB + dirA_dot_trans;
112 tA = tB * dirA_dot_dirB + dirA_dot_trans;
125 ptsVector = translation - offsetA + offsetB;
130 btScalar capsuleLengthA,
131 btScalar capsuleRadiusA,
132 btScalar capsuleLengthB,
133 btScalar capsuleRadiusB,
136 const btTransform& transformA,
137 const btTransform& transformB,
138 btScalar distanceThreshold)
140 btVector3 directionA = transformA.getBasis().getColumn(capsuleAxisA);
141 btVector3 translationA = transformA.getOrigin();
142 btVector3 directionB = transformB.getBasis().getColumn(capsuleAxisB);
143 btVector3 translationB = transformB.getOrigin();
147 btVector3 translation = translationB - translationA;
153 btVector3 offsetA, offsetB;
154 btScalar tA{ std::numeric_limits<btScalar>::max() },
155 tB{ std::numeric_limits<btScalar>::max() };
158 ptsVector, offsetA, offsetB, tA, tB, translation, directionA, capsuleLengthA, directionB, capsuleLengthB);
160 btScalar
distance = ptsVector.length() - capsuleRadiusA - capsuleRadiusB;
165 btScalar lenSqr = ptsVector.length2();
166 if (lenSqr <= (SIMD_EPSILON * SIMD_EPSILON))
170 btPlaneSpace1(directionA, normalOnB, q);
175 normalOnB = ptsVector * -btRecipSqrt(lenSqr);
177 pointOnB = transformB.getOrigin() + offsetB + normalOnB * capsuleRadiusB;
189 const btCollisionAlgorithmConstructionInfo& ci,
190 const btCollisionObjectWrapper* body0Wrap,
191 const btCollisionObjectWrapper* body1Wrap,
192 btConvexPenetrationDepthSolver* pdSolver,
193 int numPerturbationIterations,
194 int minimumPointsPerturbationThreshold)
195 : btActivatingCollisionAlgorithm(ci, body0Wrap, body1Wrap)
199 #ifdef USE_SEPDISTANCE_UTIL2
200 m_sepDistance((static_cast<btConvexShape*>(body0->getCollisionShape()))->getAngularMotionDisc(),
201 (static_cast<btConvexShape*>(body1->getCollisionShape()))->getAngularMotionDisc())
234 const btTransform& transformA,
235 const btTransform& transformB,
236 const btTransform& unPerturbedTransform,
238 btIDebugDraw* debugDrawer)
249 void addContactPoint(
const btVector3& normalOnBInWorld,
const btVector3& pointInWorld, btScalar orgDepth)
override
251 btVector3 endPt, startPt;
252 btScalar newDepth{ std::numeric_limits<btScalar>::max() };
257 btVector3 endPtOrg = pointInWorld + normalOnBInWorld * orgDepth;
259 newDepth = (endPt - pointInWorld).dot(normalOnBInWorld);
260 startPt = endPt - normalOnBInWorld * newDepth;
264 endPt = pointInWorld + normalOnBInWorld * orgDepth;
266 newDepth = (endPt - startPt).dot(normalOnBInWorld);
270 #ifdef DEBUG_CONTACTS
272 m_debugDrawer->drawSphere(startPt, 0.05, btVector3(0, 1, 0));
274 #endif // DEBUG_CONTACTS
284 const btCollisionObjectWrapper* body1Wrap,
285 const btDispatcherInfo& dispatchInfo,
286 btManifoldResult* resultOut)
291 m_manifoldPtr = m_dispatcher->getNewManifold(body0Wrap->getCollisionObject(), body1Wrap->getCollisionObject());
299 const auto* min0 =
static_cast<const btConvexShape*
>(body0Wrap->getCollisionShape());
300 const auto* min1 =
static_cast<const btConvexShape*
>(body1Wrap->getCollisionShape());
303 btVector3 pointOnBWorld;
304 #ifndef BT_DISABLE_CAPSULE_CAPSULE_COLLIDER
305 if ((min0->getShapeType() == CAPSULE_SHAPE_PROXYTYPE) && (min1->getShapeType() == CAPSULE_SHAPE_PROXYTYPE))
309 auto* capsuleA = (btCapsuleShape*)min0;
310 auto* capsuleB = (btCapsuleShape*)min1;
312 btScalar threshold =
m_manifoldPtr->getContactBreakingThreshold() + resultOut->m_closestPointDistanceThreshold;
316 capsuleA->getHalfHeight(),
317 capsuleA->getRadius(),
318 capsuleB->getHalfHeight(),
319 capsuleB->getRadius(),
320 capsuleA->getUpAxis(),
321 capsuleB->getUpAxis(),
322 body0Wrap->getWorldTransform(),
323 body1Wrap->getWorldTransform(),
326 if (dist < threshold)
328 btAssert(normalOnB.length2() >= (SIMD_EPSILON * SIMD_EPSILON));
329 resultOut->addContactPoint(normalOnB, pointOnBWorld, dist);
331 resultOut->refreshContactPoints();
335 if ((min0->getShapeType() == CAPSULE_SHAPE_PROXYTYPE) && (min1->getShapeType() == SPHERE_SHAPE_PROXYTYPE))
339 auto* capsuleA = (btCapsuleShape*)min0;
340 auto* capsuleB = (btSphereShape*)min1;
342 btScalar threshold =
m_manifoldPtr->getContactBreakingThreshold() + resultOut->m_closestPointDistanceThreshold;
346 capsuleA->getHalfHeight(),
347 capsuleA->getRadius(),
349 capsuleB->getRadius(),
350 capsuleA->getUpAxis(),
352 body0Wrap->getWorldTransform(),
353 body1Wrap->getWorldTransform(),
356 if (dist < threshold)
358 btAssert(normalOnB.length2() >= (SIMD_EPSILON * SIMD_EPSILON));
359 resultOut->addContactPoint(normalOnB, pointOnBWorld, dist);
361 resultOut->refreshContactPoints();
365 if ((min0->getShapeType() == SPHERE_SHAPE_PROXYTYPE) && (min1->getShapeType() == CAPSULE_SHAPE_PROXYTYPE))
369 auto* capsuleA = (btSphereShape*)min0;
370 auto* capsuleB = (btCapsuleShape*)min1;
372 btScalar threshold =
m_manifoldPtr->getContactBreakingThreshold() + resultOut->m_closestPointDistanceThreshold;
377 capsuleA->getRadius(),
378 capsuleB->getHalfHeight(),
379 capsuleB->getRadius(),
381 capsuleB->getUpAxis(),
382 body0Wrap->getWorldTransform(),
383 body1Wrap->getWorldTransform(),
386 if (dist < threshold)
388 btAssert(normalOnB.length2() >= (SIMD_EPSILON * SIMD_EPSILON));
389 resultOut->addContactPoint(normalOnB, pointOnBWorld, dist);
391 resultOut->refreshContactPoints();
394 #endif // BT_DISABLE_CAPSULE_CAPSULE_COLLIDER
396 #ifdef USE_SEPDISTANCE_UTIL2
397 if (dispatchInfo.m_useConvexConservativeDistanceUtil)
399 m_sepDistance.updateSeparatingDistance(body0->getWorldTransform(), body1->getWorldTransform());
402 if (!dispatchInfo.m_useConvexConservativeDistanceUtil || m_sepDistance.getConservativeSeparatingDistance() <= 0.f)
403 #endif // USE_SEPDISTANCE_UTIL2
409 TesseractGjkPairDetector::ClosestPointInput input;
410 btVoronoiSimplexSolver simplexSolver;
416 #ifdef USE_SEPDISTANCE_UTIL2
417 if (dispatchInfo.m_useConvexConservativeDistanceUtil)
419 input.m_maximumDistanceSquared = BT_LARGE_FLOAT;
422 #endif // USE_SEPDISTANCE_UTIL2
429 input.m_maximumDistanceSquared = min0->getMargin() + min1->getMargin() +
431 resultOut->m_closestPointDistanceThreshold;
434 input.m_maximumDistanceSquared *= input.m_maximumDistanceSquared;
437 input.m_transformA = body0Wrap->getWorldTransform();
438 input.m_transformB = body1Wrap->getWorldTransform();
440 #ifdef USE_SEPDISTANCE_UTIL2
441 btScalar sepDist = 0.f;
442 if (dispatchInfo.m_useConvexConservativeDistanceUtil)
445 if (sepDist > SIMD_EPSILON)
447 sepDist += dispatchInfo.m_convexConservativeDistanceThreshold;
451 #endif // USE_SEPDISTANCE_UTIL2
453 if (min0->isPolyhedral() && min1->isPolyhedral())
455 struct btDummyResult :
public btDiscreteCollisionDetectorInterface::Result
457 btVector3 m_normalOnBInWorld;
458 btVector3 m_pointInWorld;
459 btScalar m_depth{ std::numeric_limits<btScalar>::max() };
460 bool m_hasContact{
false };
462 btDummyResult() =
default;
464 void setShapeIdentifiersA(
int ,
int )
override {}
465 void setShapeIdentifiersB(
int ,
int )
override {}
466 void addContactPoint(
const btVector3& normalOnBInWorld,
const btVector3& pointInWorld, btScalar depth)
override
469 m_normalOnBInWorld = normalOnBInWorld;
470 m_pointInWorld = pointInWorld;
475 struct btWithoutMarginResult :
public btDiscreteCollisionDetectorInterface::Result
477 btDiscreteCollisionDetectorInterface::Result* m_originalResult;
478 btVector3 m_reportedNormalOnWorld;
479 btScalar m_marginOnA;
480 btScalar m_marginOnB;
481 btScalar m_reportedDistance{ 0 };
483 bool m_foundResult{
false };
484 btWithoutMarginResult(btDiscreteCollisionDetectorInterface::Result* result,
487 : m_originalResult(result), m_marginOnA(marginOnA), m_marginOnB(marginOnB)
491 void setShapeIdentifiersA(
int ,
int )
override {}
492 void setShapeIdentifiersB(
int ,
int )
override {}
493 void addContactPoint(
const btVector3& normalOnBInWorld,
494 const btVector3& pointInWorldOrg,
495 btScalar depthOrg)
override
497 m_reportedDistance = depthOrg;
498 m_reportedNormalOnWorld = normalOnBInWorld;
500 btVector3 adjustedPointB = pointInWorldOrg - normalOnBInWorld * m_marginOnB;
501 m_reportedDistance = depthOrg + (m_marginOnA + m_marginOnB);
502 if (m_reportedDistance < btScalar(0.))
504 m_foundResult =
true;
506 m_originalResult->addContactPoint(normalOnBInWorld, adjustedPointB, m_reportedDistance);
514 btScalar min0Margin = min0->getShapeType() == BOX_SHAPE_PROXYTYPE ? btScalar(0.) : min0->getMargin();
515 btScalar min1Margin = min1->getShapeType() == BOX_SHAPE_PROXYTYPE ? btScalar(0.) : min1->getMargin();
517 btWithoutMarginResult withoutMargin(resultOut, min0Margin, min1Margin);
519 auto* polyhedronA = (btPolyhedralConvexShape*)min0;
520 auto* polyhedronB = (btPolyhedralConvexShape*)min1;
522 if (polyhedronA->getConvexPolyhedron() !=
nullptr && polyhedronB->getConvexPolyhedron() !=
nullptr)
524 btScalar threshold =
m_manifoldPtr->getContactBreakingThreshold() + resultOut->m_closestPointDistanceThreshold;
526 auto minDist = btScalar(-1e30);
527 btVector3 sepNormalWorldSpace;
528 bool foundSepAxis =
true;
530 if (dispatchInfo.m_enableSatConvex)
532 foundSepAxis = btPolyhedralContactClipping::findSeparatingAxis(*polyhedronA->getConvexPolyhedron(),
533 *polyhedronB->getConvexPolyhedron(),
534 body0Wrap->getWorldTransform(),
535 body1Wrap->getWorldTransform(),
543 gjkPairDetector.
getClosestPoints(input, *resultOut, dispatchInfo.m_debugDraw);
546 gjkPairDetector.
getClosestPoints(input, withoutMargin, dispatchInfo.m_debugDraw);
548 #endif // ZERO_MARGIN
552 sepNormalWorldSpace =
553 withoutMargin.m_reportedNormalOnWorld;
562 foundSepAxis = withoutMargin.m_foundResult && minDist < 0;
571 btPolyhedralContactClipping::clipHullAgainstHull(sepNormalWorldSpace,
572 *polyhedronA->getConvexPolyhedron(),
573 *polyhedronB->getConvexPolyhedron(),
574 body0Wrap->getWorldTransform(),
575 body1Wrap->getWorldTransform(),
584 resultOut->refreshContactPoints();
591 if (dispatchInfo.m_enableSatConvex && polyhedronA->getConvexPolyhedron() !=
nullptr &&
592 polyhedronB->getShapeType() == TRIANGLE_SHAPE_PROXYTYPE)
594 btVertexArray worldSpaceVertices;
595 auto* tri = (btTriangleShape*)polyhedronB;
596 worldSpaceVertices.push_back(body1Wrap->getWorldTransform() * tri->m_vertices1[0]);
597 worldSpaceVertices.push_back(body1Wrap->getWorldTransform() * tri->m_vertices1[1]);
598 worldSpaceVertices.push_back(body1Wrap->getWorldTransform() * tri->m_vertices1[2]);
603 m_manifoldPtr->getContactBreakingThreshold() + resultOut->m_closestPointDistanceThreshold;
605 btVector3 sepNormalWorldSpace;
606 auto minDist = btScalar(-1e30);
607 btScalar maxDist = threshold;
609 bool foundSepAxis =
false;
610 bool useSatSepNormal =
true;
618 polyhedronB->initializePolyhedralFeatures();
622 btVector3 uniqueEdges[3] = { tri->m_vertices1[1] - tri->m_vertices1[0],
623 tri->m_vertices1[2] - tri->m_vertices1[1],
624 tri->m_vertices1[0] - tri->m_vertices1[2] };
626 uniqueEdges[0].normalize();
627 uniqueEdges[1].normalize();
628 uniqueEdges[2].normalize();
630 btConvexPolyhedron polyhedron;
631 polyhedron.m_vertices.push_back(tri->m_vertices1[2]);
632 polyhedron.m_vertices.push_back(tri->m_vertices1[0]);
633 polyhedron.m_vertices.push_back(tri->m_vertices1[1]);
636 btFace combinedFaceA;
637 combinedFaceA.m_indices.push_back(0);
638 combinedFaceA.m_indices.push_back(1);
639 combinedFaceA.m_indices.push_back(2);
640 btVector3 faceNormal = uniqueEdges[0].cross(uniqueEdges[1]);
641 faceNormal.normalize();
642 auto planeEq = btScalar(1e30);
643 for (
int v = 0; v < combinedFaceA.m_indices.size(); v++)
645 btScalar eq = tri->m_vertices1[combinedFaceA.m_indices[v]].dot(faceNormal);
646 planeEq = std::min(planeEq, eq);
648 combinedFaceA.m_plane[0] = faceNormal[0];
649 combinedFaceA.m_plane[1] = faceNormal[1];
650 combinedFaceA.m_plane[2] = faceNormal[2];
651 combinedFaceA.m_plane[3] = -planeEq;
652 polyhedron.m_faces.push_back(combinedFaceA);
655 btFace combinedFaceB;
656 combinedFaceB.m_indices.push_back(0);
657 combinedFaceB.m_indices.push_back(2);
658 combinedFaceB.m_indices.push_back(1);
659 btVector3 faceNormal = -uniqueEdges[0].cross(uniqueEdges[1]);
660 faceNormal.normalize();
661 auto planeEq = btScalar(1e30);
662 for (
int v = 0; v < combinedFaceB.m_indices.size(); v++)
664 btScalar eq = tri->m_vertices1[combinedFaceB.m_indices[v]].dot(faceNormal);
665 planeEq = std::min(planeEq, eq);
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);
675 polyhedron.m_uniqueEdges.push_back(uniqueEdges[0]);
676 polyhedron.m_uniqueEdges.push_back(uniqueEdges[1]);
677 polyhedron.m_uniqueEdges.push_back(uniqueEdges[2]);
678 polyhedron.initialize2();
680 polyhedronB->setPolyhedralFeatures(polyhedron);
683 foundSepAxis = btPolyhedralContactClipping::findSeparatingAxis(*polyhedronA->getConvexPolyhedron(),
684 *polyhedronB->getConvexPolyhedron(),
685 body0Wrap->getWorldTransform(),
686 body1Wrap->getWorldTransform(),
695 gjkPairDetector.
getClosestPoints(input, *resultOut, dispatchInfo.m_debugDraw);
698 #endif // ZERO_MARGIN
700 if (dummy.m_hasContact && dummy.m_depth < 0)
704 if (dummy.m_normalOnBInWorld.dot(sepNormalWorldSpace) < 0.99)
713 sepNormalWorldSpace.setValue(0, 0, 1);
733 btPolyhedralContactClipping::clipFaceAgainstHull(sepNormalWorldSpace,
734 *polyhedronA->getConvexPolyhedron(),
735 body0Wrap->getWorldTransform(),
745 resultOut->refreshContactPoints();
753 gjkPairDetector.
getClosestPoints(input, *resultOut, dispatchInfo.m_debugDraw);
762 btVector3 sepNormalWorldSpace;
765 if (l2 > SIMD_EPSILON)
769 btPlaneSpace1(sepNormalWorldSpace, v0, v1);
771 bool perturbeA =
true;
772 const btScalar angleLimit = btScalar(0.125) * SIMD_PI;
773 btScalar perturbeAngle{ std::numeric_limits<btScalar>::max() };
774 btScalar radiusA = min0->getAngularMotionDisc();
775 btScalar radiusB = min1->getAngularMotionDisc();
776 if (radiusA < radiusB)
786 perturbeAngle = std::min(perturbeAngle, angleLimit);
788 btTransform unPerturbedTransform;
791 unPerturbedTransform = input.m_transformA;
795 unPerturbedTransform = input.m_transformB;
800 if (v0.length2() > SIMD_EPSILON)
802 btQuaternion perturbeRot(v0, perturbeAngle);
804 btQuaternion rotq(sepNormalWorldSpace, iterationAngle);
808 input.m_transformA.setBasis(btMatrix3x3(rotq.inverse() * perturbeRot * rotq) *
809 body0Wrap->getWorldTransform().getBasis());
810 input.m_transformB = body1Wrap->getWorldTransform();
811 #ifdef DEBUG_CONTACTS
812 dispatchInfo.m_debugDraw->drawTransform(input.m_transformA, 10.0);
813 #endif // DEBUG_CONTACTS
817 input.m_transformA = body0Wrap->getWorldTransform();
818 input.m_transformB.setBasis(btMatrix3x3(rotq.inverse() * perturbeRot * rotq) *
819 body1Wrap->getWorldTransform().getBasis());
820 #ifdef DEBUG_CONTACTS
821 dispatchInfo.m_debugDraw->drawTransform(input.m_transformB, 10.0);
828 unPerturbedTransform,
830 dispatchInfo.m_debugDraw);
831 gjkPairDetector.
getClosestPoints(input, perturbedResultOut, dispatchInfo.m_debugDraw);
837 #ifdef USE_SEPDISTANCE_UTIL2
838 if (dispatchInfo.m_useConvexConservativeDistanceUtil && (sepDist > SIMD_EPSILON))
840 m_sepDistance.initSeparatingDistance(
843 #endif // USE_SEPDISTANCE_UTIL2
848 resultOut->refreshContactPoints();
854 btCollisionObject* body1,
855 const btDispatcherInfo& dispatchInfo,
856 btManifoldResult* resultOut)
864 auto resultFraction = btScalar(1.);
866 btScalar squareMot0 =
867 (body0->getInterpolationWorldTransform().getOrigin() - body0->getWorldTransform().getOrigin()).length2();
868 btScalar squareMot1 =
869 (body1->getInterpolationWorldTransform().getOrigin() - body1->getWorldTransform().getOrigin()).length2();
871 if (squareMot0 < body0->getCcdSquareMotionThreshold() && squareMot1 < body1->getCcdSquareMotionThreshold())
872 return resultFraction;
886 auto* convex0 =
static_cast<btConvexShape*
>(body0->getCollisionShape());
888 btSphereShape sphere1(body1->getCcdSweptSphereRadius());
890 btConvexCast::CastResult result;
891 btVoronoiSimplexSolver voronoiSimplex;
894 btGjkConvexCast ccd1(convex0, &sphere1, &voronoiSimplex);
896 if (ccd1.calcTimeOfImpact(body0->getWorldTransform(),
897 body0->getInterpolationWorldTransform(),
898 body1->getWorldTransform(),
899 body1->getInterpolationWorldTransform(),
904 if (body0->getHitFraction() > result.m_fraction)
905 body0->setHitFraction(result.m_fraction);
907 if (body1->getHitFraction() > result.m_fraction)
908 body1->setHitFraction(result.m_fraction);
910 resultFraction = std::min(resultFraction, result.m_fraction);
916 auto* convex1 =
static_cast<btConvexShape*
>(body1->getCollisionShape());
918 btSphereShape sphere0(body0->getCcdSweptSphereRadius());
920 btConvexCast::CastResult result;
921 btVoronoiSimplexSolver voronoiSimplex;
924 btGjkConvexCast ccd1(&sphere0, convex1, &voronoiSimplex);
926 if (ccd1.calcTimeOfImpact(body0->getWorldTransform(),
927 body0->getInterpolationWorldTransform(),
928 body1->getWorldTransform(),
929 body1->getInterpolationWorldTransform(),
934 if (body0->getHitFraction() > result.m_fraction)
935 body0->setHitFraction(result.m_fraction);
937 if (body1->getHitFraction() > result.m_fraction)
938 body1->setHitFraction(result.m_fraction);
940 resultFraction = std::min(resultFraction, result.m_fraction);
944 return resultFraction;