revert constraint solver changes to allow block solver, since it breaks the multithreaded solver.
(re-enable if/when we can redo those changes without breaking multithreading)
This commit is contained in:
File diff suppressed because it is too large
Load Diff
@@ -29,68 +29,6 @@ class btCollisionObject;
|
|||||||
|
|
||||||
typedef btScalar (*btSingleConstraintRowSolver)(btSolverBody&, btSolverBody&, const btSolverConstraint&);
|
typedef btScalar (*btSingleConstraintRowSolver)(btSolverBody&, btSolverBody&, const btSolverConstraint&);
|
||||||
|
|
||||||
struct btSISolverSingleIterationData
|
|
||||||
{
|
|
||||||
btAlignedObjectArray<btSolverBody>& m_tmpSolverBodyPool;
|
|
||||||
btConstraintArray& m_tmpSolverContactConstraintPool;
|
|
||||||
btConstraintArray& m_tmpSolverNonContactConstraintPool;
|
|
||||||
btConstraintArray& m_tmpSolverContactFrictionConstraintPool;
|
|
||||||
btConstraintArray& m_tmpSolverContactRollingFrictionConstraintPool;
|
|
||||||
|
|
||||||
btAlignedObjectArray<int>& m_orderTmpConstraintPool;
|
|
||||||
btAlignedObjectArray<int>& m_orderNonContactConstraintPool;
|
|
||||||
btAlignedObjectArray<int>& m_orderFrictionConstraintPool;
|
|
||||||
btAlignedObjectArray<btTypedConstraint::btConstraintInfo1>& m_tmpConstraintSizesPool;
|
|
||||||
unsigned long& m_seed;
|
|
||||||
|
|
||||||
btSingleConstraintRowSolver& m_resolveSingleConstraintRowGeneric;
|
|
||||||
btSingleConstraintRowSolver& m_resolveSingleConstraintRowLowerLimit;
|
|
||||||
btSingleConstraintRowSolver& m_resolveSplitPenetrationImpulse;
|
|
||||||
btAlignedObjectArray<int>& m_kinematicBodyUniqueIdToSolverBodyTable;
|
|
||||||
int& m_fixedBodyId;
|
|
||||||
int& m_maxOverrideNumSolverIterations;
|
|
||||||
int getOrInitSolverBody(btCollisionObject & body, btScalar timeStep);
|
|
||||||
static void initSolverBody(btSolverBody * solverBody, btCollisionObject * collisionObject, btScalar timeStep);
|
|
||||||
int getSolverBody(btCollisionObject& body) const;
|
|
||||||
|
|
||||||
|
|
||||||
btSISolverSingleIterationData(btAlignedObjectArray<btSolverBody>& tmpSolverBodyPool,
|
|
||||||
btConstraintArray& tmpSolverContactConstraintPool,
|
|
||||||
btConstraintArray& tmpSolverNonContactConstraintPool,
|
|
||||||
btConstraintArray& tmpSolverContactFrictionConstraintPool,
|
|
||||||
btConstraintArray& tmpSolverContactRollingFrictionConstraintPool,
|
|
||||||
btAlignedObjectArray<int>& orderTmpConstraintPool,
|
|
||||||
btAlignedObjectArray<int>& orderNonContactConstraintPool,
|
|
||||||
btAlignedObjectArray<int>& orderFrictionConstraintPool,
|
|
||||||
btAlignedObjectArray<btTypedConstraint::btConstraintInfo1>& tmpConstraintSizesPool,
|
|
||||||
btSingleConstraintRowSolver& resolveSingleConstraintRowGeneric,
|
|
||||||
btSingleConstraintRowSolver& resolveSingleConstraintRowLowerLimit,
|
|
||||||
btSingleConstraintRowSolver& resolveSplitPenetrationImpulse,
|
|
||||||
btAlignedObjectArray<int>& kinematicBodyUniqueIdToSolverBodyTable,
|
|
||||||
unsigned long& seed,
|
|
||||||
int& fixedBodyId,
|
|
||||||
int& maxOverrideNumSolverIterations
|
|
||||||
)
|
|
||||||
:m_tmpSolverBodyPool(tmpSolverBodyPool),
|
|
||||||
m_tmpSolverContactConstraintPool(tmpSolverContactConstraintPool),
|
|
||||||
m_tmpSolverNonContactConstraintPool(tmpSolverNonContactConstraintPool),
|
|
||||||
m_tmpSolverContactFrictionConstraintPool(tmpSolverContactFrictionConstraintPool),
|
|
||||||
m_tmpSolverContactRollingFrictionConstraintPool(tmpSolverContactRollingFrictionConstraintPool),
|
|
||||||
m_orderTmpConstraintPool(orderTmpConstraintPool),
|
|
||||||
m_orderNonContactConstraintPool(orderNonContactConstraintPool),
|
|
||||||
m_orderFrictionConstraintPool(orderFrictionConstraintPool),
|
|
||||||
m_tmpConstraintSizesPool(tmpConstraintSizesPool),
|
|
||||||
m_seed(seed),
|
|
||||||
m_resolveSingleConstraintRowGeneric(resolveSingleConstraintRowGeneric),
|
|
||||||
m_resolveSingleConstraintRowLowerLimit(resolveSingleConstraintRowLowerLimit),
|
|
||||||
m_resolveSplitPenetrationImpulse(resolveSplitPenetrationImpulse),
|
|
||||||
m_kinematicBodyUniqueIdToSolverBodyTable(kinematicBodyUniqueIdToSolverBodyTable),
|
|
||||||
m_fixedBodyId(fixedBodyId),
|
|
||||||
m_maxOverrideNumSolverIterations(maxOverrideNumSolverIterations)
|
|
||||||
{
|
|
||||||
}
|
|
||||||
};
|
|
||||||
|
|
||||||
struct btSolverAnalyticsData
|
struct btSolverAnalyticsData
|
||||||
{
|
{
|
||||||
btSolverAnalyticsData()
|
btSolverAnalyticsData()
|
||||||
@@ -178,7 +116,6 @@ protected:
|
|||||||
virtual void convertJoints(btTypedConstraint * *constraints, int numConstraints, const btContactSolverInfo& infoGlobal);
|
virtual void convertJoints(btTypedConstraint * *constraints, int numConstraints, const btContactSolverInfo& infoGlobal);
|
||||||
void convertJoint(btSolverConstraint * currentConstraintRow, btTypedConstraint * constraint, const btTypedConstraint::btConstraintInfo1& info1, int solverBodyIdA, int solverBodyIdB, const btContactSolverInfo& infoGlobal);
|
void convertJoint(btSolverConstraint * currentConstraintRow, btTypedConstraint * constraint, const btTypedConstraint::btConstraintInfo1& info1, int solverBodyIdA, int solverBodyIdB, const btContactSolverInfo& infoGlobal);
|
||||||
|
|
||||||
|
|
||||||
virtual void convertBodies(btCollisionObject * *bodies, int numBodies, const btContactSolverInfo& infoGlobal);
|
virtual void convertBodies(btCollisionObject * *bodies, int numBodies, const btContactSolverInfo& infoGlobal);
|
||||||
|
|
||||||
btScalar resolveSplitPenetrationSIMD(btSolverBody & bodyA, btSolverBody & bodyB, const btSolverConstraint& contactConstraint)
|
btScalar resolveSplitPenetrationSIMD(btSolverBody & bodyA, btSolverBody & bodyB, const btSolverConstraint& contactConstraint)
|
||||||
@@ -204,8 +141,7 @@ protected:
|
|||||||
return m_resolveSplitPenetrationImpulse(bodyA, bodyB, contactConstraint);
|
return m_resolveSplitPenetrationImpulse(bodyA, bodyB, contactConstraint);
|
||||||
}
|
}
|
||||||
|
|
||||||
public:
|
protected:
|
||||||
|
|
||||||
void writeBackContacts(int iBegin, int iEnd, const btContactSolverInfo& infoGlobal);
|
void writeBackContacts(int iBegin, int iEnd, const btContactSolverInfo& infoGlobal);
|
||||||
void writeBackJoints(int iBegin, int iEnd, const btContactSolverInfo& infoGlobal);
|
void writeBackJoints(int iBegin, int iEnd, const btContactSolverInfo& infoGlobal);
|
||||||
void writeBackBodies(int iBegin, int iEnd, const btContactSolverInfo& infoGlobal);
|
void writeBackBodies(int iBegin, int iEnd, const btContactSolverInfo& infoGlobal);
|
||||||
@@ -213,7 +149,6 @@ public:
|
|||||||
virtual btScalar solveGroupCacheFriendlyFinish(btCollisionObject * *bodies, int numBodies, const btContactSolverInfo& infoGlobal);
|
virtual btScalar solveGroupCacheFriendlyFinish(btCollisionObject * *bodies, int numBodies, const btContactSolverInfo& infoGlobal);
|
||||||
virtual btScalar solveSingleIteration(int iteration, btCollisionObject** bodies, int numBodies, btPersistentManifold** manifoldPtr, int numManifolds, btTypedConstraint** constraints, int numConstraints, const btContactSolverInfo& infoGlobal, btIDebugDraw* debugDrawer);
|
virtual btScalar solveSingleIteration(int iteration, btCollisionObject** bodies, int numBodies, btPersistentManifold** manifoldPtr, int numManifolds, btTypedConstraint** constraints, int numConstraints, const btContactSolverInfo& infoGlobal, btIDebugDraw* debugDrawer);
|
||||||
|
|
||||||
|
|
||||||
virtual btScalar solveGroupCacheFriendlySetup(btCollisionObject * *bodies, int numBodies, btPersistentManifold** manifoldPtr, int numManifolds, btTypedConstraint** constraints, int numConstraints, const btContactSolverInfo& infoGlobal, btIDebugDraw* debugDrawer);
|
virtual btScalar solveGroupCacheFriendlySetup(btCollisionObject * *bodies, int numBodies, btPersistentManifold** manifoldPtr, int numManifolds, btTypedConstraint** constraints, int numConstraints, const btContactSolverInfo& infoGlobal, btIDebugDraw* debugDrawer);
|
||||||
virtual btScalar solveGroupCacheFriendlyIterations(btCollisionObject * *bodies, int numBodies, btPersistentManifold** manifoldPtr, int numManifolds, btTypedConstraint** constraints, int numConstraints, const btContactSolverInfo& infoGlobal, btIDebugDraw* debugDrawer);
|
virtual btScalar solveGroupCacheFriendlyIterations(btCollisionObject * *bodies, int numBodies, btPersistentManifold** manifoldPtr, int numManifolds, btTypedConstraint** constraints, int numConstraints, const btContactSolverInfo& infoGlobal, btIDebugDraw* debugDrawer);
|
||||||
|
|
||||||
@@ -225,51 +160,12 @@ public:
|
|||||||
|
|
||||||
virtual btScalar solveGroup(btCollisionObject * *bodies, int numBodies, btPersistentManifold** manifold, int numManifolds, btTypedConstraint** constraints, int numConstraints, const btContactSolverInfo& info, btIDebugDraw* debugDrawer, btDispatcher* dispatcher);
|
virtual btScalar solveGroup(btCollisionObject * *bodies, int numBodies, btPersistentManifold** manifold, int numManifolds, btTypedConstraint** constraints, int numConstraints, const btContactSolverInfo& info, btIDebugDraw* debugDrawer, btDispatcher* dispatcher);
|
||||||
|
|
||||||
static btScalar solveSingleIterationInternal(btSISolverSingleIterationData& siData, int iteration, btTypedConstraint** constraints, int numConstraints, const btContactSolverInfo& infoGlobal);
|
|
||||||
static void convertBodiesInternal(btSISolverSingleIterationData& siData, btCollisionObject** bodies, int numBodies, const btContactSolverInfo& infoGlobal);
|
|
||||||
static void convertJointsInternal(btSISolverSingleIterationData& siData, btTypedConstraint** constraints, int numConstraints, const btContactSolverInfo& infoGlobal);
|
|
||||||
static void convertContactInternal(btSISolverSingleIterationData& siData, btPersistentManifold * manifold, const btContactSolverInfo& infoGlobal);
|
|
||||||
static void setupContactConstraintInternal(btSISolverSingleIterationData& siData, btSolverConstraint& solverConstraint, int solverBodyIdA, int solverBodyIdB, btManifoldPoint& cp, const btContactSolverInfo& infoGlobal, btScalar& relaxation,
|
|
||||||
const btVector3& rel_pos1, const btVector3& rel_pos2);
|
|
||||||
static btScalar restitutionCurveInternal(btScalar rel_vel, btScalar restitution, btScalar velocityThreshold);
|
|
||||||
static btSolverConstraint& addTorsionalFrictionConstraintInternal(btAlignedObjectArray<btSolverBody>& tmpSolverBodyPool, btConstraintArray& tmpSolverContactRollingFrictionConstraintPool, const btVector3& normalAxis, int solverBodyIdA, int solverBodyIdB, int frictionIndex, btManifoldPoint& cp, btScalar combinedTorsionalFriction, const btVector3& rel_pos1, const btVector3& rel_pos2, btCollisionObject* colObj0, btCollisionObject* colObj1, btScalar relaxation, btScalar desiredVelocity = 0, btScalar cfmSlip = 0.);
|
|
||||||
static void setupTorsionalFrictionConstraintInternal(btAlignedObjectArray<btSolverBody>& tmpSolverBodyPool, btSolverConstraint& solverConstraint, const btVector3& normalAxis1, int solverBodyIdA, int solverBodyIdB,
|
|
||||||
btManifoldPoint& cp, btScalar combinedTorsionalFriction, const btVector3& rel_pos1, const btVector3& rel_pos2,
|
|
||||||
btCollisionObject* colObj0, btCollisionObject* colObj1, btScalar relaxation,
|
|
||||||
btScalar desiredVelocity, btScalar cfmSlip);
|
|
||||||
static void setupFrictionConstraintInternal(btAlignedObjectArray<btSolverBody>& tmpSolverBodyPool, btSolverConstraint& solverConstraint, const btVector3& normalAxis, int solverBodyIdA, int solverBodyIdB, btManifoldPoint& cp, const btVector3& rel_pos1, const btVector3& rel_pos2, btCollisionObject* colObj0, btCollisionObject* colObj1, btScalar relaxation, const btContactSolverInfo& infoGlobal, btScalar desiredVelocity, btScalar cfmSlip);
|
|
||||||
static btSolverConstraint& addFrictionConstraintInternal(btAlignedObjectArray<btSolverBody>& tmpSolverBodyPool, btConstraintArray& tmpSolverContactFrictionConstraintPool, const btVector3& normalAxis, int solverBodyIdA, int solverBodyIdB, int frictionIndex, btManifoldPoint& cp, const btVector3& rel_pos1, const btVector3& rel_pos2, btCollisionObject* colObj0, btCollisionObject* colObj1, btScalar relaxation, const btContactSolverInfo& infoGlobal, btScalar desiredVelocity = 0., btScalar cfmSlip = 0.);
|
|
||||||
static void setFrictionConstraintImpulseInternal(btAlignedObjectArray<btSolverBody>& tmpSolverBodyPool, btConstraintArray& tmpSolverContactFrictionConstraintPool,
|
|
||||||
|
|
||||||
btSolverConstraint& solverConstraint,
|
|
||||||
int solverBodyIdA, int solverBodyIdB,
|
|
||||||
btManifoldPoint& cp, const btContactSolverInfo& infoGlobal);
|
|
||||||
static void convertJointInternal(btAlignedObjectArray<btSolverBody>& tmpSolverBodyPool,
|
|
||||||
int& maxOverrideNumSolverIterations,
|
|
||||||
btSolverConstraint* currentConstraintRow,
|
|
||||||
btTypedConstraint* constraint,
|
|
||||||
const btTypedConstraint::btConstraintInfo1& info1,
|
|
||||||
int solverBodyIdA,
|
|
||||||
int solverBodyIdB,
|
|
||||||
const btContactSolverInfo& infoGlobal);
|
|
||||||
|
|
||||||
static btScalar solveGroupCacheFriendlyFinishInternal(btSISolverSingleIterationData& siData, btCollisionObject** bodies, int numBodies, const btContactSolverInfo& infoGlobal);
|
|
||||||
|
|
||||||
static void writeBackContactsInternal(btConstraintArray& tmpSolverContactConstraintPool, btConstraintArray& tmpSolverContactFrictionConstraintPool, int iBegin, int iEnd, const btContactSolverInfo& infoGlobal);
|
|
||||||
|
|
||||||
static void writeBackJointsInternal(btConstraintArray& tmpSolverNonContactConstraintPool, int iBegin, int iEnd, const btContactSolverInfo& infoGlobal);
|
|
||||||
static void writeBackBodiesInternal(btAlignedObjectArray<btSolverBody>& tmpSolverBodyPool, int iBegin, int iEnd, const btContactSolverInfo& infoGlobal);
|
|
||||||
static void solveGroupCacheFriendlySplitImpulseIterationsInternal(btSISolverSingleIterationData& siData, btCollisionObject** bodies, int numBodies, btPersistentManifold** manifoldPtr, int numManifolds, btTypedConstraint** constraints, int numConstraints, const btContactSolverInfo& infoGlobal, btIDebugDraw* debugDrawer);
|
|
||||||
|
|
||||||
|
|
||||||
///clear internal cached data and reset random seed
|
///clear internal cached data and reset random seed
|
||||||
virtual void reset();
|
virtual void reset();
|
||||||
|
|
||||||
unsigned long btRand2();
|
unsigned long btRand2();
|
||||||
int btRandInt2(int n);
|
|
||||||
|
|
||||||
static unsigned long btRand2a(unsigned long& seed);
|
int btRandInt2(int n);
|
||||||
static int btRandInt2a(int n, unsigned long& seed);
|
|
||||||
|
|
||||||
void setRandSeed(unsigned long seed)
|
void setRandSeed(unsigned long seed)
|
||||||
{
|
{
|
||||||
@@ -305,18 +201,14 @@ public:
|
|||||||
|
|
||||||
|
|
||||||
///Various implementations of solving a single constraint row using a generic equality constraint, using scalar reference, SSE2 or SSE4
|
///Various implementations of solving a single constraint row using a generic equality constraint, using scalar reference, SSE2 or SSE4
|
||||||
static btSingleConstraintRowSolver getScalarConstraintRowSolverGeneric();
|
btSingleConstraintRowSolver getScalarConstraintRowSolverGeneric();
|
||||||
static btSingleConstraintRowSolver getSSE2ConstraintRowSolverGeneric();
|
btSingleConstraintRowSolver getSSE2ConstraintRowSolverGeneric();
|
||||||
static btSingleConstraintRowSolver getSSE4_1ConstraintRowSolverGeneric();
|
btSingleConstraintRowSolver getSSE4_1ConstraintRowSolverGeneric();
|
||||||
|
|
||||||
///Various implementations of solving a single constraint row using an inequality (lower limit) constraint, using scalar reference, SSE2 or SSE4
|
///Various implementations of solving a single constraint row using an inequality (lower limit) constraint, using scalar reference, SSE2 or SSE4
|
||||||
static btSingleConstraintRowSolver getScalarConstraintRowSolverLowerLimit();
|
btSingleConstraintRowSolver getScalarConstraintRowSolverLowerLimit();
|
||||||
static btSingleConstraintRowSolver getSSE2ConstraintRowSolverLowerLimit();
|
btSingleConstraintRowSolver getSSE2ConstraintRowSolverLowerLimit();
|
||||||
static btSingleConstraintRowSolver getSSE4_1ConstraintRowSolverLowerLimit();
|
btSingleConstraintRowSolver getSSE4_1ConstraintRowSolverLowerLimit();
|
||||||
|
|
||||||
static btSingleConstraintRowSolver getScalarSplitPenetrationImpulseGeneric();
|
|
||||||
static btSingleConstraintRowSolver getSSE2SplitPenetrationImpulseGeneric();
|
|
||||||
|
|
||||||
btSolverAnalyticsData m_analyticsData;
|
btSolverAnalyticsData m_analyticsData;
|
||||||
};
|
};
|
||||||
|
|
||||||
|
|||||||
@@ -46,31 +46,14 @@ protected:
|
|||||||
|
|
||||||
void writeToSolverBody(btCollisionObject** bodies, int numBodies, const btContactSolverInfo& infoGlobal)
|
void writeToSolverBody(btCollisionObject** bodies, int numBodies, const btContactSolverInfo& infoGlobal)
|
||||||
{
|
{
|
||||||
btSISolverSingleIterationData siData(m_tmpSolverBodyPool,
|
|
||||||
m_tmpSolverContactConstraintPool,
|
|
||||||
m_tmpSolverNonContactConstraintPool,
|
|
||||||
m_tmpSolverContactFrictionConstraintPool,
|
|
||||||
m_tmpSolverContactRollingFrictionConstraintPool,
|
|
||||||
m_orderTmpConstraintPool,
|
|
||||||
m_orderNonContactConstraintPool,
|
|
||||||
m_orderFrictionConstraintPool,
|
|
||||||
m_tmpConstraintSizesPool,
|
|
||||||
m_resolveSingleConstraintRowGeneric,
|
|
||||||
m_resolveSingleConstraintRowLowerLimit,
|
|
||||||
m_resolveSplitPenetrationImpulse,
|
|
||||||
m_kinematicBodyUniqueIdToSolverBodyTable,
|
|
||||||
m_btSeed2,
|
|
||||||
m_fixedBodyId,
|
|
||||||
m_maxOverrideNumSolverIterations);
|
|
||||||
|
|
||||||
for (int i = 0; i < numBodies; i++)
|
for (int i = 0; i < numBodies; i++)
|
||||||
{
|
{
|
||||||
int bodyId = siData.getOrInitSolverBody(*bodies[i], infoGlobal.m_timeStep);
|
int bodyId = getOrInitSolverBody(*bodies[i], infoGlobal.m_timeStep);
|
||||||
|
|
||||||
btRigidBody* body = btRigidBody::upcast(bodies[i]);
|
btRigidBody* body = btRigidBody::upcast(bodies[i]);
|
||||||
if (body && body->getInvMass())
|
if (body && body->getInvMass())
|
||||||
{
|
{
|
||||||
btSolverBody& solverBody = siData.m_tmpSolverBodyPool[bodyId];
|
btSolverBody& solverBody = m_tmpSolverBodyPool[bodyId];
|
||||||
solverBody.m_linearVelocity = body->getLinearVelocity() - solverBody.m_deltaLinearVelocity;
|
solverBody.m_linearVelocity = body->getLinearVelocity() - solverBody.m_deltaLinearVelocity;
|
||||||
solverBody.m_angularVelocity = body->getAngularVelocity() - solverBody.m_deltaAngularVelocity;
|
solverBody.m_angularVelocity = body->getAngularVelocity() - solverBody.m_deltaAngularVelocity;
|
||||||
}
|
}
|
||||||
|
|||||||
Reference in New Issue
Block a user