Bullet Collision Detection & Physics Library
btDiscreteDynamicsWorldMt.cpp
Go to the documentation of this file.
1 /*
2 Bullet Continuous Collision Detection and Physics Library
3 Copyright (c) 2003-2009 Erwin Coumans http://bulletphysics.org
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 //collision detection
26 #include "LinearMath/btQuickprof.h"
27 
28 //rigidbody & constraints
40 
41 
44 
45 
47 #include "LinearMath/btQuickprof.h"
49 
51 
52 
53 
57 
59 {
60  int i = 0;
61 #if BT_THREADSAFE
62  i = btGetCurrentThreadIndex() % m_solvers.size();
63 #endif // #if BT_THREADSAFE
64  while ( true )
65  {
66  ThreadSolver& solver = m_solvers[ i ];
67  if ( solver.mutex.tryLock() )
68  {
69  return &solver;
70  }
71  // failed, try the next one
72  i = ( i + 1 ) % m_solvers.size();
73  }
74  return NULL;
75 }
76 
77 void btConstraintSolverPoolMt::init( btConstraintSolver** solvers, int numSolvers )
78 {
80  m_solvers.resize( numSolvers );
81  for ( int i = 0; i < numSolvers; ++i )
82  {
83  m_solvers[ i ].solver = solvers[ i ];
84  }
85  if ( numSolvers > 0 )
86  {
87  m_solverType = solvers[ 0 ]->getSolverType();
88  }
89 }
90 
91 // create the solvers for me
93 {
95  solvers.reserve( numSolvers );
96  for ( int i = 0; i < numSolvers; ++i )
97  {
99  solvers.push_back( solver );
100  }
101  init( &solvers[ 0 ], numSolvers );
102 }
103 
104 // pass in fully constructed solvers (destructor will delete them)
106 {
107  init( solvers, numSolvers );
108 }
109 
111 {
112  // delete all solvers
113  for ( int i = 0; i < m_solvers.size(); ++i )
114  {
115  ThreadSolver& solver = m_solvers[ i ];
116  delete solver.solver;
117  solver.solver = NULL;
118  }
119 }
120 
123  int numBodies,
124  btPersistentManifold** manifolds,
125  int numManifolds,
126  btTypedConstraint** constraints,
127  int numConstraints,
128  const btContactSolverInfo& info,
129  btIDebugDraw* debugDrawer,
130  btDispatcher* dispatcher
131 )
132 {
134  ts->solver->solveGroup( bodies, numBodies, manifolds, numManifolds, constraints, numConstraints, info, debugDrawer, dispatcher );
135  ts->mutex.unlock();
136  return 0.0f;
137 }
138 
140 {
141  for ( int i = 0; i < m_solvers.size(); ++i )
142  {
143  ThreadSolver& solver = m_solvers[ i ];
144  solver.mutex.lock();
145  solver.solver->reset();
146  solver.mutex.unlock();
147  }
148 }
149 
150 
154 
156  btBroadphaseInterface* pairCache,
157  btConstraintSolverPoolMt* constraintSolver,
158  btConstraintSolver* constraintSolverMt,
159  btCollisionConfiguration* collisionConfiguration
160 )
161 : btDiscreteDynamicsWorld(dispatcher,pairCache,constraintSolver,collisionConfiguration)
162 {
164  {
167  }
168  {
169  void* mem = btAlignedAlloc(sizeof(btSimulationIslandManagerMt),16);
172  m_islandManager = im;
173  }
174  m_constraintSolverMt = constraintSolverMt;
175 }
176 
177 
179 {
180 }
181 
182 
184 {
185  BT_PROFILE("solveConstraints");
186 
188 
192  solverParams.m_solverPool = m_constraintSolver;
193  solverParams.m_solverMt = m_constraintSolverMt;
194  solverParams.m_solverInfo = &solverInfo;
195  solverParams.m_debugDrawer = m_debugDrawer;
196  solverParams.m_dispatcher = getCollisionWorld()->getDispatcher();
198 
200 }
201 
202 
204 {
207 
208  void forLoop( int iBegin, int iEnd ) const BT_OVERRIDE
209  {
210  for ( int i = iBegin; i < iEnd; ++i )
211  {
212  btRigidBody* body = rigidBodies[ i ];
213  if ( !body->isStaticOrKinematicObject() )
214  {
215  //don't integrate/update velocities here, it happens in the constraint solver
216  body->applyDamping( timeStep );
218  }
219  }
220  }
221 };
222 
223 
225 {
226  BT_PROFILE( "predictUnconstraintMotion" );
227  if ( m_nonStaticRigidBodies.size() > 0 )
228  {
230  update.timeStep = timeStep;
231  update.rigidBodies = &m_nonStaticRigidBodies[ 0 ];
232  int grainSize = 50; // num of iterations per task for task scheduler
233  btParallelFor( 0, m_nonStaticRigidBodies.size(), grainSize, update );
234  }
235 }
236 
237 
239 {
240  BT_PROFILE( "createPredictiveContacts" );
242  if ( m_nonStaticRigidBodies.size() > 0 )
243  {
245  update.world = this;
246  update.timeStep = timeStep;
247  update.rigidBodies = &m_nonStaticRigidBodies[ 0 ];
248  int grainSize = 50; // num of iterations per task for task scheduler
249  btParallelFor( 0, m_nonStaticRigidBodies.size(), grainSize, update );
250  }
251 }
252 
253 
255 {
256  BT_PROFILE( "integrateTransforms" );
257  if ( m_nonStaticRigidBodies.size() > 0 )
258  {
260  update.world = this;
261  update.timeStep = timeStep;
262  update.rigidBodies = &m_nonStaticRigidBodies[ 0 ];
263  int grainSize = 50; // num of iterations per task for task scheduler
264  btParallelFor( 0, m_nonStaticRigidBodies.size(), grainSize, update );
265  }
266 }
267 
268 
269 int btDiscreteDynamicsWorldMt::stepSimulation( btScalar timeStep, int maxSubSteps, btScalar fixedTimeStep )
270 {
271  int numSubSteps = btDiscreteDynamicsWorld::stepSimulation(timeStep, maxSubSteps, fixedTimeStep);
272  if (btITaskScheduler* scheduler = btGetTaskScheduler())
273  {
274  // tell Bullet's threads to sleep, so other threads can run
275  scheduler->sleepWorkerThreadsHint();
276  }
277  return numSubSteps;
278 }
virtual btScalar solveGroup(btCollisionObject **bodies, int numBodies, btPersistentManifold **manifolds, int numManifolds, btTypedConstraint **constraints, int numConstraints, const btContactSolverInfo &info, btIDebugDraw *debugDrawer, btDispatcher *dispatcher) BT_OVERRIDE
solve a group of constraints
btPersistentManifold is a contact point cache, it stays persistent as long as objects are overlapping...
void push_back(const T &_Val)
btConstraintSolverPoolMt - masquerades as a constraint solver, but really it is a threadsafe pool of ...
btSimulationIslandManager * m_islandManager
btAlignedObjectArray< btRigidBody * > m_nonStaticRigidBodies
The btAlignedObjectArray template class uses a subset of the stl::vector interface for its methods It...
virtual void createPredictiveContacts(btScalar timeStep) BT_OVERRIDE
void predictIntegratedTransform(btScalar step, btTransform &predictedTransform)
continuous collision detection needs prediction
virtual void solveConstraints(btContactSolverInfo &solverInfo) BT_OVERRIDE
bool tryLock()
Definition: btThreads.cpp:216
btITaskScheduler * btGetTaskScheduler()
Definition: btThreads.cpp:423
btDiscreteDynamicsWorld provides discrete rigid body simulation those classes replace the obsolete Cc...
btDiscreteDynamicsWorldMt(btDispatcher *dispatcher, btBroadphaseInterface *pairCache, btConstraintSolverPoolMt *constraintSolver, btConstraintSolver *constraintSolverMt, btCollisionConfiguration *collisionConfiguration)
btDiscreteDynamicsWorldMt
btCollisionConfiguration allows to configure Bullet collision detection stack allocator size...
virtual btScalar solveGroup(btCollisionObject **bodies, int numBodies, btPersistentManifold **manifold, int numManifolds, btTypedConstraint **constraints, int numConstraints, const btContactSolverInfo &info, class btIDebugDraw *debugDrawer, btDispatcher *dispatcher)=0
solve a group of constraints
int getNumCollisionObjects() const
void init(btConstraintSolver **solvers, int numSolvers)
virtual void reset() BT_OVERRIDE
clear internal cached data and reset random seed
virtual void predictUnconstraintMotion(btScalar timeStep) BT_OVERRIDE
btContactSolverInfo m_solverInfo
const btTransform & getInterpolationWorldTransform() const
btCollisionWorld * getCollisionWorld()
btConstraintSolver * m_constraintSolverMt
int size() const
return the number of elements in the array
#define BT_OVERRIDE
Definition: btThreads.h:28
btIDebugDraw * m_debugDrawer
void lock()
Definition: btThreads.cpp:206
ThreadSolver * getAndLockThreadSolver()
btConstraintSolverPoolMt
virtual void integrateTransforms(btScalar timeStep) BT_OVERRIDE
virtual void buildAndProcessIslands(btDispatcher *dispatcher, btCollisionWorld *collisionWorld, btAlignedObjectArray< btTypedConstraint * > &constraints, const SolverParams &solverParams)
void unlock()
Definition: btThreads.cpp:211
bool isStaticOrKinematicObject() const
#define btAlignedFree(ptr)
btCollisionObject can be used to manage collision detection objects.
The btIDebugDraw interface class allows hooking up a debug renderer to visually debug simulations...
Definition: btIDebugDraw.h:29
The btRigidBody is the main class for rigid body objects.
Definition: btRigidBody.h:62
The btBroadphaseInterface class provides an interface to detect aabb-overlapping object pairs...
btDispatcher * getDispatcher()
virtual btConstraintSolverType getSolverType() const =0
virtual int stepSimulation(btScalar timeStep, int maxSubSteps=1, btScalar fixedTimeStep=btScalar(1.)/btScalar(60.))
if maxSubSteps > 0, it will interpolate motion between fixedTimeStep&#39;s
The btSequentialImpulseConstraintSolver is a fast SIMD implementation of the Projected Gauss Seidel (...
#define BT_PROFILE(name)
Definition: btQuickprof.h:216
btAlignedObjectArray< ThreadSolver > m_solvers
virtual void allSolved(const btContactSolverInfo &, class btIDebugDraw *)
void applyDamping(btScalar timeStep)
applyDamping damps the velocity, using the given m_linearDamping and m_angularDamping ...
virtual void prepareSolve(int, int)
TypedConstraint is the baseclass for Bullet constraints and vehicles.
btConstraintSolverType m_solverType
#define btAlignedAlloc(size, alignment)
btConstraintSolver * m_constraintSolver
void btParallelFor(int iBegin, int iEnd, int grainSize, const btIParallelForBody &body)
Definition: btThreads.cpp:429
unsigned int btGetCurrentThreadIndex()
Definition: btThreads.cpp:304
void forLoop(int iBegin, int iEnd) const BT_OVERRIDE
virtual void reset()=0
clear internal cached data and reset random seed
The btDispatcher interface class can be used in combination with broadphase to dispatch calculations ...
Definition: btDispatcher.h:77
virtual int stepSimulation(btScalar timeStep, int maxSubSteps, btScalar fixedTimeStep) BT_OVERRIDE
if maxSubSteps > 0, it will interpolate motion between fixedTimeStep&#39;s
float btScalar
The btScalar type abstracts floating point numbers, to easily switch between double and single floati...
Definition: btScalar.h:292
SimulationIslandManagerMt – Multithread capable version of SimulationIslandManager Splits the world ...
btAlignedObjectArray< btTypedConstraint * > m_constraints