16 #ifndef BT_MULTIBODY_MLCP_CONSTRAINT_SOLVER_H    17 #define BT_MULTIBODY_MLCP_CONSTRAINT_SOLVER_H   187 #endif  // BT_MULTIBODY_MLCP_CONSTRAINT_SOLVER_H btAlignedObjectArray< btSolverConstraint * > m_allConstraintPtrArray
Array of all the rigid body constraints. 
void createMLCPFastMultiBody(const btContactSolverInfo &infoGlobal)
Constructs MLCP terms for constraints of two multi-bodies or one rigid body and one multibody...
btPersistentManifold is a contact point cache, it stays persistent as long as objects are overlapping...
virtual bool solveMLCP(const btContactSolverInfo &infoGlobal)
Solves MLCP and returns the success. 
btVectorXu m_xSplit
Split impulse cache vector corresponding to m_x. 
BT_DECLARE_ALIGNED_ALLOCATOR()
btVectorXu m_hi
Upper bound of constraint impulse, m_x. 
btConstraintSolverType
btConstraintSolver provides solver interface 
int m_fallback
Count of fallbacks of using btSequentialImpulseConstraintSolver, which happens when the MLCP solver f...
btVectorXu m_x
Constraint impulse, which is an output of MLCP solving. 
void createMLCPFastRigidBody(const btContactSolverInfo &infoGlobal)
Constructs MLCP terms for constraints of two rigid bodies. 
btScalar solveGroupCacheFriendlySetup(btCollisionObject **bodies, int numBodies, btPersistentManifold **manifoldPtr, int numManifolds, btTypedConstraint **constraints, int numConstraints, const btContactSolverInfo &infoGlobal, btIDebugDraw *debugDrawer) BT_OVERRIDE
int getNumFallbacks() const 
Returns the number of fallbacks of using btSequentialImpulseConstraintSolver, which happens when the ...
btVectorXu m_multiBodyLo
Lower bound of constraint impulse, m_x. 
void setNumFallbacks(int num)
Sets the number of fallbacks. This function may be used to reset the number to zero. 
void setMLCPSolver(btMLCPSolverInterface *solver)
Sets MLCP solver. Assumed it's not null. 
btMatrixXu m_scratchJInvM3
Cache variable for constraint Jacobian times inverse mass matrix. 
btMatrixXu m_multiBodyA
A matrix in the MLCP formulation. 
original version written by Erwin Coumans, October 2013 
btScalar solveGroupCacheFriendlyIterations(btCollisionObject **bodies, int numBodies, btPersistentManifold **manifoldPtr, int numManifolds, btTypedConstraint **constraints, int numConstraints, const btContactSolverInfo &infoGlobal, btIDebugDraw *debugDrawer) BT_OVERRIDE
btAlignedObjectArray< int > m_multiBodyLimitDependencies
Indices of normal contact constraint associated with frictional contact constraint for multibodies...
btCollisionObject can be used to manage collision detection objects. 
The btIDebugDraw interface class allows hooking up a debug renderer to visually debug simulations...
btMatrixXu m_A
A matrix in the MLCP formulation. 
btAlignedObjectArray< int > m_scratchOfs
Cache variable for offsets. 
btAlignedObjectArray< int > m_limitDependencies
Indices of normal contact constraint associated with frictional contact constraint for rigid bodies...
btVectorXu m_b
b vector in the MLCP formulation. 
btAlignedObjectArray< btMultiBodySolverConstraint * > m_multiBodyAllConstraintPtrArray
Array of all the multibody constraints. 
TypedConstraint is the baseclass for Bullet constraints and vehicles. 
btVectorXu m_multiBodyHi
Upper bound of constraint impulse, m_x. 
btMLCPSolverInterface * m_solver
MLCP solver. 
virtual void createMLCPFast(const btContactSolverInfo &infoGlobal)
Constructs MLCP terms, which are m_A, m_b, m_lo, and m_hi. 
btVectorXu m_bSplit
Split impulse Cache vector corresponding to m_b. 
btVectorXu m_multiBodyB
b vector in the MLCP formulation. 
btVectorXu m_multiBodyX
Constraint impulse, which is an output of MLCP solving. 
float btScalar
The btScalar type abstracts floating point numbers, to easily switch between double and single floati...
btVectorXu m_lo
Lower bound of constraint impulse, m_x. 
btMatrixXu m_scratchJ3
Cache variable for constraint Jacobian matrix. 
virtual btConstraintSolverType getSolverType() const 
Returns the constraint solver type.