Bullet Collision Detection & Physics Library
btSequentialImpulseConstraintSolverMt.cpp
Go to the documentation of this file.
1 /*
2 Bullet Continuous Collision Detection and Physics Library
3 Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/
4 
5 This software is provided 'as-is', without any express or implied warranty.
6 In no event will the authors be held liable for any damages arising from the use of this software.
7 Permission is granted to anyone to use this software for any purpose,
8 including commercial applications, and to alter it and redistribute it freely,
9 subject to the following restrictions:
10 
11 1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required.
12 2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software.
13 3. This notice may not be removed or altered from any source distribution.
14 */
15 
16 
18 
19 #include "LinearMath/btQuickprof.h"
20 
22 
25 
26 
27 
28 bool btSequentialImpulseConstraintSolverMt::s_allowNestedParallelForLoops = false; // some task schedulers don't like nested loops
34 
35 
37 {
39  m_useBatching = false;
41 }
42 
43 
45 {
46 }
47 
48 
50 {
51  BT_PROFILE("setupBatchedContactConstraints");
58  );
59 }
60 
61 
63 {
64  BT_PROFILE("setupBatchedJointConstraints");
71  );
72 }
73 
74 
76 {
77  btSolverConstraint& contactConstraint = m_tmpSolverContactConstraintPool[iContactConstraint];
78 
79  btVector3 rel_pos1;
80  btVector3 rel_pos2;
81  btScalar relaxation;
82 
83  int solverBodyIdA = contactConstraint.m_solverBodyIdA;
84  int solverBodyIdB = contactConstraint.m_solverBodyIdB;
85 
86  btSolverBody* solverBodyA = &m_tmpSolverBodyPool[ solverBodyIdA ];
87  btSolverBody* solverBodyB = &m_tmpSolverBodyPool[ solverBodyIdB ];
88 
89  btRigidBody* colObj0 = solverBodyA->m_originalBody;
90  btRigidBody* colObj1 = solverBodyB->m_originalBody;
91 
92  btManifoldPoint& cp = *static_cast<btManifoldPoint*>( contactConstraint.m_originalContactPoint );
93 
94  const btVector3& pos1 = cp.getPositionWorldOnA();
95  const btVector3& pos2 = cp.getPositionWorldOnB();
96 
97  rel_pos1 = pos1 - solverBodyA->getWorldTransform().getOrigin();
98  rel_pos2 = pos2 - solverBodyB->getWorldTransform().getOrigin();
99 
100  btVector3 vel1;
101  btVector3 vel2;
102 
103  solverBodyA->getVelocityInLocalPointNoDelta( rel_pos1, vel1 );
104  solverBodyB->getVelocityInLocalPointNoDelta( rel_pos2, vel2 );
105 
106  btVector3 vel = vel1 - vel2;
107  btScalar rel_vel = cp.m_normalWorldOnB.dot( vel );
108 
109  setupContactConstraint( contactConstraint, solverBodyIdA, solverBodyIdB, cp, infoGlobal, relaxation, rel_pos1, rel_pos2 );
110 
111  // setup rolling friction constraints
112  int rollingFrictionIndex = m_rollingFrictionIndexTable[iContactConstraint];
113  if (rollingFrictionIndex >= 0)
114  {
115  btSolverConstraint& spinningFrictionConstraint = m_tmpSolverContactRollingFrictionConstraintPool[ rollingFrictionIndex ];
116  btAssert( spinningFrictionConstraint.m_frictionIndex == iContactConstraint );
117  setupTorsionalFrictionConstraint( spinningFrictionConstraint,
118  cp.m_normalWorldOnB,
119  solverBodyIdA,
120  solverBodyIdB,
121  cp,
123  rel_pos1,
124  rel_pos2,
125  colObj0,
126  colObj1,
127  relaxation,
128  0.0f,
129  0.0f
130  );
131  btVector3 axis[2];
132  btPlaneSpace1( cp.m_normalWorldOnB, axis[0], axis[1] );
133  axis[0].normalize();
134  axis[1].normalize();
135 
140  // put the largest axis first
141  if (axis[1].length2() > axis[0].length2())
142  {
143  btSwap(axis[0], axis[1]);
144  }
145  const btScalar kRollingFrictionThreshold = 0.001f;
146  for (int i = 0; i < 2; ++i)
147  {
148  int iRollingFric = rollingFrictionIndex + 1 + i;
149  btSolverConstraint& rollingFrictionConstraint = m_tmpSolverContactRollingFrictionConstraintPool[ iRollingFric ];
150  btAssert(rollingFrictionConstraint.m_frictionIndex == iContactConstraint);
151  btVector3 dir = axis[i];
152  if ( dir.length() > kRollingFrictionThreshold )
153  {
154  setupTorsionalFrictionConstraint( rollingFrictionConstraint,
155  dir,
156  solverBodyIdA,
157  solverBodyIdB,
158  cp,
160  rel_pos1,
161  rel_pos2,
162  colObj0,
163  colObj1,
164  relaxation,
165  0.0f,
166  0.0f
167  );
168  }
169  else
170  {
171  rollingFrictionConstraint.m_frictionIndex = -1; // disable constraint
172  }
173  }
174  }
175 
176  // setup friction constraints
177  // setupFrictionConstraint(solverConstraint, normalAxis, solverBodyIdA, solverBodyIdB, cp, rel_pos1, rel_pos2, colObj0, colObj1, relaxation, infoGlobal, desiredVelocity, cfmSlip);
178  {
183 
194  btSolverConstraint* frictionConstraint1 = &m_tmpSolverContactFrictionConstraintPool[contactConstraint.m_frictionIndex];
195  btAssert(frictionConstraint1->m_frictionIndex == iContactConstraint);
196 
197  btSolverConstraint* frictionConstraint2 = NULL;
199  {
200  frictionConstraint2 = &m_tmpSolverContactFrictionConstraintPool[contactConstraint.m_frictionIndex + 1];
201  btAssert( frictionConstraint2->m_frictionIndex == iContactConstraint );
202  }
203 
205  {
206  cp.m_lateralFrictionDir1 = vel - cp.m_normalWorldOnB * rel_vel;
207  btScalar lat_rel_vel = cp.m_lateralFrictionDir1.length2();
208  if ( !( infoGlobal.m_solverMode & SOLVER_DISABLE_VELOCITY_DEPENDENT_FRICTION_DIRECTION ) && lat_rel_vel > SIMD_EPSILON )
209  {
210  cp.m_lateralFrictionDir1 *= 1.f / btSqrt( lat_rel_vel );
213  setupFrictionConstraint( *frictionConstraint1, cp.m_lateralFrictionDir1, solverBodyIdA, solverBodyIdB, cp, rel_pos1, rel_pos2, colObj0, colObj1, relaxation, infoGlobal );
214 
215  if ( frictionConstraint2 )
216  {
221  setupFrictionConstraint( *frictionConstraint2, cp.m_lateralFrictionDir2, solverBodyIdA, solverBodyIdB, cp, rel_pos1, rel_pos2, colObj0, colObj1, relaxation, infoGlobal );
222  }
223  }
224  else
225  {
227 
230  setupFrictionConstraint( *frictionConstraint1, cp.m_lateralFrictionDir1, solverBodyIdA, solverBodyIdB, cp, rel_pos1, rel_pos2, colObj0, colObj1, relaxation, infoGlobal );
231 
232  if ( frictionConstraint2 )
233  {
236  setupFrictionConstraint( *frictionConstraint2, cp.m_lateralFrictionDir2, solverBodyIdA, solverBodyIdB, cp, rel_pos1, rel_pos2, colObj0, colObj1, relaxation, infoGlobal );
237  }
238 
240  {
242  }
243  }
244  }
245  else
246  {
247  setupFrictionConstraint( *frictionConstraint1, cp.m_lateralFrictionDir1, solverBodyIdA, solverBodyIdB, cp, rel_pos1, rel_pos2, colObj0, colObj1, relaxation, infoGlobal, cp.m_contactMotion1, cp.m_frictionCFM );
248  if ( frictionConstraint2 )
249  {
250  setupFrictionConstraint( *frictionConstraint2, cp.m_lateralFrictionDir2, solverBodyIdA, solverBodyIdB, cp, rel_pos1, rel_pos2, colObj0, colObj1, relaxation, infoGlobal, cp.m_contactMotion2, cp.m_frictionCFM );
251  }
252  }
253  }
254 
255  setFrictionConstraintImpulse( contactConstraint, solverBodyIdA, solverBodyIdB, cp, infoGlobal );
256 }
257 
258 
260 {
264 
266  {
267  m_solver = solver;
268  m_bc = bc;
269  m_infoGlobal = &infoGlobal;
270  }
271  void forLoop( int iBegin, int iEnd ) const BT_OVERRIDE
272  {
273  BT_PROFILE( "SetupContactConstraintsLoop" );
274  for ( int iBatch = iBegin; iBatch < iEnd; ++iBatch )
275  {
276  const btBatchedConstraints::Range& batch = m_bc->m_batches[ iBatch ];
277  for (int i = batch.begin; i < batch.end; ++i)
278  {
279  int iContact = m_bc->m_constraintIndices[i];
280  m_solver->internalSetupContactConstraints( iContact, *m_infoGlobal );
281  }
282  }
283  }
284 };
285 
286 
288 {
289  BT_PROFILE( "setupAllContactConstraints" );
290  if ( m_useBatching )
291  {
293  SetupContactConstraintsLoop loop( this, &batchedCons, infoGlobal );
294  for ( int iiPhase = 0; iiPhase < batchedCons.m_phases.size(); ++iiPhase )
295  {
296  int iPhase = batchedCons.m_phaseOrder[ iiPhase ];
297  const btBatchedConstraints::Range& phase = batchedCons.m_phases[ iPhase ];
298  int grainSize = 1;
299  btParallelFor( phase.begin, phase.end, grainSize, loop );
300  }
301  }
302  else
303  {
304  for ( int i = 0; i < m_tmpSolverContactConstraintPool.size(); ++i )
305  {
306  internalSetupContactConstraints( i, infoGlobal );
307  }
308  }
309 }
310 
311 
313 {
314  //
315  // getOrInitSolverBody is threadsafe only for a single thread per solver (with potentially multiple solvers)
316  //
317  // getOrInitSolverBodyThreadsafe -- attempts to be fully threadsafe (however may affect determinism)
318  //
319  int solverBodyId = -1;
320  bool isRigidBodyType = btRigidBody::upcast( &body ) != NULL;
321  if ( isRigidBodyType && !body.isStaticOrKinematicObject() )
322  {
323  // dynamic body
324  // Dynamic bodies can only be in one island, so it's safe to write to the companionId
325  solverBodyId = body.getCompanionId();
326  if ( solverBodyId < 0 )
327  {
329  // now that we have the lock, check again
330  solverBodyId = body.getCompanionId();
331  if ( solverBodyId < 0 )
332  {
333  solverBodyId = m_tmpSolverBodyPool.size();
334  btSolverBody& solverBody = m_tmpSolverBodyPool.expand();
335  initSolverBody( &solverBody, &body, timeStep );
336  body.setCompanionId( solverBodyId );
337  }
339  }
340  }
341  else if (isRigidBodyType && body.isKinematicObject())
342  {
343  //
344  // NOTE: must test for kinematic before static because some kinematic objects also
345  // identify as "static"
346  //
347  // Kinematic bodies can be in multiple islands at once, so it is a
348  // race condition to write to them, so we use an alternate method
349  // to record the solverBodyId
350  int uniqueId = body.getWorldArrayIndex();
351  const int INVALID_SOLVER_BODY_ID = -1;
353  {
355  // now that we have the lock, check again
357  {
358  m_kinematicBodyUniqueIdToSolverBodyTable.resize( uniqueId + 1, INVALID_SOLVER_BODY_ID );
359  }
361  }
363  // if no table entry yet,
364  if ( INVALID_SOLVER_BODY_ID == solverBodyId )
365  {
366  // need to acquire both locks
369  // now that we have the lock, check again
371  if ( INVALID_SOLVER_BODY_ID == solverBodyId )
372  {
373  // create a table entry for this body
374  solverBodyId = m_tmpSolverBodyPool.size();
375  btSolverBody& solverBody = m_tmpSolverBodyPool.expand();
376  initSolverBody( &solverBody, &body, timeStep );
378  }
381  }
382  }
383  else
384  {
385  // all fixed bodies (inf mass) get mapped to a single solver id
386  if ( m_fixedBodyId < 0 )
387  {
389  // now that we have the lock, check again
390  if ( m_fixedBodyId < 0 )
391  {
393  btSolverBody& fixedBody = m_tmpSolverBodyPool.expand();
394  initSolverBody( &fixedBody, 0, timeStep );
395  }
397  }
398  solverBodyId = m_fixedBodyId;
399  }
400  btAssert( solverBodyId >= 0 && solverBodyId < m_tmpSolverBodyPool.size() );
401  return solverBodyId;
402 }
403 
404 
406 {
407  BT_PROFILE("internalCollectContactManifoldCachedInfo");
408  for (int i = 0; i < numManifolds; ++i)
409  {
410  btContactManifoldCachedInfo* cachedInfo = &cachedInfoArray[i];
411  btPersistentManifold* manifold = manifoldPtr[i];
412  btCollisionObject* colObj0 = (btCollisionObject*) manifold->getBody0();
413  btCollisionObject* colObj1 = (btCollisionObject*) manifold->getBody1();
414 
415  int solverBodyIdA = getOrInitSolverBodyThreadsafe( *colObj0, infoGlobal.m_timeStep );
416  int solverBodyIdB = getOrInitSolverBodyThreadsafe( *colObj1, infoGlobal.m_timeStep );
417 
418  cachedInfo->solverBodyIds[ 0 ] = solverBodyIdA;
419  cachedInfo->solverBodyIds[ 1 ] = solverBodyIdB;
420  cachedInfo->numTouchingContacts = 0;
421 
422  btSolverBody* solverBodyA = &m_tmpSolverBodyPool[ solverBodyIdA ];
423  btSolverBody* solverBodyB = &m_tmpSolverBodyPool[ solverBodyIdB ];
424 
425  // A contact manifold between 2 static object should not exist!
426  // check the collision flags of your objects if this assert fires.
427  // Incorrectly set collision object flags can degrade performance in various ways.
428  btAssert( !m_tmpSolverBodyPool[ solverBodyIdA ].m_invMass.isZero() || !m_tmpSolverBodyPool[ solverBodyIdB ].m_invMass.isZero() );
429 
430  int iContact = 0;
431  for ( int j = 0; j < manifold->getNumContacts(); j++ )
432  {
433  btManifoldPoint& cp = manifold->getContactPoint( j );
434 
435  if ( cp.getDistance() <= manifold->getContactProcessingThreshold() )
436  {
437  cachedInfo->contactPoints[ iContact ] = &cp;
438  cachedInfo->contactHasRollingFriction[ iContact ] = ( cp.m_combinedRollingFriction > 0.f );
439  iContact++;
440  }
441  }
442  cachedInfo->numTouchingContacts = iContact;
443  }
444 }
445 
446 
448 {
453 
455  {
456  m_solver = solver;
457  m_cachedInfoArray = cachedInfoArray;
458  m_manifoldPtr = manifoldPtr;
459  m_infoGlobal = &infoGlobal;
460  }
461  void forLoop( int iBegin, int iEnd ) const BT_OVERRIDE
462  {
463  m_solver->internalCollectContactManifoldCachedInfo( m_cachedInfoArray + iBegin, m_manifoldPtr + iBegin, iEnd - iBegin, *m_infoGlobal );
464  }
465 };
466 
467 
469 {
470  BT_PROFILE("internalAllocContactConstraints");
471  // possibly parallel part
472  for ( int iManifold = 0; iManifold < numManifolds; ++iManifold )
473  {
474  const btContactManifoldCachedInfo& cachedInfo = cachedInfoArray[ iManifold ];
475  int contactIndex = cachedInfo.contactIndex;
476  int frictionIndex = contactIndex * m_numFrictionDirections;
477  int rollingFrictionIndex = cachedInfo.rollingFrictionIndex;
478  for ( int i = 0; i < cachedInfo.numTouchingContacts; i++ )
479  {
480  btSolverConstraint& contactConstraint = m_tmpSolverContactConstraintPool[contactIndex];
481  contactConstraint.m_solverBodyIdA = cachedInfo.solverBodyIds[ 0 ];
482  contactConstraint.m_solverBodyIdB = cachedInfo.solverBodyIds[ 1 ];
483  contactConstraint.m_originalContactPoint = cachedInfo.contactPoints[ i ];
484 
485  // allocate the friction constraints
486  contactConstraint.m_frictionIndex = frictionIndex;
487  for ( int iDir = 0; iDir < m_numFrictionDirections; ++iDir )
488  {
489  btSolverConstraint& frictionConstraint = m_tmpSolverContactFrictionConstraintPool[frictionIndex];
490  frictionConstraint.m_frictionIndex = contactIndex;
491  frictionIndex++;
492  }
493 
494  // allocate rolling friction constraints
495  if ( cachedInfo.contactHasRollingFriction[ i ] )
496  {
497  m_rollingFrictionIndexTable[ contactIndex ] = rollingFrictionIndex;
498  // allocate 3 (although we may use only 2 sometimes)
499  for ( int i = 0; i < 3; i++ )
500  {
501  m_tmpSolverContactRollingFrictionConstraintPool[ rollingFrictionIndex ].m_frictionIndex = contactIndex;
502  rollingFrictionIndex++;
503  }
504  }
505  else
506  {
507  // indicate there is no rolling friction for this contact point
508  m_rollingFrictionIndexTable[ contactIndex ] = -1;
509  }
510  contactIndex++;
511  }
512  }
513 }
514 
515 
517 {
520 
522  {
523  m_solver = solver;
524  m_cachedInfoArray = cachedInfoArray;
525  }
526  void forLoop( int iBegin, int iEnd ) const BT_OVERRIDE
527  {
528  m_solver->internalAllocContactConstraints( m_cachedInfoArray + iBegin, iEnd - iBegin );
529  }
530 };
531 
532 
534 {
535  BT_PROFILE( "allocAllContactConstraints" );
536  btAlignedObjectArray<btContactManifoldCachedInfo> cachedInfoArray; // = m_manifoldCachedInfoArray;
537  cachedInfoArray.resizeNoInitialize( numManifolds );
538  if (/* DISABLES CODE */ (false))
539  {
540  // sequential
541  internalCollectContactManifoldCachedInfo(&cachedInfoArray[ 0 ], manifoldPtr, numManifolds, infoGlobal);
542  }
543  else
544  {
545  // may alter ordering of bodies which affects determinism
546  CollectContactManifoldCachedInfoLoop loop( this, &cachedInfoArray[ 0 ], manifoldPtr, infoGlobal );
547  int grainSize = 200;
548  btParallelFor( 0, numManifolds, grainSize, loop );
549  }
550 
551  {
552  // serial part
553  int numContacts = 0;
554  int numRollingFrictionConstraints = 0;
555  for ( int iManifold = 0; iManifold < numManifolds; ++iManifold )
556  {
557  btContactManifoldCachedInfo& cachedInfo = cachedInfoArray[ iManifold ];
558  cachedInfo.contactIndex = numContacts;
559  cachedInfo.rollingFrictionIndex = numRollingFrictionConstraints;
560  numContacts += cachedInfo.numTouchingContacts;
561  for (int i = 0; i < cachedInfo.numTouchingContacts; ++i)
562  {
563  if (cachedInfo.contactHasRollingFriction[i])
564  {
565  numRollingFrictionConstraints += 3;
566  }
567  }
568  }
569  {
570  BT_PROFILE( "allocPools" );
571  if ( m_tmpSolverContactConstraintPool.capacity() < numContacts )
572  {
573  // if we need to reallocate, reserve some extra so we don't have to reallocate again next frame
574  int extraReserve = numContacts / 16;
575  m_tmpSolverContactConstraintPool.reserve( numContacts + extraReserve );
576  m_rollingFrictionIndexTable.reserve( numContacts + extraReserve );
578  m_tmpSolverContactRollingFrictionConstraintPool.reserve( numRollingFrictionConstraints + extraReserve );
579  }
584  }
585  }
586  {
587  AllocContactConstraintsLoop loop(this, &cachedInfoArray[0]);
588  int grainSize = 200;
589  btParallelFor( 0, numManifolds, grainSize, loop );
590  }
591 }
592 
593 
595 {
596  if (!m_useBatching)
597  {
598  btSequentialImpulseConstraintSolver::convertContacts(manifoldPtr, numManifolds, infoGlobal);
599  return;
600  }
601  BT_PROFILE( "convertContacts" );
602  if (numManifolds > 0)
603  {
604  if ( m_fixedBodyId < 0 )
605  {
607  btSolverBody& fixedBody = m_tmpSolverBodyPool.expand();
608  initSolverBody( &fixedBody, 0, infoGlobal.m_timeStep );
609  }
610  allocAllContactConstraints( manifoldPtr, numManifolds, infoGlobal );
611  if ( m_useBatching )
612  {
614  }
615  setupAllContactConstraints( infoGlobal );
616  }
617 }
618 
619 
621 {
622  BT_PROFILE("internalInitMultipleJoints");
623  for ( int i = iBegin; i < iEnd; i++ )
624  {
625  btTypedConstraint* constraint = constraints[i];
627  if (constraint->isEnabled())
628  {
629  constraint->buildJacobian();
630  constraint->internalSetAppliedImpulse( 0.0f );
631  btJointFeedback* fb = constraint->getJointFeedback();
632  if ( fb )
633  {
638  }
639  constraint->getInfo1( &info1 );
640  }
641  else
642  {
643  info1.m_numConstraintRows = 0;
644  info1.nub = 0;
645  }
646  }
647 }
648 
649 
651 {
654 
656  {
657  m_solver = solver;
658  m_constraints = constraints;
659  }
660  void forLoop( int iBegin, int iEnd ) const BT_OVERRIDE
661  {
662  m_solver->internalInitMultipleJoints( m_constraints, iBegin, iEnd );
663  }
664 };
665 
666 
668 {
669  BT_PROFILE("internalConvertMultipleJoints");
670  for ( int i = iBegin; i < iEnd; ++i )
671  {
672  const JointParams& jointParams = jointParamsArray[ i ];
673  int currentRow = jointParams.m_solverConstraint;
674  if ( currentRow != -1 )
675  {
678  btAssert( info1.m_numConstraintRows > 0 );
679 
680  btSolverConstraint* currentConstraintRow = &m_tmpSolverNonContactConstraintPool[ currentRow ];
681  btTypedConstraint* constraint = constraints[ i ];
682 
683  convertJoint( currentConstraintRow, constraint, info1, jointParams.m_solverBodyA, jointParams.m_solverBodyB, infoGlobal );
684  }
685  }
686 }
687 
688 
690 {
695 
698  btTypedConstraint** srcConstraints,
699  const btContactSolverInfo& infoGlobal
700  ) :
701  m_jointParamsArray(jointParamsArray),
702  m_infoGlobal(infoGlobal)
703  {
704  m_solver = solver;
705  m_srcConstraints = srcConstraints;
706  }
707  void forLoop( int iBegin, int iEnd ) const BT_OVERRIDE
708  {
709  m_solver->internalConvertMultipleJoints( m_jointParamsArray, m_srcConstraints, iBegin, iEnd, m_infoGlobal );
710  }
711 };
712 
713 
714 void btSequentialImpulseConstraintSolverMt::convertJoints(btTypedConstraint** constraints, int numConstraints, const btContactSolverInfo& infoGlobal)
715 {
716  if ( !m_useBatching )
717  {
718  btSequentialImpulseConstraintSolver::convertJoints(constraints, numConstraints, infoGlobal);
719  return;
720  }
721  BT_PROFILE("convertJoints");
722  bool parallelJointSetup = true;
724  if (parallelJointSetup)
725  {
726  InitJointsLoop loop(this, constraints);
727  int grainSize = 40;
728  btParallelFor(0, numConstraints, grainSize, loop);
729  }
730  else
731  {
732  internalInitMultipleJoints( constraints, 0, numConstraints );
733  }
734 
735  int totalNumRows = 0;
736  btAlignedObjectArray<JointParams> jointParamsArray;
737  jointParamsArray.resizeNoInitialize(numConstraints);
738 
739  //calculate the total number of contraint rows
740  for (int i=0;i<numConstraints;i++)
741  {
742  btTypedConstraint* constraint = constraints[ i ];
743 
744  JointParams& params = jointParamsArray[ i ];
746 
747  if (info1.m_numConstraintRows)
748  {
749  params.m_solverConstraint = totalNumRows;
750  params.m_solverBodyA = getOrInitSolverBody( constraint->getRigidBodyA(), infoGlobal.m_timeStep );
751  params.m_solverBodyB = getOrInitSolverBody( constraint->getRigidBodyB(), infoGlobal.m_timeStep );
752  }
753  else
754  {
755  params.m_solverConstraint = -1;
756  }
757  totalNumRows += info1.m_numConstraintRows;
758  }
760 
762  if ( parallelJointSetup )
763  {
764  ConvertJointsLoop loop(this, jointParamsArray, constraints, infoGlobal);
765  int grainSize = 20;
766  btParallelFor(0, numConstraints, grainSize, loop);
767  }
768  else
769  {
770  internalConvertMultipleJoints( jointParamsArray, constraints, 0, numConstraints, infoGlobal );
771  }
773 }
774 
775 
777 {
778  BT_PROFILE("internalConvertBodies");
779  for (int i=iBegin; i < iEnd; i++)
780  {
781  btCollisionObject* obj = bodies[i];
782  obj->setCompanionId(i);
783  btSolverBody& solverBody = m_tmpSolverBodyPool[i];
784  initSolverBody(&solverBody, obj, infoGlobal.m_timeStep);
785 
786  btRigidBody* body = btRigidBody::upcast(obj);
787  if (body && body->getInvMass())
788  {
789  btVector3 gyroForce (0,0,0);
791  {
792  gyroForce = body->computeGyroscopicForceExplicit(infoGlobal.m_maxGyroscopicForce);
793  solverBody.m_externalTorqueImpulse -= gyroForce*body->getInvInertiaTensorWorld()*infoGlobal.m_timeStep;
794  }
796  {
797  gyroForce = body->computeGyroscopicImpulseImplicit_World(infoGlobal.m_timeStep);
798  solverBody.m_externalTorqueImpulse += gyroForce;
799  }
801  {
802  gyroForce = body->computeGyroscopicImpulseImplicit_Body(infoGlobal.m_timeStep);
803  solverBody.m_externalTorqueImpulse += gyroForce;
804  }
805  }
806  }
807 }
808 
809 
811 {
816 
818  btCollisionObject** bodies,
819  int numBodies,
820  const btContactSolverInfo& infoGlobal
821  ) :
822  m_infoGlobal(infoGlobal)
823  {
824  m_solver = solver;
825  m_bodies = bodies;
826  m_numBodies = numBodies;
827  }
828  void forLoop( int iBegin, int iEnd ) const BT_OVERRIDE
829  {
830  m_solver->internalConvertBodies( m_bodies, iBegin, iEnd, m_infoGlobal );
831  }
832 };
833 
834 
836 {
837  BT_PROFILE("convertBodies");
839 
841 
842  m_fixedBodyId = numBodies;
843  {
845  initSolverBody( &fixedBody, NULL, infoGlobal.m_timeStep );
846  }
847 
848  bool parallelBodySetup = true;
849  if (parallelBodySetup)
850  {
851  ConvertBodiesLoop loop(this, bodies, numBodies, infoGlobal);
852  int grainSize = 40;
853  btParallelFor(0, numBodies, grainSize, loop);
854  }
855  else
856  {
857  internalConvertBodies( bodies, 0, numBodies, infoGlobal );
858  }
859 }
860 
861 
863  btCollisionObject** bodies,
864  int numBodies,
865  btPersistentManifold** manifoldPtr,
866  int numManifolds,
867  btTypedConstraint** constraints,
868  int numConstraints,
869  const btContactSolverInfo& infoGlobal,
870  btIDebugDraw* debugDrawer
871  )
872 {
874  m_useBatching = false;
875  if ( numManifolds >= s_minimumContactManifoldsForBatching &&
877  )
878  {
879  m_useBatching = true;
882  }
884  numBodies,
885  manifoldPtr,
886  numManifolds,
887  constraints,
888  numConstraints,
889  infoGlobal,
890  debugDrawer
891  );
892  return 0.0f;
893 }
894 
895 
897 {
898  btScalar leastSquaresResidual = 0.f;
899  for ( int iiCons = batchBegin; iiCons < batchEnd; ++iiCons )
900  {
901  int iCons = consIndices[ iiCons ];
902  const btSolverConstraint& solveManifold = m_tmpSolverContactConstraintPool[ iCons ];
903  btSolverBody& bodyA = m_tmpSolverBodyPool[ solveManifold.m_solverBodyIdA ];
904  btSolverBody& bodyB = m_tmpSolverBodyPool[ solveManifold.m_solverBodyIdB ];
905  btScalar residual = resolveSplitPenetrationImpulse( bodyA, bodyB, solveManifold );
906  leastSquaresResidual += residual*residual;
907  }
908  return leastSquaresResidual;
909 }
910 
911 
913 {
916 
918  {
919  m_solver = solver;
920  m_bc = bc;
921  }
922  btScalar sumLoop( int iBegin, int iEnd ) const BT_OVERRIDE
923  {
924  BT_PROFILE( "ContactSplitPenetrationImpulseSolverLoop" );
925  btScalar sum = 0;
926  for ( int iBatch = iBegin; iBatch < iEnd; ++iBatch )
927  {
928  const btBatchedConstraints::Range& batch = m_bc->m_batches[ iBatch ];
930  }
931  return sum;
932  }
933 };
934 
935 
936 void btSequentialImpulseConstraintSolverMt::solveGroupCacheFriendlySplitImpulseIterations(btCollisionObject** bodies,int numBodies,btPersistentManifold** manifoldPtr, int numManifolds,btTypedConstraint** constraints,int numConstraints,const btContactSolverInfo& infoGlobal,btIDebugDraw* debugDrawer)
937 {
938  BT_PROFILE("solveGroupCacheFriendlySplitImpulseIterations");
939  if (infoGlobal.m_splitImpulse)
940  {
941  for ( int iteration = 0; iteration < infoGlobal.m_numIterations; iteration++ )
942  {
943  btScalar leastSquaresResidual = 0.f;
944  if (m_useBatching)
945  {
947  ContactSplitPenetrationImpulseSolverLoop loop( this, &batchedCons );
948  btScalar leastSquaresResidual = 0.f;
949  for ( int iiPhase = 0; iiPhase < batchedCons.m_phases.size(); ++iiPhase )
950  {
951  int iPhase = batchedCons.m_phaseOrder[ iiPhase ];
952  const btBatchedConstraints::Range& phase = batchedCons.m_phases[ iPhase ];
953  int grainSize = batchedCons.m_phaseGrainSize[iPhase];
954  leastSquaresResidual += btParallelSum( phase.begin, phase.end, grainSize, loop );
955  }
956  }
957  else
958  {
959  // non-batched
961  }
962  if ( leastSquaresResidual <= infoGlobal.m_leastSquaresResidualThreshold || iteration >= ( infoGlobal.m_numIterations - 1 ) )
963  {
964 #ifdef VERBOSE_RESIDUAL_PRINTF
965  printf( "residual = %f at iteration #%d\n", leastSquaresResidual, iteration );
966 #endif
967  break;
968  }
969  }
970  }
971 }
972 
973 
974 btScalar btSequentialImpulseConstraintSolverMt::solveSingleIteration(int iteration, btCollisionObject** bodies, int numBodies, btPersistentManifold** manifoldPtr, int numManifolds, btTypedConstraint** constraints,int numConstraints,const btContactSolverInfo& infoGlobal,btIDebugDraw* debugDrawer)
975 {
976  if ( !m_useBatching )
977  {
978  return btSequentialImpulseConstraintSolver::solveSingleIteration( iteration, bodies, numBodies, manifoldPtr, numManifolds, constraints, numConstraints, infoGlobal, debugDrawer );
979  }
980  BT_PROFILE( "solveSingleIterationMt" );
981  btScalar leastSquaresResidual = 0.f;
982 
983  if (infoGlobal.m_solverMode & SOLVER_RANDMIZE_ORDER)
984  {
985  if (1) // uncomment this for a bit less random ((iteration & 7) == 0)
986  {
987  randomizeConstraintOrdering(iteration, infoGlobal.m_numIterations);
988  }
989  }
990 
991  {
993  leastSquaresResidual += resolveAllJointConstraints(iteration);
994 
995  if (iteration< infoGlobal.m_numIterations)
996  {
997  // this loop is only used for cone-twist constraints,
998  // it would be nice to skip this loop if none of the constraints need it
1000  {
1001  for ( int j = 0; j<numConstraints; j++ )
1002  {
1003  if ( constraints[ j ]->isEnabled() )
1004  {
1005  int bodyAid = getOrInitSolverBody( constraints[ j ]->getRigidBodyA(), infoGlobal.m_timeStep );
1006  int bodyBid = getOrInitSolverBody( constraints[ j ]->getRigidBodyB(), infoGlobal.m_timeStep );
1007  btSolverBody& bodyA = m_tmpSolverBodyPool[ bodyAid ];
1008  btSolverBody& bodyB = m_tmpSolverBodyPool[ bodyBid ];
1009  constraints[ j ]->solveConstraintObsolete( bodyA, bodyB, infoGlobal.m_timeStep );
1010  }
1011  }
1012  }
1013 
1015  {
1016  // solve all contact, contact-friction, and rolling friction constraints interleaved
1017  leastSquaresResidual += resolveAllContactConstraintsInterleaved();
1018  }
1019  else//SOLVER_INTERLEAVE_CONTACT_AND_FRICTION_CONSTRAINTS
1020  {
1021  // don't interleave them
1022  // solve all contact constraints
1023  leastSquaresResidual += resolveAllContactConstraints();
1024 
1025  // solve all contact friction constraints
1026  leastSquaresResidual += resolveAllContactFrictionConstraints();
1027 
1028  // solve all rolling friction constraints
1029  leastSquaresResidual += resolveAllRollingFrictionConstraints();
1030  }
1031  }
1032  }
1033  return leastSquaresResidual;
1034 }
1035 
1036 
1038 {
1039  btScalar leastSquaresResidual = 0.f;
1040  for ( int iiCons = batchBegin; iiCons < batchEnd; ++iiCons )
1041  {
1042  int iCons = consIndices[ iiCons ];
1043  const btSolverConstraint& constraint = m_tmpSolverNonContactConstraintPool[ iCons ];
1044  if ( iteration < constraint.m_overrideNumSolverIterations )
1045  {
1046  btSolverBody& bodyA = m_tmpSolverBodyPool[ constraint.m_solverBodyIdA ];
1047  btSolverBody& bodyB = m_tmpSolverBodyPool[ constraint.m_solverBodyIdB ];
1048  btScalar residual = resolveSingleConstraintRowGeneric( bodyA, bodyB, constraint );
1049  leastSquaresResidual += residual*residual;
1050  }
1051  }
1052  return leastSquaresResidual;
1053 }
1054 
1055 
1057 {
1058  btScalar leastSquaresResidual = 0.f;
1059  for ( int iiCons = batchBegin; iiCons < batchEnd; ++iiCons )
1060  {
1061  int iCons = consIndices[ iiCons ];
1062  const btSolverConstraint& solveManifold = m_tmpSolverContactConstraintPool[ iCons ];
1063  btSolverBody& bodyA = m_tmpSolverBodyPool[ solveManifold.m_solverBodyIdA ];
1064  btSolverBody& bodyB = m_tmpSolverBodyPool[ solveManifold.m_solverBodyIdB ];
1065  btScalar residual = resolveSingleConstraintRowLowerLimit( bodyA, bodyB, solveManifold );
1066  leastSquaresResidual += residual*residual;
1067  }
1068  return leastSquaresResidual;
1069 }
1070 
1071 
1073 {
1074  btScalar leastSquaresResidual = 0.f;
1075  for ( int iiCons = batchBegin; iiCons < batchEnd; ++iiCons )
1076  {
1077  int iContact = consIndices[ iiCons ];
1078  btScalar totalImpulse = m_tmpSolverContactConstraintPool[ iContact ].m_appliedImpulse;
1079 
1080  // apply sliding friction
1081  if ( totalImpulse > 0.0f )
1082  {
1083  int iBegin = iContact * m_numFrictionDirections;
1084  int iEnd = iBegin + m_numFrictionDirections;
1085  for ( int iFriction = iBegin; iFriction < iEnd; ++iFriction )
1086  {
1087  btSolverConstraint& solveManifold = m_tmpSolverContactFrictionConstraintPool[ iFriction++ ];
1088  btAssert( solveManifold.m_frictionIndex == iContact );
1089 
1090  solveManifold.m_lowerLimit = -( solveManifold.m_friction*totalImpulse );
1091  solveManifold.m_upperLimit = solveManifold.m_friction*totalImpulse;
1092 
1093  btSolverBody& bodyA = m_tmpSolverBodyPool[ solveManifold.m_solverBodyIdA ];
1094  btSolverBody& bodyB = m_tmpSolverBodyPool[ solveManifold.m_solverBodyIdB ];
1095  btScalar residual = resolveSingleConstraintRowGeneric( bodyA, bodyB, solveManifold );
1096  leastSquaresResidual += residual*residual;
1097  }
1098  }
1099  }
1100  return leastSquaresResidual;
1101 }
1102 
1103 
1105 {
1106  btScalar leastSquaresResidual = 0.f;
1107  for ( int iiCons = batchBegin; iiCons < batchEnd; ++iiCons )
1108  {
1109  int iContact = consIndices[ iiCons ];
1110  int iFirstRollingFriction = m_rollingFrictionIndexTable[ iContact ];
1111  if ( iFirstRollingFriction >= 0 )
1112  {
1113  btScalar totalImpulse = m_tmpSolverContactConstraintPool[ iContact ].m_appliedImpulse;
1114  // apply rolling friction
1115  if ( totalImpulse > 0.0f )
1116  {
1117  int iBegin = iFirstRollingFriction;
1118  int iEnd = iBegin + 3;
1119  for ( int iRollingFric = iBegin; iRollingFric < iEnd; ++iRollingFric )
1120  {
1121  btSolverConstraint& rollingFrictionConstraint = m_tmpSolverContactRollingFrictionConstraintPool[ iRollingFric ];
1122  if ( rollingFrictionConstraint.m_frictionIndex != iContact )
1123  {
1124  break;
1125  }
1126  btScalar rollingFrictionMagnitude = rollingFrictionConstraint.m_friction*totalImpulse;
1127  if ( rollingFrictionMagnitude > rollingFrictionConstraint.m_friction )
1128  {
1129  rollingFrictionMagnitude = rollingFrictionConstraint.m_friction;
1130  }
1131 
1132  rollingFrictionConstraint.m_lowerLimit = -rollingFrictionMagnitude;
1133  rollingFrictionConstraint.m_upperLimit = rollingFrictionMagnitude;
1134 
1135  btScalar residual = resolveSingleConstraintRowGeneric( m_tmpSolverBodyPool[ rollingFrictionConstraint.m_solverBodyIdA ], m_tmpSolverBodyPool[ rollingFrictionConstraint.m_solverBodyIdB ], rollingFrictionConstraint );
1136  leastSquaresResidual += residual*residual;
1137  }
1138  }
1139  }
1140  }
1141  return leastSquaresResidual;
1142 }
1143 
1144 
1146  int batchBegin,
1147  int batchEnd
1148  )
1149 {
1150  btScalar leastSquaresResidual = 0.f;
1151  int numPoolConstraints = m_tmpSolverContactConstraintPool.size();
1152 
1153  for ( int iiCons = batchBegin; iiCons < batchEnd; iiCons++ )
1154  {
1155  btScalar totalImpulse = 0;
1156  int iContact = contactIndices[ iiCons ];
1157  // apply penetration constraint
1158  {
1159  const btSolverConstraint& solveManifold = m_tmpSolverContactConstraintPool[ iContact ];
1160  btScalar residual = resolveSingleConstraintRowLowerLimit( m_tmpSolverBodyPool[ solveManifold.m_solverBodyIdA ], m_tmpSolverBodyPool[ solveManifold.m_solverBodyIdB ], solveManifold );
1161  leastSquaresResidual += residual*residual;
1162  totalImpulse = solveManifold.m_appliedImpulse;
1163  }
1164 
1165  // apply sliding friction
1166  if ( totalImpulse > 0.0f )
1167  {
1168  int iBegin = iContact * m_numFrictionDirections;
1169  int iEnd = iBegin + m_numFrictionDirections;
1170  for ( int iFriction = iBegin; iFriction < iEnd; ++iFriction )
1171  {
1172  btSolverConstraint& solveManifold = m_tmpSolverContactFrictionConstraintPool[ iFriction ];
1173  btAssert( solveManifold.m_frictionIndex == iContact );
1174 
1175  solveManifold.m_lowerLimit = -( solveManifold.m_friction*totalImpulse );
1176  solveManifold.m_upperLimit = solveManifold.m_friction*totalImpulse;
1177 
1178  btSolverBody& bodyA = m_tmpSolverBodyPool[ solveManifold.m_solverBodyIdA ];
1179  btSolverBody& bodyB = m_tmpSolverBodyPool[ solveManifold.m_solverBodyIdB ];
1180  btScalar residual = resolveSingleConstraintRowGeneric( bodyA, bodyB, solveManifold );
1181  leastSquaresResidual += residual*residual;
1182  }
1183  }
1184 
1185  // apply rolling friction
1186  int iFirstRollingFriction = m_rollingFrictionIndexTable[ iContact ];
1187  if ( totalImpulse > 0.0f && iFirstRollingFriction >= 0)
1188  {
1189  int iBegin = iFirstRollingFriction;
1190  int iEnd = iBegin + 3;
1191  for ( int iRollingFric = iBegin; iRollingFric < iEnd; ++iRollingFric )
1192  {
1193  btSolverConstraint& rollingFrictionConstraint = m_tmpSolverContactRollingFrictionConstraintPool[ iRollingFric ];
1194  if ( rollingFrictionConstraint.m_frictionIndex != iContact )
1195  {
1196  break;
1197  }
1198  btScalar rollingFrictionMagnitude = rollingFrictionConstraint.m_friction*totalImpulse;
1199  if ( rollingFrictionMagnitude > rollingFrictionConstraint.m_friction )
1200  {
1201  rollingFrictionMagnitude = rollingFrictionConstraint.m_friction;
1202  }
1203 
1204  rollingFrictionConstraint.m_lowerLimit = -rollingFrictionMagnitude;
1205  rollingFrictionConstraint.m_upperLimit = rollingFrictionMagnitude;
1206 
1207  btScalar residual = resolveSingleConstraintRowGeneric( m_tmpSolverBodyPool[ rollingFrictionConstraint.m_solverBodyIdA ], m_tmpSolverBodyPool[ rollingFrictionConstraint.m_solverBodyIdB ], rollingFrictionConstraint );
1208  leastSquaresResidual += residual*residual;
1209  }
1210  }
1211  }
1212  return leastSquaresResidual;
1213 }
1214 
1215 
1217 {
1218  btBatchedConstraints& bc = *batchedConstraints;
1219  // randomize ordering of phases
1220  for ( int ii = 1; ii < bc.m_phaseOrder.size(); ++ii )
1221  {
1222  int iSwap = btRandInt2( ii + 1 );
1223  bc.m_phaseOrder.swap( ii, iSwap );
1224  }
1225 
1226  // for each batch,
1227  for ( int iBatch = 0; iBatch < bc.m_batches.size(); ++iBatch )
1228  {
1229  // randomize ordering of constraints within the batch
1230  const btBatchedConstraints::Range& batch = bc.m_batches[ iBatch ];
1231  for ( int iiCons = batch.begin; iiCons < batch.end; ++iiCons )
1232  {
1233  int iSwap = batch.begin + btRandInt2( iiCons - batch.begin + 1 );
1234  btAssert(iSwap >= batch.begin && iSwap < batch.end);
1235  bc.m_constraintIndices.swap( iiCons, iSwap );
1236  }
1237  }
1238 }
1239 
1240 
1242 {
1243  // randomize ordering of joint constraints
1245 
1246  //contact/friction constraints are not solved more than numIterations
1247  if ( iteration < numIterations )
1248  {
1250  }
1251 }
1252 
1253 
1255 {
1259 
1261  {
1262  m_solver = solver;
1263  m_bc = bc;
1264  m_iteration = iteration;
1265  }
1266  btScalar sumLoop( int iBegin, int iEnd ) const BT_OVERRIDE
1267  {
1268  BT_PROFILE( "JointSolverLoop" );
1269  btScalar sum = 0;
1270  for ( int iBatch = iBegin; iBatch < iEnd; ++iBatch )
1271  {
1272  const btBatchedConstraints::Range& batch = m_bc->m_batches[ iBatch ];
1273  sum += m_solver->resolveMultipleJointConstraints( m_bc->m_constraintIndices, batch.begin, batch.end, m_iteration );
1274  }
1275  return sum;
1276  }
1277 };
1278 
1279 
1281 {
1282  BT_PROFILE( "resolveAllJointConstraints" );
1283  const btBatchedConstraints& batchedCons = m_batchedJointConstraints;
1284  JointSolverLoop loop( this, &batchedCons, iteration );
1285  btScalar leastSquaresResidual = 0.f;
1286  for ( int iiPhase = 0; iiPhase < batchedCons.m_phases.size(); ++iiPhase )
1287  {
1288  int iPhase = batchedCons.m_phaseOrder[ iiPhase ];
1289  const btBatchedConstraints::Range& phase = batchedCons.m_phases[ iPhase ];
1290  int grainSize = 1;
1291  leastSquaresResidual += btParallelSum( phase.begin, phase.end, grainSize, loop );
1292  }
1293  return leastSquaresResidual;
1294 }
1295 
1296 
1298 {
1301 
1303  {
1304  m_solver = solver;
1305  m_bc = bc;
1306  }
1307  btScalar sumLoop( int iBegin, int iEnd ) const BT_OVERRIDE
1308  {
1309  BT_PROFILE( "ContactSolverLoop" );
1310  btScalar sum = 0;
1311  for ( int iBatch = iBegin; iBatch < iEnd; ++iBatch )
1312  {
1313  const btBatchedConstraints::Range& batch = m_bc->m_batches[ iBatch ];
1314  sum += m_solver->resolveMultipleContactConstraints( m_bc->m_constraintIndices, batch.begin, batch.end );
1315  }
1316  return sum;
1317  }
1318 };
1319 
1320 
1322 {
1323  BT_PROFILE( "resolveAllContactConstraints" );
1325  ContactSolverLoop loop( this, &batchedCons );
1326  btScalar leastSquaresResidual = 0.f;
1327  for ( int iiPhase = 0; iiPhase < batchedCons.m_phases.size(); ++iiPhase )
1328  {
1329  int iPhase = batchedCons.m_phaseOrder[ iiPhase ];
1330  const btBatchedConstraints::Range& phase = batchedCons.m_phases[ iPhase ];
1331  int grainSize = batchedCons.m_phaseGrainSize[iPhase];
1332  leastSquaresResidual += btParallelSum( phase.begin, phase.end, grainSize, loop );
1333  }
1334  return leastSquaresResidual;
1335 }
1336 
1337 
1339 {
1342 
1344  {
1345  m_solver = solver;
1346  m_bc = bc;
1347  }
1348  btScalar sumLoop( int iBegin, int iEnd ) const BT_OVERRIDE
1349  {
1350  BT_PROFILE( "ContactFrictionSolverLoop" );
1351  btScalar sum = 0;
1352  for ( int iBatch = iBegin; iBatch < iEnd; ++iBatch )
1353  {
1354  const btBatchedConstraints::Range& batch = m_bc->m_batches[ iBatch ];
1355  sum += m_solver->resolveMultipleContactFrictionConstraints( m_bc->m_constraintIndices, batch.begin, batch.end );
1356  }
1357  return sum;
1358  }
1359 };
1360 
1361 
1363 {
1364  BT_PROFILE( "resolveAllContactFrictionConstraints" );
1366  ContactFrictionSolverLoop loop( this, &batchedCons );
1367  btScalar leastSquaresResidual = 0.f;
1368  for ( int iiPhase = 0; iiPhase < batchedCons.m_phases.size(); ++iiPhase )
1369  {
1370  int iPhase = batchedCons.m_phaseOrder[ iiPhase ];
1371  const btBatchedConstraints::Range& phase = batchedCons.m_phases[ iPhase ];
1372  int grainSize = batchedCons.m_phaseGrainSize[iPhase];
1373  leastSquaresResidual += btParallelSum( phase.begin, phase.end, grainSize, loop );
1374  }
1375  return leastSquaresResidual;
1376 }
1377 
1378 
1380 {
1383 
1385  {
1386  m_solver = solver;
1387  m_bc = bc;
1388  }
1389  btScalar sumLoop( int iBegin, int iEnd ) const BT_OVERRIDE
1390  {
1391  BT_PROFILE( "InterleavedContactSolverLoop" );
1392  btScalar sum = 0;
1393  for ( int iBatch = iBegin; iBatch < iEnd; ++iBatch )
1394  {
1395  const btBatchedConstraints::Range& batch = m_bc->m_batches[ iBatch ];
1396  sum += m_solver->resolveMultipleContactConstraintsInterleaved( m_bc->m_constraintIndices, batch.begin, batch.end );
1397  }
1398  return sum;
1399  }
1400 };
1401 
1402 
1404 {
1405  BT_PROFILE( "resolveAllContactConstraintsInterleaved" );
1407  InterleavedContactSolverLoop loop( this, &batchedCons );
1408  btScalar leastSquaresResidual = 0.f;
1409  for ( int iiPhase = 0; iiPhase < batchedCons.m_phases.size(); ++iiPhase )
1410  {
1411  int iPhase = batchedCons.m_phaseOrder[ iiPhase ];
1412  const btBatchedConstraints::Range& phase = batchedCons.m_phases[ iPhase ];
1413  int grainSize = 1;
1414  leastSquaresResidual += btParallelSum( phase.begin, phase.end, grainSize, loop );
1415  }
1416  return leastSquaresResidual;
1417 }
1418 
1419 
1421 {
1424 
1426  {
1427  m_solver = solver;
1428  m_bc = bc;
1429  }
1430  btScalar sumLoop( int iBegin, int iEnd ) const BT_OVERRIDE
1431  {
1432  BT_PROFILE( "ContactFrictionSolverLoop" );
1433  btScalar sum = 0;
1434  for ( int iBatch = iBegin; iBatch < iEnd; ++iBatch )
1435  {
1436  const btBatchedConstraints::Range& batch = m_bc->m_batches[ iBatch ];
1437  sum += m_solver->resolveMultipleContactRollingFrictionConstraints( m_bc->m_constraintIndices, batch.begin, batch.end );
1438  }
1439  return sum;
1440  }
1441 };
1442 
1443 
1445 {
1446  BT_PROFILE( "resolveAllRollingFrictionConstraints" );
1447  btScalar leastSquaresResidual = 0.f;
1448  //
1449  // We do not generate batches for rolling friction constraints. We assume that
1450  // one of two cases is true:
1451  //
1452  // 1. either most bodies in the simulation have rolling friction, in which case we can use the
1453  // batches for contacts and use a lookup table to translate contact indices to rolling friction
1454  // (ignoring any contact indices that don't map to a rolling friction constraint). As long as
1455  // most contacts have a corresponding rolling friction constraint, this should parallelize well.
1456  //
1457  // -OR-
1458  //
1459  // 2. few bodies in the simulation have rolling friction, so it is not worth trying to use the
1460  // batches from contacts as most of the contacts won't have corresponding rolling friction
1461  // constraints and most threads would end up doing very little work. Most of the time would
1462  // go to threading overhead, so we don't bother with threading.
1463  //
1464  int numRollingFrictionPoolConstraints = m_tmpSolverContactRollingFrictionConstraintPool.size();
1465  if (numRollingFrictionPoolConstraints >= m_tmpSolverContactConstraintPool.size())
1466  {
1467  // use batching if there are many rolling friction constraints
1469  ContactRollingFrictionSolverLoop loop( this, &batchedCons );
1470  btScalar leastSquaresResidual = 0.f;
1471  for ( int iiPhase = 0; iiPhase < batchedCons.m_phases.size(); ++iiPhase )
1472  {
1473  int iPhase = batchedCons.m_phaseOrder[ iiPhase ];
1474  const btBatchedConstraints::Range& phase = batchedCons.m_phases[ iPhase ];
1475  int grainSize = 1;
1476  leastSquaresResidual += btParallelSum( phase.begin, phase.end, grainSize, loop );
1477  }
1478  }
1479  else
1480  {
1481  // no batching, also ignores SOLVER_RANDMIZE_ORDER
1482  for ( int j = 0; j < numRollingFrictionPoolConstraints; j++ )
1483  {
1484  btSolverConstraint& rollingFrictionConstraint = m_tmpSolverContactRollingFrictionConstraintPool[ j ];
1485  if ( rollingFrictionConstraint.m_frictionIndex >= 0 )
1486  {
1487  btScalar totalImpulse = m_tmpSolverContactConstraintPool[ rollingFrictionConstraint.m_frictionIndex ].m_appliedImpulse;
1488  if ( totalImpulse > 0.0f )
1489  {
1490  btScalar rollingFrictionMagnitude = rollingFrictionConstraint.m_friction*totalImpulse;
1491  if ( rollingFrictionMagnitude > rollingFrictionConstraint.m_friction )
1492  rollingFrictionMagnitude = rollingFrictionConstraint.m_friction;
1493 
1494  rollingFrictionConstraint.m_lowerLimit = -rollingFrictionMagnitude;
1495  rollingFrictionConstraint.m_upperLimit = rollingFrictionMagnitude;
1496 
1497  btScalar residual = resolveSingleConstraintRowGeneric( m_tmpSolverBodyPool[ rollingFrictionConstraint.m_solverBodyIdA ], m_tmpSolverBodyPool[ rollingFrictionConstraint.m_solverBodyIdB ], rollingFrictionConstraint );
1498  leastSquaresResidual += residual*residual;
1499  }
1500  }
1501  }
1502  }
1503  return leastSquaresResidual;
1504 }
1505 
1506 
1508 {
1509  BT_PROFILE("internalWriteBackContacts");
1510  writeBackContacts(iBegin, iEnd, infoGlobal);
1511  //for ( int iContact = iBegin; iContact < iEnd; ++iContact)
1512  //{
1513  // const btSolverConstraint& contactConstraint = m_tmpSolverContactConstraintPool[ iContact ];
1514  // btManifoldPoint* pt = (btManifoldPoint*) contactConstraint.m_originalContactPoint;
1515  // btAssert( pt );
1516  // pt->m_appliedImpulse = contactConstraint.m_appliedImpulse;
1517  // pt->m_appliedImpulseLateral1 = m_tmpSolverContactFrictionConstraintPool[ contactConstraint.m_frictionIndex ].m_appliedImpulse;
1518  // if ( m_numFrictionDirections == 2 )
1519  // {
1520  // pt->m_appliedImpulseLateral2 = m_tmpSolverContactFrictionConstraintPool[ contactConstraint.m_frictionIndex + 1 ].m_appliedImpulse;
1521  // }
1522  //}
1523 }
1524 
1525 
1527 {
1528  BT_PROFILE("internalWriteBackJoints");
1529  writeBackJoints(iBegin, iEnd, infoGlobal);
1530 }
1531 
1532 
1534 {
1535  BT_PROFILE("internalWriteBackBodies");
1536  writeBackBodies( iBegin, iEnd, infoGlobal );
1537 }
1538 
1539 
1541 {
1544 
1546  {
1547  m_solver = solver;
1548  m_infoGlobal = &infoGlobal;
1549  }
1550  void forLoop( int iBegin, int iEnd ) const BT_OVERRIDE
1551  {
1552  m_solver->internalWriteBackContacts( iBegin, iEnd, *m_infoGlobal );
1553  }
1554 };
1555 
1556 
1558 {
1561 
1563  {
1564  m_solver = solver;
1565  m_infoGlobal = &infoGlobal;
1566  }
1567  void forLoop( int iBegin, int iEnd ) const BT_OVERRIDE
1568  {
1569  m_solver->internalWriteBackJoints( iBegin, iEnd, *m_infoGlobal );
1570  }
1571 };
1572 
1573 
1575 {
1578 
1580  {
1581  m_solver = solver;
1582  m_infoGlobal = &infoGlobal;
1583  }
1584  void forLoop( int iBegin, int iEnd ) const BT_OVERRIDE
1585  {
1586  m_solver->internalWriteBackBodies( iBegin, iEnd, *m_infoGlobal );
1587  }
1588 };
1589 
1590 
1592 {
1593  BT_PROFILE("solveGroupCacheFriendlyFinish");
1594 
1595  if (infoGlobal.m_solverMode & SOLVER_USE_WARMSTARTING)
1596  {
1597  WriteContactPointsLoop loop( this, infoGlobal );
1598  int grainSize = 500;
1599  btParallelFor( 0, m_tmpSolverContactConstraintPool.size(), grainSize, loop );
1600  }
1601 
1602  {
1603  WriteJointsLoop loop( this, infoGlobal );
1604  int grainSize = 400;
1605  btParallelFor( 0, m_tmpSolverNonContactConstraintPool.size(), grainSize, loop );
1606  }
1607  {
1608  WriteBodiesLoop loop( this, infoGlobal );
1609  int grainSize = 100;
1610  btParallelFor( 0, m_tmpSolverBodyPool.size(), grainSize, loop );
1611  }
1612 
1617 
1619  return 0.f;
1620 }
1621 
btScalar getInvMass() const
Definition: btRigidBody.h:273
static T sum(const btAlignedObjectArray< T > &items)
static const btRigidBody * upcast(const btCollisionObject *colObj)
to keep collision detection and dynamics separate we don&#39;t store a rigidbody pointer but a rigidbody ...
Definition: btRigidBody.h:203
void internalAllocContactConstraints(const btContactManifoldCachedInfo *cachedInfoArray, int numManifolds)
#define SIMD_EPSILON
Definition: btScalar.h:521
btScalar resolveMultipleContactSplitPenetrationImpulseConstraints(const btAlignedObjectArray< int > &consIndices, int batchBegin, int batchEnd)
btPersistentManifold is a contact point cache, it stays persistent as long as objects are overlapping...
WriteJointsLoop(btSequentialImpulseConstraintSolverMt *solver, const btContactSolverInfo &infoGlobal)
virtual void convertContacts(btPersistentManifold **manifoldPtr, int numManifolds, const btContactSolverInfo &infoGlobal) BT_OVERRIDE
btScalar sumLoop(int iBegin, int iEnd) const BT_OVERRIDE
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.)
virtual void getInfo1(btConstraintInfo1 *info)=0
internal method used by the constraint solver, don&#39;t use them directly
btSequentialImpulseConstraintSolverMt * m_solver
btVector3 m_lateralFrictionDir1
btSequentialImpulseConstraintSolverMt * m_solver
virtual btScalar solveGroupCacheFriendlySetup(btCollisionObject **bodies, int numBodies, btPersistentManifold **manifoldPtr, int numManifolds, btTypedConstraint **constraints, int numConstraints, const btContactSolverInfo &infoGlobal, btIDebugDraw *debugDrawer) BT_OVERRIDE
btScalar sumLoop(int iBegin, int iEnd) const BT_OVERRIDE
btScalar resolveMultipleContactRollingFrictionConstraints(const btAlignedObjectArray< int > &consIndices, int batchBegin, int batchEnd)
The btAlignedObjectArray template class uses a subset of the stl::vector interface for its methods It...
ContactSolverLoop(btSequentialImpulseConstraintSolverMt *solver, const btBatchedConstraints *bc)
virtual void convertBodies(btCollisionObject **bodies, int numBodies, const btContactSolverInfo &infoGlobal) BT_OVERRIDE
btScalar sumLoop(int iBegin, int iEnd) const BT_OVERRIDE
btVector3 computeGyroscopicImpulseImplicit_World(btScalar dt) const
perform implicit force computation in world space
void internalSetupContactConstraints(int iContactConstraint, const btContactSolverInfo &infoGlobal)
ContactSplitPenetrationImpulseSolverLoop(btSequentialImpulseConstraintSolverMt *solver, const btBatchedConstraints *bc)
1D constraint along a normal axis between bodyA and bodyB. It can be combined to solve contact and fr...
void btPlaneSpace1(const T &n, T &p, T &q)
Definition: btVector3.h:1284
void resizeNoInitialize(int newsize)
resize changes the number of elements in the array.
btScalar btSqrt(btScalar y)
Definition: btScalar.h:444
#define btAssert(x)
Definition: btScalar.h:131
btScalar sumLoop(int iBegin, int iEnd) const BT_OVERRIDE
virtual void randomizeConstraintOrdering(int iteration, int numIterations)
btSequentialImpulseConstraintSolverMt * m_solver
virtual btScalar solveSingleIteration(int iteration, btCollisionObject **bodies, int numBodies, btPersistentManifold **manifoldPtr, int numManifolds, btTypedConstraint **constraints, int numConstraints, const btContactSolverInfo &infoGlobal, btIDebugDraw *debugDrawer)
btScalar m_frictionCFM
btSequentialImpulseConstraintSolverMt::btContactManifoldCachedInfo * m_cachedInfoArray
ManifoldContactPoint collects and maintains persistent contactpoints.
btAlignedObjectArray< int > m_phaseOrder
const btCollisionObject * getBody0() const
btScalar m_contactMotion1
void getVelocityInLocalPointNoDelta(const btVector3 &rel_pos, btVector3 &velocity) const
Definition: btSolverBody.h:137
const btContactSolverInfo * m_infoGlobal
ContactFrictionSolverLoop(btSequentialImpulseConstraintSolverMt *solver, const btBatchedConstraints *bc)
static btBatchedConstraints::BatchingMethod s_jointBatchingMethod
static btBatchedConstraints::BatchingMethod s_contactBatchingMethod
void initSolverBody(btSolverBody *solverBody, btCollisionObject *collisionObject, btScalar timeStep)
btScalar sumLoop(int iBegin, int iEnd) const BT_OVERRIDE
btSequentialImpulseConstraintSolverMt * m_solver
btScalar resolveSingleConstraintRowLowerLimit(btSolverBody &bodyA, btSolverBody &bodyB, const btSolverConstraint &contactConstraint)
void swap(int index0, int index1)
btScalar dot(const btVector3 &v) const
Return the dot product.
Definition: btVector3.h:235
WriteBodiesLoop(btSequentialImpulseConstraintSolverMt *solver, const btContactSolverInfo &infoGlobal)
btVector3 m_externalTorqueImpulse
Definition: btSolverBody.h:122
btVector3 & normalize()
Normalize this vector x^2 + y^2 + z^2 = 1.
Definition: btVector3.h:309
void forLoop(int iBegin, int iEnd) const BT_OVERRIDE
btVector3 m_appliedForceBodyB
btSequentialImpulseConstraintSolverMt * m_solver
void internalConvertMultipleJoints(const btAlignedObjectArray< JointParams > &jointParamsArray, btTypedConstraint **constraints, int iBegin, int iEnd, const btContactSolverInfo &infoGlobal)
const btJointFeedback * getJointFeedback() const
int getOrInitSolverBody(btCollisionObject &body, btScalar timeStep)
void forLoop(int iBegin, int iEnd) const BT_OVERRIDE
BT_ENABLE_GYROPSCOPIC_FORCE flags is enabled by default in Bullet 2.83 and onwards.
Definition: btRigidBody.h:47
const btAlignedObjectArray< btSequentialImpulseConstraintSolverMt::JointParams > & m_jointParamsArray
btScalar m_combinedRollingFriction
btAlignedObjectArray< btSolverBody > m_tmpSolverBodyPool
SetupContactConstraintsLoop(btSequentialImpulseConstraintSolverMt *solver, const btBatchedConstraints *bc, const btContactSolverInfo &infoGlobal)
void forLoop(int iBegin, int iEnd) const BT_OVERRIDE
const btContactSolverInfo & m_infoGlobal
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.)
int getWorldArrayIndex() const
btVector3 computeGyroscopicForceExplicit(btScalar maxGyroscopicForce) const
explicit version is best avoided, it gains energy
btVector3 m_normalWorldOnB
int size() const
return the number of elements in the array
btVector3 & getOrigin()
Return the origin vector translation.
Definition: btTransform.h:117
void forLoop(int iBegin, int iEnd) const BT_OVERRIDE
btVector3 m_appliedForceBodyA
ContactRollingFrictionSolverLoop(btSequentialImpulseConstraintSolverMt *solver, const btBatchedConstraints *bc)
bool btThreadsAreRunning()
Definition: btThreads.cpp:395
void internalCollectContactManifoldCachedInfo(btContactManifoldCachedInfo *cachedInfoArray, btPersistentManifold **manifoldPtr, int numManifolds, const btContactSolverInfo &infoGlobal)
const btSequentialImpulseConstraintSolverMt::btContactManifoldCachedInfo * m_cachedInfoArray
#define BT_OVERRIDE
Definition: btThreads.h:28
void forLoop(int iBegin, int iEnd) const BT_OVERRIDE
void setFrictionConstraintImpulse(btSolverConstraint &solverConstraint, int solverBodyIdA, int solverBodyIdB, btManifoldPoint &cp, const btContactSolverInfo &infoGlobal)
InterleavedContactSolverLoop(btSequentialImpulseConstraintSolverMt *solver, const btBatchedConstraints *bc)
bool isKinematicObject() const
void lock()
Definition: btThreads.cpp:206
virtual void convertContacts(btPersistentManifold **manifoldPtr, int numManifolds, const btContactSolverInfo &infoGlobal)
void btSwap(T &a, T &b)
Definition: btScalar.h:621
const btContactSolverInfo * m_infoGlobal
void randomizeBatchedConstraintOrdering(btBatchedConstraints *batchedConstraints)
void forLoop(int iBegin, int iEnd) const BT_OVERRIDE
void forLoop(int iBegin, int iEnd) const BT_OVERRIDE
void internalConvertBodies(btCollisionObject **bodies, int iBegin, int iEnd, const btContactSolverInfo &infoGlobal)
btVector3 cross(const btVector3 &v) const
Return the cross product between this and another vector.
Definition: btVector3.h:389
void unlock()
Definition: btThreads.cpp:211
bool isStaticOrKinematicObject() const
btCollisionObject can be used to manage collision detection objects.
btScalar getContactProcessingThreshold() const
btScalar sumLoop(int iBegin, int iEnd) const BT_OVERRIDE
The btIDebugDraw interface class allows hooking up a debug renderer to visually debug simulations...
Definition: btIDebugDraw.h:29
void setZero()
Definition: btVector3.h:683
void internalInitMultipleJoints(btTypedConstraint **constraints, int iBegin, int iEnd)
CollectContactManifoldCachedInfoLoop(btSequentialImpulseConstraintSolverMt *solver, btSequentialImpulseConstraintSolverMt::btContactManifoldCachedInfo *cachedInfoArray, btPersistentManifold **manifoldPtr, const btContactSolverInfo &infoGlobal)
btAlignedObjectArray< Range > m_phases
The btRigidBody is the main class for rigid body objects.
Definition: btRigidBody.h:62
btScalar length() const
Return the length of the vector.
Definition: btVector3.h:263
btAlignedObjectArray< int > m_constraintIndices
void writeBackContacts(int iBegin, int iEnd, const btContactSolverInfo &infoGlobal)
const btManifoldPoint & getContactPoint(int index) const
ConvertJointsLoop(btSequentialImpulseConstraintSolverMt *solver, const btAlignedObjectArray< btSequentialImpulseConstraintSolverMt::JointParams > &jointParamsArray, btTypedConstraint **srcConstraints, const btContactSolverInfo &infoGlobal)
void setCompanionId(int id)
btScalar resolveMultipleContactConstraintsInterleaved(const btAlignedObjectArray< int > &contactIndices, int batchBegin, int batchEnd)
btSequentialImpulseConstraintSolverMt * m_solver
btScalar resolveMultipleContactFrictionConstraints(const btAlignedObjectArray< int > &consIndices, int batchBegin, int batchEnd)
btSequentialImpulseConstraintSolverMt * m_solver
bool isEnabled() const
int capacity() const
return the pre-allocated (reserved) elements, this is at least as large as the total number of elemen...
const btVector3 & getPositionWorldOnB() const
void forLoop(int iBegin, int iEnd) const BT_OVERRIDE
btVector3 can be used to represent 3D points and vectors.
Definition: btVector3.h:83
int getCompanionId() const
btScalar length2() const
Return the length of the vector squared.
Definition: btVector3.h:257
btScalar resolveSplitPenetrationImpulse(btSolverBody &bodyA, btSolverBody &bodyB, const btSolverConstraint &contactConstraint)
virtual void solveConstraintObsolete(btSolverBody &, btSolverBody &, btScalar)
internal method used by the constraint solver, don&#39;t use them directly
#define BT_PROFILE(name)
Definition: btQuickprof.h:216
btSequentialImpulseConstraintSolverMt * m_solver
btAlignedObjectArray< char > m_phaseGrainSize
btScalar resolveMultipleContactConstraints(const btAlignedObjectArray< int > &consIndices, int batchBegin, int batchEnd)
btVector3 m_appliedTorqueBodyB
void setup(btConstraintArray *constraints, const btAlignedObjectArray< btSolverBody > &bodies, BatchingMethod batchingMethod, int minBatchSize, int maxBatchSize, btAlignedObjectArray< char > *scratchMemory)
const btBatchedConstraints * m_bc
The btSolverBody is an internal datastructure for the constraint solver. Only necessary data is packe...
Definition: btSolverBody.h:108
btAlignedObjectArray< btTypedConstraint::btConstraintInfo1 > m_tmpConstraintSizesPool
JointSolverLoop(btSequentialImpulseConstraintSolverMt *solver, const btBatchedConstraints *bc, int iteration)
TypedConstraint is the baseclass for Bullet constraints and vehicles.
void resize(int newsize, const T &fillData=T())
btRigidBody * m_originalBody
Definition: btSolverBody.h:124
virtual btScalar solveSingleIteration(int iteration, btCollisionObject **bodies, int numBodies, btPersistentManifold **manifoldPtr, int numManifolds, btTypedConstraint **constraints, int numConstraints, const btContactSolverInfo &infoGlobal, btIDebugDraw *debugDrawer) BT_OVERRIDE
const btRigidBody & getRigidBodyA() const
void setupAllContactConstraints(const btContactSolverInfo &infoGlobal)
virtual btScalar solveGroupCacheFriendlySetup(btCollisionObject **bodies, int numBodies, btPersistentManifold **manifoldPtr, int numManifolds, btTypedConstraint **constraints, int numConstraints, const btContactSolverInfo &infoGlobal, btIDebugDraw *debugDrawer)
int getOrInitSolverBodyThreadsafe(btCollisionObject &body, btScalar timeStep)
btScalar btParallelSum(int iBegin, int iEnd, int grainSize, const btIParallelSumBody &body)
Definition: btThreads.cpp:456
btIDebugDraw * m_debugDrawer
btScalar m_contactMotion2
const btMatrix3x3 & getInvInertiaTensorWorld() const
Definition: btRigidBody.h:274
virtual btScalar solveGroupCacheFriendlyFinish(btCollisionObject **bodies, int numBodies, const btContactSolverInfo &infoGlobal) BT_OVERRIDE
AllocContactConstraintsLoop(btSequentialImpulseConstraintSolverMt *solver, btSequentialImpulseConstraintSolverMt::btContactManifoldCachedInfo *cachedInfoArray)
void allocAllContactConstraints(btPersistentManifold **manifoldPtr, int numManifolds, const btContactSolverInfo &infoGlobal)
virtual void convertJoints(btTypedConstraint **constraints, int numConstraints, const btContactSolverInfo &infoGlobal)
T & expand(const T &fillValue=T())
btVector3 m_appliedTorqueBodyA
btSequentialImpulseConstraintSolverMt * m_solver
const btVector3 & getPositionWorldOnA() const
btSequentialImpulseConstraintSolverMt * m_solver
void writeBackBodies(int iBegin, int iEnd, const btContactSolverInfo &infoGlobal)
const btContactSolverInfo & m_infoGlobal
void setupContactConstraint(btSolverConstraint &solverConstraint, int solverBodyIdA, int solverBodyIdB, btManifoldPoint &cp, const btContactSolverInfo &infoGlobal, btScalar &relaxation, const btVector3 &rel_pos1, const btVector3 &rel_pos2)
InitJointsLoop(btSequentialImpulseConstraintSolverMt *solver, btTypedConstraint **constraints)
const btTransform & getWorldTransform() const
Definition: btSolverBody.h:130
void btParallelFor(int iBegin, int iEnd, int grainSize, const btIParallelForBody &body)
Definition: btThreads.cpp:429
void forLoop(int iBegin, int iEnd) const BT_OVERRIDE
void internalWriteBackBodies(int iBegin, int iEnd, const btContactSolverInfo &infoGlobal)
virtual void convertJoints(btTypedConstraint **constraints, int numConstraints, const btContactSolverInfo &infoGlobal) BT_OVERRIDE
void internalSetAppliedImpulse(btScalar appliedImpulse)
internal method used by the constraint solver, don&#39;t use them directly
WriteContactPointsLoop(btSequentialImpulseConstraintSolverMt *solver, const btContactSolverInfo &infoGlobal)
btVector3 m_lateralFrictionDir2
btSimdScalar m_appliedImpulse
btScalar getDistance() const
btScalar resolveMultipleJointConstraints(const btAlignedObjectArray< int > &consIndices, int batchBegin, int batchEnd, int iteration)
btVector3 computeGyroscopicImpulseImplicit_Body(btScalar step) const
perform implicit force computation in body space (inertial frame)
btScalar resolveSingleConstraintRowGeneric(btSolverBody &bodyA, btSolverBody &bodyB, const btSolverConstraint &contactConstraint)
btSequentialImpulseConstraintSolverMt * m_solver
const btRigidBody & getRigidBodyB() const
static void applyAnisotropicFriction(btCollisionObject *colObj, btVector3 &frictionDirection, int frictionMode)
btSequentialImpulseConstraintSolverMt * m_solver
const btCollisionObject * getBody1() const
void internalWriteBackJoints(int iBegin, int iEnd, const btContactSolverInfo &infoGlobal)
virtual void buildJacobian()
internal method used by the constraint solver, don&#39;t use them directly
btAlignedObjectArray< Range > m_batches
void convertJoint(btSolverConstraint *currentConstraintRow, btTypedConstraint *constraint, const btTypedConstraint::btConstraintInfo1 &info1, int solverBodyIdA, int solverBodyIdB, const btContactSolverInfo &infoGlobal)
float btScalar
The btScalar type abstracts floating point numbers, to easily switch between double and single floati...
Definition: btScalar.h:292
btSequentialImpulseConstraintSolverMt * m_solver
btScalar m_combinedSpinningFriction
int getFlags() const
Definition: btRigidBody.h:533
ConvertBodiesLoop(btSequentialImpulseConstraintSolverMt *solver, btCollisionObject **bodies, int numBodies, const btContactSolverInfo &infoGlobal)
virtual void solveGroupCacheFriendlySplitImpulseIterations(btCollisionObject **bodies, int numBodies, btPersistentManifold **manifoldPtr, int numManifolds, btTypedConstraint **constraints, int numConstraints, const btContactSolverInfo &infoGlobal, btIDebugDraw *debugDrawer) BT_OVERRIDE
btAlignedObjectArray< int > m_kinematicBodyUniqueIdToSolverBodyTable
static int uniqueId
Definition: btRigidBody.cpp:27
void internalWriteBackContacts(int iBegin, int iEnd, const btContactSolverInfo &infoGlobal)
void writeBackJoints(int iBegin, int iEnd, const btContactSolverInfo &infoGlobal)