Skip to content

Commit

Permalink
Merge pull request #2034 from erwincoumans/master
Browse files Browse the repository at this point in the history
Cleaning up the issue tracked with old/out-of-date/issues that haven't been addressed for too long.
  • Loading branch information
erwincoumans committed Dec 31, 2018
2 parents 8bc1c8e + 21d9465 commit 126b676
Show file tree
Hide file tree
Showing 5 changed files with 22 additions and 14 deletions.
Binary file modified build3/premake5.exe
Binary file not shown.
Original file line number Diff line number Diff line change
Expand Up @@ -113,6 +113,12 @@ struct btCompoundLeafCallback : btDbvt::ICollide
const btCompoundShape* compoundShape = static_cast<const btCompoundShape*>(m_compoundColObjWrap->getCollisionShape());
btAssert(index < compoundShape->getNumChildShapes());

if (gCompoundChildShapePairCallback)
{
if (!gCompoundChildShapePairCallback(m_otherObjWrap->getCollisionShape(), childShape))
return;
}

//backup
btTransform orgTrans = m_compoundColObjWrap->getWorldTransform();

Expand All @@ -130,11 +136,6 @@ struct btCompoundLeafCallback : btDbvt::ICollide
btVector3 aabbMin1, aabbMax1;
m_otherObjWrap->getCollisionShape()->getAabb(m_otherObjWrap->getWorldTransform(), aabbMin1, aabbMax1);

if (gCompoundChildShapePairCallback)
{
if (!gCompoundChildShapePairCallback(m_otherObjWrap->getCollisionShape(), childShape))
return;
}

if (TestAabbAgainstAabb2(aabbMin0, aabbMax0, aabbMin1, aabbMax1))
{
Expand Down
15 changes: 11 additions & 4 deletions src/BulletCollision/Gimpact/btGImpactCollisionAlgorithm.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -50,10 +50,11 @@ class btPlaneShape : public btStaticPlaneShape

void get_plane_equation_transformed(const btTransform& trans, btVector4& equation) const
{
equation[0] = trans.getBasis().getRow(0).dot(m_planeNormal);
equation[1] = trans.getBasis().getRow(1).dot(m_planeNormal);
equation[2] = trans.getBasis().getRow(2).dot(m_planeNormal);
equation[3] = trans.getOrigin().dot(m_planeNormal) + m_planeConstant;
const btVector3 normal = trans.getBasis() * m_planeNormal;
equation[0] = normal[0];
equation[1] = normal[1];
equation[2] = normal[2];
equation[3] = normal.dot(trans * (m_planeConstant * m_planeNormal));
}
};

Expand Down Expand Up @@ -821,6 +822,12 @@ void btGImpactCollisionAlgorithm::processCollision(const btCollisionObjectWrappe

gimpact_vs_shape(body1Wrap, body0Wrap, gimpactshape1, body0Wrap->getCollisionShape(), true);
}

// Ensure that gContactProcessedCallback is called for concave shapes.
if (getLastManifold())
{
m_resultOut->refreshContactPoints();
}
}

btScalar btGImpactCollisionAlgorithm::calculateTimeOfImpact(btCollisionObject* body0, btCollisionObject* body1, const btDispatcherInfo& dispatchInfo, btManifoldResult* resultOut)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -737,7 +737,7 @@ void btKinematicCharacterController::playerStep(btCollisionWorld* collisionWorld
}

// quick check...
if (!m_useWalkDirection && (m_velocityTimeInterval <= 0.0))
if (!m_useWalkDirection && (m_velocityTimeInterval <= 0.0 || m_walkDirection.fuzzyZero()))
{
// printf("\n");
return; // no motion
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -918,9 +918,9 @@ void btSequentialImpulseConstraintSolver::setupContactConstraint(btSolverConstra
{
solverConstraint.m_appliedImpulse = cp.m_appliedImpulse * infoGlobal.m_warmstartingFactor;
if (rb0)
bodyA->internalApplyImpulse(solverConstraint.m_contactNormal1 * bodyA->internalGetInvMass() * rb0->getLinearFactor(), solverConstraint.m_angularComponentA, solverConstraint.m_appliedImpulse);
bodyA->internalApplyImpulse(solverConstraint.m_contactNormal1 * bodyA->internalGetInvMass(), solverConstraint.m_angularComponentA, solverConstraint.m_appliedImpulse);
if (rb1)
bodyB->internalApplyImpulse(-solverConstraint.m_contactNormal2 * bodyB->internalGetInvMass() * rb1->getLinearFactor(), -solverConstraint.m_angularComponentB, -(btScalar)solverConstraint.m_appliedImpulse);
bodyB->internalApplyImpulse(-solverConstraint.m_contactNormal2 * bodyB->internalGetInvMass() , -solverConstraint.m_angularComponentB, -(btScalar)solverConstraint.m_appliedImpulse);
}
else
{
Expand Down Expand Up @@ -990,9 +990,9 @@ void btSequentialImpulseConstraintSolver::setFrictionConstraintImpulse(btSolverC
{
frictionConstraint1.m_appliedImpulse = cp.m_appliedImpulseLateral1 * infoGlobal.m_warmstartingFactor;
if (rb0)
bodyA->internalApplyImpulse(frictionConstraint1.m_contactNormal1 * rb0->getInvMass() * rb0->getLinearFactor(), frictionConstraint1.m_angularComponentA, frictionConstraint1.m_appliedImpulse);
bodyA->internalApplyImpulse(frictionConstraint1.m_contactNormal1 * rb0->getInvMass() , frictionConstraint1.m_angularComponentA, frictionConstraint1.m_appliedImpulse);
if (rb1)
bodyB->internalApplyImpulse(-frictionConstraint1.m_contactNormal2 * rb1->getInvMass() * rb1->getLinearFactor(), -frictionConstraint1.m_angularComponentB, -(btScalar)frictionConstraint1.m_appliedImpulse);
bodyB->internalApplyImpulse(-frictionConstraint1.m_contactNormal2 * rb1->getInvMass() , -frictionConstraint1.m_angularComponentB, -(btScalar)frictionConstraint1.m_appliedImpulse);
}
else
{
Expand Down

0 comments on commit 126b676

Please sign in to comment.