Bullet Collision Detection & Physics Library
Classes | Public Member Functions | Static Public Attributes | Protected Member Functions | Protected Attributes | Static Protected Attributes | List of all members
btSequentialImpulseConstraintSolverMt Class Reference

btSequentialImpulseConstraintSolverMt More...

#include <btSequentialImpulseConstraintSolverMt.h>

Inheritance diagram for btSequentialImpulseConstraintSolverMt:
Inheritance graph
[legend]
Collaboration diagram for btSequentialImpulseConstraintSolverMt:
Collaboration graph
[legend]

Classes

struct  btContactManifoldCachedInfo
 
struct  JointParams
 

Public Member Functions

virtual void solveGroupCacheFriendlySplitImpulseIterations (btCollisionObject **bodies, int numBodies, btPersistentManifold **manifoldPtr, int numManifolds, btTypedConstraint **constraints, int numConstraints, const btContactSolverInfo &infoGlobal, btIDebugDraw *debugDrawer) BT_OVERRIDE
 
virtual btScalar solveSingleIteration (int iteration, btCollisionObject **bodies, int numBodies, btPersistentManifold **manifoldPtr, int numManifolds, btTypedConstraint **constraints, int numConstraints, const btContactSolverInfo &infoGlobal, btIDebugDraw *debugDrawer) BT_OVERRIDE
 
virtual btScalar solveGroupCacheFriendlySetup (btCollisionObject **bodies, int numBodies, btPersistentManifold **manifoldPtr, int numManifolds, btTypedConstraint **constraints, int numConstraints, const btContactSolverInfo &infoGlobal, btIDebugDraw *debugDrawer) BT_OVERRIDE
 
virtual btScalar solveGroupCacheFriendlyFinish (btCollisionObject **bodies, int numBodies, const btContactSolverInfo &infoGlobal) BT_OVERRIDE
 
void internalInitMultipleJoints (btTypedConstraint **constraints, int iBegin, int iEnd)
 
void internalConvertMultipleJoints (const btAlignedObjectArray< JointParams > &jointParamsArray, btTypedConstraint **constraints, int iBegin, int iEnd, const btContactSolverInfo &infoGlobal)
 
 BT_DECLARE_ALIGNED_ALLOCATOR ()
 
 btSequentialImpulseConstraintSolverMt ()
 
virtual ~btSequentialImpulseConstraintSolverMt ()
 
btScalar resolveMultipleJointConstraints (const btAlignedObjectArray< int > &consIndices, int batchBegin, int batchEnd, int iteration)
 
btScalar resolveMultipleContactConstraints (const btAlignedObjectArray< int > &consIndices, int batchBegin, int batchEnd)
 
btScalar resolveMultipleContactSplitPenetrationImpulseConstraints (const btAlignedObjectArray< int > &consIndices, int batchBegin, int batchEnd)
 
btScalar resolveMultipleContactFrictionConstraints (const btAlignedObjectArray< int > &consIndices, int batchBegin, int batchEnd)
 
btScalar resolveMultipleContactRollingFrictionConstraints (const btAlignedObjectArray< int > &consIndices, int batchBegin, int batchEnd)
 
btScalar resolveMultipleContactConstraintsInterleaved (const btAlignedObjectArray< int > &contactIndices, int batchBegin, int batchEnd)
 
void internalCollectContactManifoldCachedInfo (btContactManifoldCachedInfo *cachedInfoArray, btPersistentManifold **manifoldPtr, int numManifolds, const btContactSolverInfo &infoGlobal)
 
void internalAllocContactConstraints (const btContactManifoldCachedInfo *cachedInfoArray, int numManifolds)
 
void internalSetupContactConstraints (int iContactConstraint, const btContactSolverInfo &infoGlobal)
 
void internalConvertBodies (btCollisionObject **bodies, int iBegin, int iEnd, const btContactSolverInfo &infoGlobal)
 
void internalWriteBackContacts (int iBegin, int iEnd, const btContactSolverInfo &infoGlobal)
 
void internalWriteBackJoints (int iBegin, int iEnd, const btContactSolverInfo &infoGlobal)
 
void internalWriteBackBodies (int iBegin, int iEnd, const btContactSolverInfo &infoGlobal)
 
- Public Member Functions inherited from btSequentialImpulseConstraintSolver
 BT_DECLARE_ALIGNED_ALLOCATOR ()
 
 btSequentialImpulseConstraintSolver ()
 
virtual ~btSequentialImpulseConstraintSolver ()
 
virtual btScalar solveGroup (btCollisionObject **bodies, int numBodies, btPersistentManifold **manifold, int numManifolds, btTypedConstraint **constraints, int numConstraints, const btContactSolverInfo &info, btIDebugDraw *debugDrawer, btDispatcher *dispatcher)
 btSequentialImpulseConstraintSolver Sequentially applies impulses More...
 
virtual void reset ()
 clear internal cached data and reset random seed More...
 
unsigned long btRand2 ()
 
int btRandInt2 (int n)
 
void setRandSeed (unsigned long seed)
 
unsigned long getRandSeed () const
 
virtual btConstraintSolverType getSolverType () const
 
btSingleConstraintRowSolver getActiveConstraintRowSolverGeneric ()
 
void setConstraintRowSolverGeneric (btSingleConstraintRowSolver rowSolver)
 
btSingleConstraintRowSolver getActiveConstraintRowSolverLowerLimit ()
 
void setConstraintRowSolverLowerLimit (btSingleConstraintRowSolver rowSolver)
 
btSingleConstraintRowSolver getScalarConstraintRowSolverGeneric ()
 Various implementations of solving a single constraint row using a generic equality constraint, using scalar reference, SSE2 or SSE4. More...
 
btSingleConstraintRowSolver getSSE2ConstraintRowSolverGeneric ()
 
btSingleConstraintRowSolver getSSE4_1ConstraintRowSolverGeneric ()
 
btSingleConstraintRowSolver getScalarConstraintRowSolverLowerLimit ()
 Various implementations of solving a single constraint row using an inequality (lower limit) constraint, using scalar reference, SSE2 or SSE4. More...
 
btSingleConstraintRowSolver getSSE2ConstraintRowSolverLowerLimit ()
 
btSingleConstraintRowSolver getSSE4_1ConstraintRowSolverLowerLimit ()
 
- Public Member Functions inherited from btConstraintSolver
virtual ~btConstraintSolver ()
 
virtual void prepareSolve (int, int)
 
virtual void allSolved (const btContactSolverInfo &, class btIDebugDraw *)
 

Static Public Attributes

static bool s_allowNestedParallelForLoops = false
 
static int s_minimumContactManifoldsForBatching = 250
 
static btBatchedConstraints::BatchingMethod s_contactBatchingMethod = btBatchedConstraints::BATCHING_METHOD_SPATIAL_GRID_2D
 
static btBatchedConstraints::BatchingMethod s_jointBatchingMethod = btBatchedConstraints::BATCHING_METHOD_SPATIAL_GRID_2D
 
static int s_minBatchSize = 50
 
static int s_maxBatchSize = 100
 

Protected Member Functions

virtual void randomizeConstraintOrdering (int iteration, int numIterations)
 
virtual btScalar resolveAllJointConstraints (int iteration)
 
virtual btScalar resolveAllContactConstraints ()
 
virtual btScalar resolveAllContactFrictionConstraints ()
 
virtual btScalar resolveAllContactConstraintsInterleaved ()
 
virtual btScalar resolveAllRollingFrictionConstraints ()
 
virtual void setupBatchedContactConstraints ()
 
virtual void setupBatchedJointConstraints ()
 
virtual void convertJoints (btTypedConstraint **constraints, int numConstraints, const btContactSolverInfo &infoGlobal) BT_OVERRIDE
 
virtual void convertContacts (btPersistentManifold **manifoldPtr, int numManifolds, const btContactSolverInfo &infoGlobal) BT_OVERRIDE
 
virtual void convertBodies (btCollisionObject **bodies, int numBodies, const btContactSolverInfo &infoGlobal) BT_OVERRIDE
 
int getOrInitSolverBodyThreadsafe (btCollisionObject &body, btScalar timeStep)
 
void allocAllContactConstraints (btPersistentManifold **manifoldPtr, int numManifolds, const btContactSolverInfo &infoGlobal)
 
void setupAllContactConstraints (const btContactSolverInfo &infoGlobal)
 
void randomizeBatchedConstraintOrdering (btBatchedConstraints *batchedConstraints)
 
- Protected Member Functions inherited from btSequentialImpulseConstraintSolver
void setupSolverFunctions (bool useSimd)
 
void setupFrictionConstraint (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=0., btScalar cfmSlip=0.)
 
void setupTorsionalFrictionConstraint (btSolverConstraint &solverConstraint, const btVector3 &normalAxis, int solverBodyIdA, int solverBodyIdB, btManifoldPoint &cp, btScalar combinedTorsionalFriction, const btVector3 &rel_pos1, const btVector3 &rel_pos2, btCollisionObject *colObj0, btCollisionObject *colObj1, btScalar relaxation, btScalar desiredVelocity=0., btScalar cfmSlip=0.)
 
btSolverConstraintaddFrictionConstraint (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.)
 
btSolverConstraintaddTorsionalFrictionConstraint (const btVector3 &normalAxis, int solverBodyIdA, int solverBodyIdB, int frictionIndex, btManifoldPoint &cp, btScalar torsionalFriction, const btVector3 &rel_pos1, const btVector3 &rel_pos2, btCollisionObject *colObj0, btCollisionObject *colObj1, btScalar relaxation, btScalar desiredVelocity=0, btScalar cfmSlip=0.f)
 
void setupContactConstraint (btSolverConstraint &solverConstraint, int solverBodyIdA, int solverBodyIdB, btManifoldPoint &cp, const btContactSolverInfo &infoGlobal, btScalar &relaxation, const btVector3 &rel_pos1, const btVector3 &rel_pos2)
 
void setFrictionConstraintImpulse (btSolverConstraint &solverConstraint, int solverBodyIdA, int solverBodyIdB, btManifoldPoint &cp, const btContactSolverInfo &infoGlobal)
 
btScalar restitutionCurve (btScalar rel_vel, btScalar restitution, btScalar velocityThreshold)
 
void convertContact (btPersistentManifold *manifold, const btContactSolverInfo &infoGlobal)
 
void convertJoint (btSolverConstraint *currentConstraintRow, btTypedConstraint *constraint, const btTypedConstraint::btConstraintInfo1 &info1, int solverBodyIdA, int solverBodyIdB, const btContactSolverInfo &infoGlobal)
 
btScalar resolveSplitPenetrationSIMD (btSolverBody &bodyA, btSolverBody &bodyB, const btSolverConstraint &contactConstraint)
 
btScalar resolveSplitPenetrationImpulseCacheFriendly (btSolverBody &bodyA, btSolverBody &bodyB, const btSolverConstraint &contactConstraint)
 
int getOrInitSolverBody (btCollisionObject &body, btScalar timeStep)
 
void initSolverBody (btSolverBody *solverBody, btCollisionObject *collisionObject, btScalar timeStep)
 
btScalar resolveSingleConstraintRowGeneric (btSolverBody &bodyA, btSolverBody &bodyB, const btSolverConstraint &contactConstraint)
 
btScalar resolveSingleConstraintRowGenericSIMD (btSolverBody &bodyA, btSolverBody &bodyB, const btSolverConstraint &contactConstraint)
 
btScalar resolveSingleConstraintRowLowerLimit (btSolverBody &bodyA, btSolverBody &bodyB, const btSolverConstraint &contactConstraint)
 
btScalar resolveSingleConstraintRowLowerLimitSIMD (btSolverBody &bodyA, btSolverBody &bodyB, const btSolverConstraint &contactConstraint)
 
btScalar resolveSplitPenetrationImpulse (btSolverBody &bodyA, btSolverBody &bodyB, const btSolverConstraint &contactConstraint)
 
void writeBackContacts (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)
 
virtual btScalar solveGroupCacheFriendlyIterations (btCollisionObject **bodies, int numBodies, btPersistentManifold **manifoldPtr, int numManifolds, btTypedConstraint **constraints, int numConstraints, const btContactSolverInfo &infoGlobal, btIDebugDraw *debugDrawer)
 

Protected Attributes

btBatchedConstraints m_batchedContactConstraints
 
btBatchedConstraints m_batchedJointConstraints
 
int m_numFrictionDirections
 
bool m_useBatching
 
bool m_useObsoleteJointConstraints
 
btAlignedObjectArray< btContactManifoldCachedInfom_manifoldCachedInfoArray
 
btAlignedObjectArray< int > m_rollingFrictionIndexTable
 
btSpinMutex m_bodySolverArrayMutex
 
char m_antiFalseSharingPadding [CACHE_LINE_SIZE]
 
btSpinMutex m_kinematicBodyUniqueIdToSolverBodyTableMutex
 
btAlignedObjectArray< char > m_scratchMemory
 
- Protected Attributes inherited from btSequentialImpulseConstraintSolver
btAlignedObjectArray< btSolverBodym_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::btConstraintInfo1m_tmpConstraintSizesPool
 
int m_maxOverrideNumSolverIterations
 
int m_fixedBodyId
 
btAlignedObjectArray< int > m_kinematicBodyUniqueIdToSolverBodyTable
 
btSingleConstraintRowSolver m_resolveSingleConstraintRowGeneric
 
btSingleConstraintRowSolver m_resolveSingleConstraintRowLowerLimit
 
btSingleConstraintRowSolver m_resolveSplitPenetrationImpulse
 
int m_cachedSolverMode
 
btScalar m_leastSquaresResidual
 
unsigned long m_btSeed2
 m_btSeed2 is used for re-arranging the constraint rows. improves convergence/quality of friction More...
 

Static Protected Attributes

static const int CACHE_LINE_SIZE = 64
 

Additional Inherited Members

- Static Protected Member Functions inherited from btSequentialImpulseConstraintSolver
static void applyAnisotropicFriction (btCollisionObject *colObj, btVector3 &frictionDirection, int frictionMode)
 

Detailed Description

btSequentialImpulseConstraintSolverMt

A multithreaded variant of the sequential impulse constraint solver. The constraints to be solved are grouped into batches and phases where each batch of constraints within a given phase can be solved in parallel with the rest. Ideally we want as few phases as possible, and each phase should have many batches, and all of the batches should have about the same number of constraints. This method works best on a large island of many constraints.

Supports all of the features of the normal sequential impulse solver such as:

When the SOLVER_INTERLEAVE_CONTACT_AND_FRICTION_CONSTRAINTS flag is enabled, unlike the normal SequentialImpulse solver, the rolling friction is interleaved as well. Interleaving the contact penetration constraints with friction reduces the number of parallel loops that need to be done, which reduces threading overhead so it can be a performance win, however, it does seem to produce a less stable simulation, at least on stacks of blocks.

When the SOLVER_RANDMIZE_ORDER flag is enabled, the ordering of phases, and the ordering of constraints within each batch is randomized, however it does not swap constraints between batches. This is to avoid regenerating the batches for each solver iteration which would be quite costly in performance.

Note that a non-zero leastSquaresResidualThreshold could possibly affect the determinism of the simulation if the task scheduler's parallelSum operation is non-deterministic. The parallelSum operation can be non-deterministic because floating point addition is not associative due to rounding errors. The task scheduler can and should ensure that the result of any parallelSum operation is deterministic.

Definition at line 56 of file btSequentialImpulseConstraintSolverMt.h.

Constructor & Destructor Documentation

btSequentialImpulseConstraintSolverMt::btSequentialImpulseConstraintSolverMt ( )

Definition at line 36 of file btSequentialImpulseConstraintSolverMt.cpp.

btSequentialImpulseConstraintSolverMt::~btSequentialImpulseConstraintSolverMt ( )
virtual

Definition at line 44 of file btSequentialImpulseConstraintSolverMt.cpp.

Member Function Documentation

void btSequentialImpulseConstraintSolverMt::allocAllContactConstraints ( btPersistentManifold **  manifoldPtr,
int  numManifolds,
const btContactSolverInfo infoGlobal 
)
protected

Definition at line 533 of file btSequentialImpulseConstraintSolverMt.cpp.

btSequentialImpulseConstraintSolverMt::BT_DECLARE_ALIGNED_ALLOCATOR ( )
void btSequentialImpulseConstraintSolverMt::convertBodies ( btCollisionObject **  bodies,
int  numBodies,
const btContactSolverInfo infoGlobal 
)
protectedvirtual
void btSequentialImpulseConstraintSolverMt::convertContacts ( btPersistentManifold **  manifoldPtr,
int  numManifolds,
const btContactSolverInfo infoGlobal 
)
protectedvirtual
void btSequentialImpulseConstraintSolverMt::convertJoints ( btTypedConstraint **  constraints,
int  numConstraints,
const btContactSolverInfo infoGlobal 
)
protectedvirtual

setup the btSolverConstraints

Reimplemented from btSequentialImpulseConstraintSolver.

Definition at line 714 of file btSequentialImpulseConstraintSolverMt.cpp.

int btSequentialImpulseConstraintSolverMt::getOrInitSolverBodyThreadsafe ( btCollisionObject body,
btScalar  timeStep 
)
protected

Definition at line 312 of file btSequentialImpulseConstraintSolverMt.cpp.

void btSequentialImpulseConstraintSolverMt::internalAllocContactConstraints ( const btContactManifoldCachedInfo cachedInfoArray,
int  numManifolds 
)

Definition at line 468 of file btSequentialImpulseConstraintSolverMt.cpp.

void btSequentialImpulseConstraintSolverMt::internalCollectContactManifoldCachedInfo ( btContactManifoldCachedInfo cachedInfoArray,
btPersistentManifold **  manifoldPtr,
int  numManifolds,
const btContactSolverInfo infoGlobal 
)

Definition at line 405 of file btSequentialImpulseConstraintSolverMt.cpp.

void btSequentialImpulseConstraintSolverMt::internalConvertBodies ( btCollisionObject **  bodies,
int  iBegin,
int  iEnd,
const btContactSolverInfo infoGlobal 
)

Definition at line 776 of file btSequentialImpulseConstraintSolverMt.cpp.

void btSequentialImpulseConstraintSolverMt::internalConvertMultipleJoints ( const btAlignedObjectArray< JointParams > &  jointParamsArray,
btTypedConstraint **  constraints,
int  iBegin,
int  iEnd,
const btContactSolverInfo infoGlobal 
)

Definition at line 667 of file btSequentialImpulseConstraintSolverMt.cpp.

void btSequentialImpulseConstraintSolverMt::internalInitMultipleJoints ( btTypedConstraint **  constraints,
int  iBegin,
int  iEnd 
)

Definition at line 620 of file btSequentialImpulseConstraintSolverMt.cpp.

void btSequentialImpulseConstraintSolverMt::internalSetupContactConstraints ( int  iContactConstraint,
const btContactSolverInfo infoGlobal 
)

Bullet has several options to set the friction directions By default, each contact has only a single friction direction that is recomputed automatically very frame based on the relative linear velocity. If the relative velocity it zero, it will automatically compute a friction direction.

You can also enable two friction directions, using the SOLVER_USE_2_FRICTION_DIRECTIONS. In that case, the second friction direction will be orthogonal to both contact normal and first friction direction.

If you choose SOLVER_DISABLE_VELOCITY_DEPENDENT_FRICTION_DIRECTION, then the friction will be independent from the relative projected velocity.

The user can manually override the friction directions for certain contacts using a contact callback, and set the cp.m_lateralFrictionInitialized to true In that case, you can set the target relative motion in each friction direction (cp.m_contactMotion1 and cp.m_contactMotion2) this will give a conveyor belt effect

Definition at line 75 of file btSequentialImpulseConstraintSolverMt.cpp.

void btSequentialImpulseConstraintSolverMt::internalWriteBackBodies ( int  iBegin,
int  iEnd,
const btContactSolverInfo infoGlobal 
)

Definition at line 1533 of file btSequentialImpulseConstraintSolverMt.cpp.

void btSequentialImpulseConstraintSolverMt::internalWriteBackContacts ( int  iBegin,
int  iEnd,
const btContactSolverInfo infoGlobal 
)

Definition at line 1507 of file btSequentialImpulseConstraintSolverMt.cpp.

void btSequentialImpulseConstraintSolverMt::internalWriteBackJoints ( int  iBegin,
int  iEnd,
const btContactSolverInfo infoGlobal 
)

Definition at line 1526 of file btSequentialImpulseConstraintSolverMt.cpp.

void btSequentialImpulseConstraintSolverMt::randomizeBatchedConstraintOrdering ( btBatchedConstraints batchedConstraints)
protected

Definition at line 1216 of file btSequentialImpulseConstraintSolverMt.cpp.

void btSequentialImpulseConstraintSolverMt::randomizeConstraintOrdering ( int  iteration,
int  numIterations 
)
protectedvirtual

Definition at line 1241 of file btSequentialImpulseConstraintSolverMt.cpp.

btScalar btSequentialImpulseConstraintSolverMt::resolveAllContactConstraints ( )
protectedvirtual

Definition at line 1321 of file btSequentialImpulseConstraintSolverMt.cpp.

btScalar btSequentialImpulseConstraintSolverMt::resolveAllContactConstraintsInterleaved ( )
protectedvirtual

Definition at line 1403 of file btSequentialImpulseConstraintSolverMt.cpp.

btScalar btSequentialImpulseConstraintSolverMt::resolveAllContactFrictionConstraints ( )
protectedvirtual

Definition at line 1362 of file btSequentialImpulseConstraintSolverMt.cpp.

btScalar btSequentialImpulseConstraintSolverMt::resolveAllJointConstraints ( int  iteration)
protectedvirtual

Definition at line 1280 of file btSequentialImpulseConstraintSolverMt.cpp.

btScalar btSequentialImpulseConstraintSolverMt::resolveAllRollingFrictionConstraints ( )
protectedvirtual

Definition at line 1444 of file btSequentialImpulseConstraintSolverMt.cpp.

btScalar btSequentialImpulseConstraintSolverMt::resolveMultipleContactConstraints ( const btAlignedObjectArray< int > &  consIndices,
int  batchBegin,
int  batchEnd 
)

Definition at line 1056 of file btSequentialImpulseConstraintSolverMt.cpp.

btScalar btSequentialImpulseConstraintSolverMt::resolveMultipleContactConstraintsInterleaved ( const btAlignedObjectArray< int > &  contactIndices,
int  batchBegin,
int  batchEnd 
)

Definition at line 1145 of file btSequentialImpulseConstraintSolverMt.cpp.

btScalar btSequentialImpulseConstraintSolverMt::resolveMultipleContactFrictionConstraints ( const btAlignedObjectArray< int > &  consIndices,
int  batchBegin,
int  batchEnd 
)

Definition at line 1072 of file btSequentialImpulseConstraintSolverMt.cpp.

btScalar btSequentialImpulseConstraintSolverMt::resolveMultipleContactRollingFrictionConstraints ( const btAlignedObjectArray< int > &  consIndices,
int  batchBegin,
int  batchEnd 
)

Definition at line 1104 of file btSequentialImpulseConstraintSolverMt.cpp.

btScalar btSequentialImpulseConstraintSolverMt::resolveMultipleContactSplitPenetrationImpulseConstraints ( const btAlignedObjectArray< int > &  consIndices,
int  batchBegin,
int  batchEnd 
)

Definition at line 896 of file btSequentialImpulseConstraintSolverMt.cpp.

btScalar btSequentialImpulseConstraintSolverMt::resolveMultipleJointConstraints ( const btAlignedObjectArray< int > &  consIndices,
int  batchBegin,
int  batchEnd,
int  iteration 
)

Definition at line 1037 of file btSequentialImpulseConstraintSolverMt.cpp.

void btSequentialImpulseConstraintSolverMt::setupAllContactConstraints ( const btContactSolverInfo infoGlobal)
protected

Definition at line 287 of file btSequentialImpulseConstraintSolverMt.cpp.

void btSequentialImpulseConstraintSolverMt::setupBatchedContactConstraints ( )
protectedvirtual

Definition at line 49 of file btSequentialImpulseConstraintSolverMt.cpp.

void btSequentialImpulseConstraintSolverMt::setupBatchedJointConstraints ( )
protectedvirtual

Definition at line 62 of file btSequentialImpulseConstraintSolverMt.cpp.

btScalar btSequentialImpulseConstraintSolverMt::solveGroupCacheFriendlyFinish ( btCollisionObject **  bodies,
int  numBodies,
const btContactSolverInfo infoGlobal 
)
virtual
btScalar btSequentialImpulseConstraintSolverMt::solveGroupCacheFriendlySetup ( btCollisionObject **  bodies,
int  numBodies,
btPersistentManifold **  manifoldPtr,
int  numManifolds,
btTypedConstraint **  constraints,
int  numConstraints,
const btContactSolverInfo infoGlobal,
btIDebugDraw debugDrawer 
)
virtual
void btSequentialImpulseConstraintSolverMt::solveGroupCacheFriendlySplitImpulseIterations ( btCollisionObject **  bodies,
int  numBodies,
btPersistentManifold **  manifoldPtr,
int  numManifolds,
btTypedConstraint **  constraints,
int  numConstraints,
const btContactSolverInfo infoGlobal,
btIDebugDraw debugDrawer 
)
virtual
btScalar btSequentialImpulseConstraintSolverMt::solveSingleIteration ( int  iteration,
btCollisionObject **  bodies,
int  numBodies,
btPersistentManifold **  manifoldPtr,
int  numManifolds,
btTypedConstraint **  constraints,
int  numConstraints,
const btContactSolverInfo infoGlobal,
btIDebugDraw debugDrawer 
)
virtual

solve all joint constraints

Reimplemented from btSequentialImpulseConstraintSolver.

Definition at line 974 of file btSequentialImpulseConstraintSolverMt.cpp.

Member Data Documentation

const int btSequentialImpulseConstraintSolverMt::CACHE_LINE_SIZE = 64
staticprotected

Definition at line 95 of file btSequentialImpulseConstraintSolverMt.h.

char btSequentialImpulseConstraintSolverMt::m_antiFalseSharingPadding[CACHE_LINE_SIZE]
protected

Definition at line 105 of file btSequentialImpulseConstraintSolverMt.h.

btBatchedConstraints btSequentialImpulseConstraintSolverMt::m_batchedContactConstraints
protected

Definition at line 97 of file btSequentialImpulseConstraintSolverMt.h.

btBatchedConstraints btSequentialImpulseConstraintSolverMt::m_batchedJointConstraints
protected

Definition at line 98 of file btSequentialImpulseConstraintSolverMt.h.

btSpinMutex btSequentialImpulseConstraintSolverMt::m_bodySolverArrayMutex
protected

Definition at line 104 of file btSequentialImpulseConstraintSolverMt.h.

btSpinMutex btSequentialImpulseConstraintSolverMt::m_kinematicBodyUniqueIdToSolverBodyTableMutex
protected

Definition at line 106 of file btSequentialImpulseConstraintSolverMt.h.

btAlignedObjectArray<btContactManifoldCachedInfo> btSequentialImpulseConstraintSolverMt::m_manifoldCachedInfoArray
protected

Definition at line 102 of file btSequentialImpulseConstraintSolverMt.h.

int btSequentialImpulseConstraintSolverMt::m_numFrictionDirections
protected

Definition at line 99 of file btSequentialImpulseConstraintSolverMt.h.

btAlignedObjectArray<int> btSequentialImpulseConstraintSolverMt::m_rollingFrictionIndexTable
protected

Definition at line 103 of file btSequentialImpulseConstraintSolverMt.h.

btAlignedObjectArray<char> btSequentialImpulseConstraintSolverMt::m_scratchMemory
protected

Definition at line 107 of file btSequentialImpulseConstraintSolverMt.h.

bool btSequentialImpulseConstraintSolverMt::m_useBatching
protected

Definition at line 100 of file btSequentialImpulseConstraintSolverMt.h.

bool btSequentialImpulseConstraintSolverMt::m_useObsoleteJointConstraints
protected

Definition at line 101 of file btSequentialImpulseConstraintSolverMt.h.

bool btSequentialImpulseConstraintSolverMt::s_allowNestedParallelForLoops = false
static

Definition at line 87 of file btSequentialImpulseConstraintSolverMt.h.

btBatchedConstraints::BatchingMethod btSequentialImpulseConstraintSolverMt::s_contactBatchingMethod = btBatchedConstraints::BATCHING_METHOD_SPATIAL_GRID_2D
static

Definition at line 89 of file btSequentialImpulseConstraintSolverMt.h.

btBatchedConstraints::BatchingMethod btSequentialImpulseConstraintSolverMt::s_jointBatchingMethod = btBatchedConstraints::BATCHING_METHOD_SPATIAL_GRID_2D
static

Definition at line 90 of file btSequentialImpulseConstraintSolverMt.h.

int btSequentialImpulseConstraintSolverMt::s_maxBatchSize = 100
static

Definition at line 92 of file btSequentialImpulseConstraintSolverMt.h.

int btSequentialImpulseConstraintSolverMt::s_minBatchSize = 50
static

Definition at line 91 of file btSequentialImpulseConstraintSolverMt.h.

int btSequentialImpulseConstraintSolverMt::s_minimumContactManifoldsForBatching = 250
static

Definition at line 88 of file btSequentialImpulseConstraintSolverMt.h.


The documentation for this class was generated from the following files: