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

original version written by Erwin Coumans, October 2013 More...

#include <btMLCPSolver.h>

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

Public Member Functions

 btMLCPSolver (btMLCPSolverInterface *solver)
 original version written by Erwin Coumans, October 2013 More...
 
virtual ~btMLCPSolver ()
 
void setMLCPSolver (btMLCPSolverInterface *solver)
 
int getNumFallbacks () const
 
void setNumFallbacks (int num)
 
virtual btConstraintSolverType getSolverType () const
 
- 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
 
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 *)
 

Protected Member Functions

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 void createMLCP (const btContactSolverInfo &infoGlobal)
 
virtual void createMLCPFast (const btContactSolverInfo &infoGlobal)
 
virtual bool solveMLCP (const btContactSolverInfo &infoGlobal)
 
- 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)
 
virtual void convertContacts (btPersistentManifold **manifoldPtr, int numManifolds, const btContactSolverInfo &infoGlobal)
 
void convertContact (btPersistentManifold *manifold, 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)
 
virtual void convertBodies (btCollisionObject **bodies, int numBodies, 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 void solveGroupCacheFriendlySplitImpulseIterations (btCollisionObject **bodies, int numBodies, btPersistentManifold **manifoldPtr, int numManifolds, btTypedConstraint **constraints, int numConstraints, const btContactSolverInfo &infoGlobal, btIDebugDraw *debugDrawer)
 
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)
 

Protected Attributes

btMatrixXu m_A
 
btVectorXu m_b
 
btVectorXu m_x
 
btVectorXu m_lo
 
btVectorXu m_hi
 
btVectorXu m_bSplit
 when using 'split impulse' we solve two separate (M)LCPs More...
 
btVectorXu m_xSplit
 
btVectorXu m_bSplit1
 
btVectorXu m_xSplit2
 
btAlignedObjectArray< int > m_limitDependencies
 
btAlignedObjectArray< btSolverConstraint * > m_allConstraintPtrArray
 
btMLCPSolverInterfacem_solver
 
int m_fallback
 
btMatrixXu m_scratchJ3
 The following scratch variables are not stateful – contents are cleared prior to each use. More...
 
btMatrixXu m_scratchJInvM3
 
btAlignedObjectArray< int > m_scratchOfs
 
btMatrixXu m_scratchMInv
 
btMatrixXu m_scratchJ
 
btMatrixXu m_scratchJTranspose
 
btMatrixXu m_scratchTmp
 
- 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...
 

Additional Inherited Members

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

Detailed Description

original version written by Erwin Coumans, October 2013

Definition at line 24 of file btMLCPSolver.h.

Constructor & Destructor Documentation

btMLCPSolver::btMLCPSolver ( btMLCPSolverInterface solver)

original version written by Erwin Coumans, October 2013

Definition at line 23 of file btMLCPSolver.cpp.

btMLCPSolver::~btMLCPSolver ( )
virtual

Definition at line 29 of file btMLCPSolver.cpp.

Member Function Documentation

void btMLCPSolver::createMLCP ( const btContactSolverInfo infoGlobal)
protectedvirtual

Definition at line 470 of file btMLCPSolver.cpp.

void btMLCPSolver::createMLCPFast ( const btContactSolverInfo infoGlobal)
protectedvirtual

fill the upper triangle of the matrix, to make it symmetric

Definition at line 154 of file btMLCPSolver.cpp.

int btMLCPSolver::getNumFallbacks ( ) const
inline

Definition at line 77 of file btMLCPSolver.h.

virtual btConstraintSolverType btMLCPSolver::getSolverType ( ) const
inlinevirtual

Reimplemented from btSequentialImpulseConstraintSolver.

Definition at line 86 of file btMLCPSolver.h.

void btMLCPSolver::setMLCPSolver ( btMLCPSolverInterface solver)
inline

Definition at line 72 of file btMLCPSolver.h.

void btMLCPSolver::setNumFallbacks ( int  num)
inline

Definition at line 81 of file btMLCPSolver.h.

btScalar btMLCPSolver::solveGroupCacheFriendlyIterations ( btCollisionObject **  bodies,
int  numBodies,
btPersistentManifold **  manifoldPtr,
int  numManifolds,
btTypedConstraint **  constraints,
int  numConstraints,
const btContactSolverInfo infoGlobal,
btIDebugDraw debugDrawer 
)
protectedvirtual

Reimplemented from btSequentialImpulseConstraintSolver.

Definition at line 586 of file btMLCPSolver.cpp.

btScalar btMLCPSolver::solveGroupCacheFriendlySetup ( btCollisionObject **  bodies,
int  numBodies,
btPersistentManifold **  manifoldPtr,
int  numManifolds,
btTypedConstraint **  constraints,
int  numConstraints,
const btContactSolverInfo infoGlobal,
btIDebugDraw debugDrawer 
)
protectedvirtual

The btSequentialImpulseConstraintSolver moves all friction constraints at the very end, we can also interleave them instead

Reimplemented from btSequentialImpulseConstraintSolver.

Definition at line 36 of file btMLCPSolver.cpp.

bool btMLCPSolver::solveMLCP ( const btContactSolverInfo infoGlobal)
protectedvirtual

Definition at line 120 of file btMLCPSolver.cpp.

Member Data Documentation

btMatrixXu btMLCPSolver::m_A
protected

Definition at line 29 of file btMLCPSolver.h.

btAlignedObjectArray<btSolverConstraint*> btMLCPSolver::m_allConstraintPtrArray
protected

Definition at line 42 of file btMLCPSolver.h.

btVectorXu btMLCPSolver::m_b
protected

Definition at line 30 of file btMLCPSolver.h.

btVectorXu btMLCPSolver::m_bSplit
protected

when using 'split impulse' we solve two separate (M)LCPs

Definition at line 36 of file btMLCPSolver.h.

btVectorXu btMLCPSolver::m_bSplit1
protected

Definition at line 38 of file btMLCPSolver.h.

int btMLCPSolver::m_fallback
protected

Definition at line 44 of file btMLCPSolver.h.

btVectorXu btMLCPSolver::m_hi
protected

Definition at line 33 of file btMLCPSolver.h.

btAlignedObjectArray<int> btMLCPSolver::m_limitDependencies
protected

Definition at line 41 of file btMLCPSolver.h.

btVectorXu btMLCPSolver::m_lo
protected

Definition at line 32 of file btMLCPSolver.h.

btMatrixXu btMLCPSolver::m_scratchJ
protected

Definition at line 53 of file btMLCPSolver.h.

btMatrixXu btMLCPSolver::m_scratchJ3
protected

The following scratch variables are not stateful – contents are cleared prior to each use.

They are only cached here to avoid extra memory allocations and deallocations and to ensure that multiple instances of the solver can be run in parallel.

Definition at line 49 of file btMLCPSolver.h.

btMatrixXu btMLCPSolver::m_scratchJInvM3
protected

Definition at line 50 of file btMLCPSolver.h.

btMatrixXu btMLCPSolver::m_scratchJTranspose
protected

Definition at line 54 of file btMLCPSolver.h.

btMatrixXu btMLCPSolver::m_scratchMInv
protected

Definition at line 52 of file btMLCPSolver.h.

btAlignedObjectArray<int> btMLCPSolver::m_scratchOfs
protected

Definition at line 51 of file btMLCPSolver.h.

btMatrixXu btMLCPSolver::m_scratchTmp
protected

Definition at line 55 of file btMLCPSolver.h.

btMLCPSolverInterface* btMLCPSolver::m_solver
protected

Definition at line 43 of file btMLCPSolver.h.

btVectorXu btMLCPSolver::m_x
protected

Definition at line 31 of file btMLCPSolver.h.

btVectorXu btMLCPSolver::m_xSplit
protected

Definition at line 37 of file btMLCPSolver.h.

btVectorXu btMLCPSolver::m_xSplit2
protected

Definition at line 39 of file btMLCPSolver.h.


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