MultiThreaded Demo:

- fixing various race conditions throughout (usage of static vars, etc)
 - addition of a few lightweight mutexes (which are compiled out by default)
 - slight code rearrangement in discreteDynamicsWorld to facilitate multithreading
 - PoolAllocator::allocate() can now be called when pool is full without
     crashing (null pointer returned)
 - PoolAllocator allocate and freeMemory, are OPTIONALLY threadsafe
     (default is un-threadsafe)
 - CollisionDispatcher no longer checks if the pool allocator is full
     before calling allocate(), instead it just calls allocate() and
     checks if the return is null -- this avoids a race condition
 - SequentialImpulseConstraintSolver OPTIONALLY uses different logic in
     getOrInitSolverBody() to avoid a race condition with kinematic bodies
 - addition of 2 classes which together allow simulation islands to be run
   in parallel:
    - btSimulationIslandManagerMt
    - btDiscreteDynamicsWorldMt
 - MultiThreadedDemo example in the example browser demonstrating use of
   OpenMP, Microsoft PPL, and Intel TBB
 - use multithreading for other demos
 - benchmark demo: add parallel raycasting
This commit is contained in:
Lunkhound
2016-09-27 00:01:45 -07:00
parent f01389ded2
commit 1c3686ca51
48 changed files with 3168 additions and 197 deletions

View File

@@ -267,7 +267,6 @@ struct btDbvt
btAlignedObjectArray<sStkNN> m_stkStack;
mutable btAlignedObjectArray<const btDbvtNode*> m_rayTestStack;
// Methods
@@ -357,6 +356,7 @@ struct btDbvt
btScalar lambda_max,
const btVector3& aabbMin,
const btVector3& aabbMax,
btAlignedObjectArray<const btDbvtNode*>& stack,
DBVT_IPOLICY) const;
DBVT_PREFIX
@@ -1006,7 +1006,8 @@ inline void btDbvt::rayTestInternal( const btDbvtNode* root,
btScalar lambda_max,
const btVector3& aabbMin,
const btVector3& aabbMax,
DBVT_IPOLICY) const
btAlignedObjectArray<const btDbvtNode*>& stack,
DBVT_IPOLICY ) const
{
(void) rayTo;
DBVT_CHECKTYPE
@@ -1016,7 +1017,6 @@ inline void btDbvt::rayTestInternal( const btDbvtNode* root,
int depth=1;
int treshold=DOUBLE_STACKSIZE-2;
btAlignedObjectArray<const btDbvtNode*>& stack = m_rayTestStack;
stack.resize(DOUBLE_STACKSIZE);
stack[0]=root;
btVector3 bounds[2];

View File

@@ -16,6 +16,7 @@ subject to the following restrictions:
///btDbvtBroadphase implementation by Nathanael Presson
#include "btDbvtBroadphase.h"
#include "LinearMath/btThreads.h"
//
// Profiling
@@ -142,6 +143,11 @@ btDbvtBroadphase::btDbvtBroadphase(btOverlappingPairCache* paircache)
{
m_stageRoots[i]=0;
}
#if BT_THREADSAFE
m_rayTestStacks.resize(BT_MAX_THREAD_COUNT);
#else
m_rayTestStacks.resize(1);
#endif
#if DBVT_BP_PROFILE
clear(m_profiling);
#endif
@@ -227,6 +233,23 @@ struct BroadphaseRayTester : btDbvt::ICollide
void btDbvtBroadphase::rayTest(const btVector3& rayFrom,const btVector3& rayTo, btBroadphaseRayCallback& rayCallback,const btVector3& aabbMin,const btVector3& aabbMax)
{
BroadphaseRayTester callback(rayCallback);
btAlignedObjectArray<const btDbvtNode*>* stack = &m_rayTestStacks[0];
#if BT_THREADSAFE
// for this function to be threadsafe, each thread must have a separate copy
// of this stack. This could be thread-local static to avoid dynamic allocations,
// instead of just a local.
int threadIndex = btGetCurrentThreadIndex();
btAlignedObjectArray<const btDbvtNode*> localStack;
if (threadIndex < m_rayTestStacks.size())
{
// use per-thread preallocated stack if possible to avoid dynamic allocations
stack = &m_rayTestStacks[threadIndex];
}
else
{
stack = &localStack;
}
#endif
m_sets[0].rayTestInternal( m_sets[0].m_root,
rayFrom,
@@ -236,6 +259,7 @@ void btDbvtBroadphase::rayTest(const btVector3& rayFrom,const btVector3& rayTo,
rayCallback.m_lambda_max,
aabbMin,
aabbMax,
*stack,
callback);
m_sets[1].rayTestInternal( m_sets[1].m_root,
@@ -246,6 +270,7 @@ void btDbvtBroadphase::rayTest(const btVector3& rayFrom,const btVector3& rayTo,
rayCallback.m_lambda_max,
aabbMin,
aabbMax,
*stack,
callback);
}

View File

@@ -87,6 +87,7 @@ struct btDbvtBroadphase : btBroadphaseInterface
bool m_releasepaircache; // Release pair cache on delete
bool m_deferedcollide; // Defere dynamic/static collision to collide call
bool m_needcleanup; // Need to run cleanup?
btAlignedObjectArray< btAlignedObjectArray<const btDbvtNode*> > m_rayTestStacks;
#if DBVT_BP_PROFILE
btClock m_clock;
struct {

View File

@@ -33,6 +33,7 @@ SET(BulletCollision_SRCS
CollisionDispatch/btInternalEdgeUtility.h
CollisionDispatch/btManifoldResult.cpp
CollisionDispatch/btSimulationIslandManager.cpp
CollisionDispatch/btSimulationIslandManagerMt.cpp
CollisionDispatch/btSphereBoxCollisionAlgorithm.cpp
CollisionDispatch/btSphereSphereCollisionAlgorithm.cpp
CollisionDispatch/btSphereTriangleCollisionAlgorithm.cpp
@@ -140,6 +141,7 @@ SET(CollisionDispatch_HDRS
CollisionDispatch/btHashedSimplePairCache.h
CollisionDispatch/btManifoldResult.h
CollisionDispatch/btSimulationIslandManager.h
CollisionDispatch/btSimulationIslandManagerMt.h
CollisionDispatch/btSphereBoxCollisionAlgorithm.h
CollisionDispatch/btSphereSphereCollisionAlgorithm.h
CollisionDispatch/btSphereTriangleCollisionAlgorithm.h

View File

@@ -84,14 +84,10 @@ btPersistentManifold* btCollisionDispatcher::getNewManifold(const btCollisionObj
btScalar contactProcessingThreshold = btMin(body0->getContactProcessingThreshold(),body1->getContactProcessingThreshold());
void* mem = 0;
if (m_persistentManifoldPoolAllocator->getFreeCount())
void* mem = m_persistentManifoldPoolAllocator->allocate( sizeof( btPersistentManifold ) );
if (NULL == mem)
{
mem = m_persistentManifoldPoolAllocator->allocate(sizeof(btPersistentManifold));
} else
{
//we got a pool memory overflow, by default we fallback to dynamically allocate memory. If we require a contiguous contact pool then assert.
//we got a pool memory overflow, by default we fallback to dynamically allocate memory. If we require a contiguous contact pool then assert.
if ((m_dispatcherFlags&CD_DISABLE_CONTACTPOOL_DYNAMIC_ALLOCATION)==0)
{
mem = btAlignedAlloc(sizeof(btPersistentManifold),16);
@@ -294,13 +290,13 @@ void btCollisionDispatcher::defaultNearCallback(btBroadphasePair& collisionPair,
void* btCollisionDispatcher::allocateCollisionAlgorithm(int size)
{
if (m_collisionAlgorithmPoolAllocator->getFreeCount())
{
return m_collisionAlgorithmPoolAllocator->allocate(size);
}
//warn user for overflow?
return btAlignedAlloc(static_cast<size_t>(size), 16);
void* mem = m_collisionAlgorithmPoolAllocator->allocate( size );
if (NULL == mem)
{
//warn user for overflow?
return btAlignedAlloc(static_cast<size_t>(size), 16);
}
return mem;
}
void btCollisionDispatcher::freeCollisionAlgorithm(void* ptr)

View File

@@ -79,6 +79,7 @@ protected:
int m_islandTag1;
int m_companionId;
int m_uniqueId;
mutable int m_activationState1;
mutable btScalar m_deactivationTime;
@@ -455,7 +456,17 @@ public:
m_companionId = id;
}
SIMD_FORCE_INLINE btScalar getHitFraction() const
SIMD_FORCE_INLINE int getUniqueId() const
{
return m_uniqueId;
}
void setUniqueId( int id )
{
m_uniqueId = id;
}
SIMD_FORCE_INLINE btScalar getHitFraction() const
{
return m_hitFraction;
}

View File

@@ -179,11 +179,10 @@ static SIMD_FORCE_INLINE btScalar capsuleCapsuleDistance(
btConvexConvexAlgorithm::CreateFunc::CreateFunc(btSimplexSolverInterface* simplexSolver, btConvexPenetrationDepthSolver* pdSolver)
btConvexConvexAlgorithm::CreateFunc::CreateFunc(btConvexPenetrationDepthSolver* pdSolver)
{
m_numPerturbationIterations = 0;
m_minimumPointsPerturbationThreshold = 3;
m_simplexSolver = simplexSolver;
m_pdSolver = pdSolver;
}
@@ -191,9 +190,8 @@ btConvexConvexAlgorithm::CreateFunc::~CreateFunc()
{
}
btConvexConvexAlgorithm::btConvexConvexAlgorithm(btPersistentManifold* mf,const btCollisionAlgorithmConstructionInfo& ci,const btCollisionObjectWrapper* body0Wrap,const btCollisionObjectWrapper* body1Wrap,btSimplexSolverInterface* simplexSolver, btConvexPenetrationDepthSolver* pdSolver,int numPerturbationIterations, int minimumPointsPerturbationThreshold)
btConvexConvexAlgorithm::btConvexConvexAlgorithm(btPersistentManifold* mf,const btCollisionAlgorithmConstructionInfo& ci,const btCollisionObjectWrapper* body0Wrap,const btCollisionObjectWrapper* body1Wrap,btConvexPenetrationDepthSolver* pdSolver,int numPerturbationIterations, int minimumPointsPerturbationThreshold)
: btActivatingCollisionAlgorithm(ci,body0Wrap,body1Wrap),
m_simplexSolver(simplexSolver),
m_pdSolver(pdSolver),
m_ownManifold (false),
m_manifoldPtr(mf),
@@ -349,8 +347,8 @@ void btConvexConvexAlgorithm ::processCollision (const btCollisionObjectWrapper*
btGjkPairDetector::ClosestPointInput input;
btGjkPairDetector gjkPairDetector(min0,min1,m_simplexSolver,m_pdSolver);
btVoronoiSimplexSolver simplexSolver;
btGjkPairDetector gjkPairDetector( min0, min1, &simplexSolver, m_pdSolver );
//TODO: if (dispatchInfo.m_useContinuous)
gjkPairDetector.setMinkowskiA(min0);
gjkPairDetector.setMinkowskiB(min1);

View File

@@ -43,7 +43,6 @@ class btConvexConvexAlgorithm : public btActivatingCollisionAlgorithm
#ifdef USE_SEPDISTANCE_UTIL2
btConvexSeparatingDistanceUtil m_sepDistance;
#endif
btSimplexSolverInterface* m_simplexSolver;
btConvexPenetrationDepthSolver* m_pdSolver;
btVertexArray worldVertsB1;
@@ -62,7 +61,7 @@ class btConvexConvexAlgorithm : public btActivatingCollisionAlgorithm
public:
btConvexConvexAlgorithm(btPersistentManifold* mf,const btCollisionAlgorithmConstructionInfo& ci,const btCollisionObjectWrapper* body0Wrap,const btCollisionObjectWrapper* body1Wrap, btSimplexSolverInterface* simplexSolver, btConvexPenetrationDepthSolver* pdSolver, int numPerturbationIterations, int minimumPointsPerturbationThreshold);
btConvexConvexAlgorithm(btPersistentManifold* mf,const btCollisionAlgorithmConstructionInfo& ci,const btCollisionObjectWrapper* body0Wrap,const btCollisionObjectWrapper* body1Wrap, btConvexPenetrationDepthSolver* pdSolver, int numPerturbationIterations, int minimumPointsPerturbationThreshold);
virtual ~btConvexConvexAlgorithm();
@@ -90,18 +89,17 @@ public:
{
btConvexPenetrationDepthSolver* m_pdSolver;
btSimplexSolverInterface* m_simplexSolver;
int m_numPerturbationIterations;
int m_minimumPointsPerturbationThreshold;
CreateFunc(btSimplexSolverInterface* simplexSolver, btConvexPenetrationDepthSolver* pdSolver);
CreateFunc(btConvexPenetrationDepthSolver* pdSolver);
virtual ~CreateFunc();
virtual btCollisionAlgorithm* CreateCollisionAlgorithm(btCollisionAlgorithmConstructionInfo& ci, const btCollisionObjectWrapper* body0Wrap,const btCollisionObjectWrapper* body1Wrap)
{
void* mem = ci.m_dispatcher1->allocateCollisionAlgorithm(sizeof(btConvexConvexAlgorithm));
return new(mem) btConvexConvexAlgorithm(ci.m_manifold,ci,body0Wrap,body1Wrap,m_simplexSolver,m_pdSolver,m_numPerturbationIterations,m_minimumPointsPerturbationThreshold);
return new(mem) btConvexConvexAlgorithm(ci.m_manifold,ci,body0Wrap,body1Wrap,m_pdSolver,m_numPerturbationIterations,m_minimumPointsPerturbationThreshold);
}
};

View File

@@ -44,9 +44,7 @@ btDefaultCollisionConfiguration::btDefaultCollisionConfiguration(const btDefault
//btDefaultCollisionConfiguration::btDefaultCollisionConfiguration(btStackAlloc* stackAlloc,btPoolAllocator* persistentManifoldPool,btPoolAllocator* collisionAlgorithmPool)
{
void* mem = btAlignedAlloc(sizeof(btVoronoiSimplexSolver),16);
m_simplexSolver = new (mem)btVoronoiSimplexSolver();
void* mem = NULL;
if (constructionInfo.m_useEpaPenetrationAlgorithm)
{
mem = btAlignedAlloc(sizeof(btGjkEpaPenetrationDepthSolver),16);
@@ -59,7 +57,7 @@ btDefaultCollisionConfiguration::btDefaultCollisionConfiguration(const btDefault
//default CreationFunctions, filling the m_doubleDispatch table
mem = btAlignedAlloc(sizeof(btConvexConvexAlgorithm::CreateFunc),16);
m_convexConvexCreateFunc = new(mem) btConvexConvexAlgorithm::CreateFunc(m_simplexSolver,m_pdSolver);
m_convexConvexCreateFunc = new(mem) btConvexConvexAlgorithm::CreateFunc(m_pdSolver);
mem = btAlignedAlloc(sizeof(btConvexConcaveCollisionAlgorithm::CreateFunc),16);
m_convexConcaveCreateFunc = new (mem)btConvexConcaveCollisionAlgorithm::CreateFunc;
mem = btAlignedAlloc(sizeof(btConvexConcaveCollisionAlgorithm::CreateFunc),16);
@@ -193,9 +191,6 @@ btDefaultCollisionConfiguration::~btDefaultCollisionConfiguration()
m_planeConvexCF->~btCollisionAlgorithmCreateFunc();
btAlignedFree( m_planeConvexCF);
m_simplexSolver->~btVoronoiSimplexSolver();
btAlignedFree(m_simplexSolver);
m_pdSolver->~btConvexPenetrationDepthSolver();
btAlignedFree(m_pdSolver);

View File

@@ -60,8 +60,7 @@ protected:
btPoolAllocator* m_collisionAlgorithmPool;
bool m_ownsCollisionAlgorithmPool;
//default simplex/penetration depth solvers
btVoronoiSimplexSolver* m_simplexSolver;
//default penetration depth solver
btConvexPenetrationDepthSolver* m_pdSolver;
//default CreationFunctions, filling the m_doubleDispatch table
@@ -102,12 +101,6 @@ public:
}
virtual btVoronoiSimplexSolver* getSimplexSolver()
{
return m_simplexSolver;
}
virtual btCollisionAlgorithmCreateFunc* getCollisionAlgorithmCreateFunc(int proxyType0,int proxyType1);
///Use this method to allow to generate multiple contact points between at once, between two objects using the generic convex-convex algorithm.

View File

@@ -0,0 +1,641 @@
/*
Bullet Continuous Collision Detection and Physics Library
Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/
This software is provided 'as-is', without any express or implied warranty.
In no event will the authors be held liable for any damages arising from the use of this software.
Permission is granted to anyone to use this software for any purpose,
including commercial applications, and to alter it and redistribute it freely,
subject to the following restrictions:
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.
2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software.
3. This notice may not be removed or altered from any source distribution.
*/
#include "LinearMath/btScalar.h"
#include "btSimulationIslandManagerMt.h"
#include "BulletCollision/BroadphaseCollision/btDispatcher.h"
#include "BulletCollision/NarrowPhaseCollision/btPersistentManifold.h"
#include "BulletCollision/CollisionDispatch/btCollisionObject.h"
#include "BulletCollision/CollisionDispatch/btCollisionWorld.h"
#include "BulletDynamics/ConstraintSolver/btTypedConstraint.h"
//#include <stdio.h>
#include "LinearMath/btQuickprof.h"
SIMD_FORCE_INLINE int calcBatchCost( int bodies, int manifolds, int constraints )
{
// rough estimate of the cost of a batch, used for merging
int batchCost = bodies + 8 * manifolds + 4 * constraints;
return batchCost;
}
SIMD_FORCE_INLINE int calcBatchCost( const btSimulationIslandManagerMt::Island* island )
{
return calcBatchCost( island->bodyArray.size(), island->manifoldArray.size(), island->constraintArray.size() );
}
btSimulationIslandManagerMt::btSimulationIslandManagerMt()
{
m_minimumSolverBatchSize = calcBatchCost(0, 128, 0);
m_batchIslandMinBodyCount = 32;
m_islandDispatch = defaultIslandDispatch;
m_batchIsland = NULL;
}
btSimulationIslandManagerMt::~btSimulationIslandManagerMt()
{
for ( int i = 0; i < m_allocatedIslands.size(); ++i )
{
delete m_allocatedIslands[ i ];
}
m_allocatedIslands.resize( 0 );
m_activeIslands.resize( 0 );
m_freeIslands.resize( 0 );
}
inline int getIslandId(const btPersistentManifold* lhs)
{
const btCollisionObject* rcolObj0 = static_cast<const btCollisionObject*>(lhs->getBody0());
const btCollisionObject* rcolObj1 = static_cast<const btCollisionObject*>(lhs->getBody1());
int islandId = rcolObj0->getIslandTag() >= 0 ? rcolObj0->getIslandTag() : rcolObj1->getIslandTag();
return islandId;
}
SIMD_FORCE_INLINE int btGetConstraintIslandId( const btTypedConstraint* lhs )
{
const btCollisionObject& rcolObj0 = lhs->getRigidBodyA();
const btCollisionObject& rcolObj1 = lhs->getRigidBodyB();
int islandId = rcolObj0.getIslandTag() >= 0 ? rcolObj0.getIslandTag() : rcolObj1.getIslandTag();
return islandId;
}
/// function object that routes calls to operator<
class IslandBatchSizeSortPredicate
{
public:
bool operator() ( const btSimulationIslandManagerMt::Island* lhs, const btSimulationIslandManagerMt::Island* rhs ) const
{
int lCost = calcBatchCost( lhs );
int rCost = calcBatchCost( rhs );
return lCost > rCost;
}
};
class IslandBodyCapacitySortPredicate
{
public:
bool operator() ( const btSimulationIslandManagerMt::Island* lhs, const btSimulationIslandManagerMt::Island* rhs ) const
{
return lhs->bodyArray.capacity() > rhs->bodyArray.capacity();
}
};
void btSimulationIslandManagerMt::Island::append( const Island& other )
{
// append bodies
for ( int i = 0; i < other.bodyArray.size(); ++i )
{
bodyArray.push_back( other.bodyArray[ i ] );
}
// append manifolds
for ( int i = 0; i < other.manifoldArray.size(); ++i )
{
manifoldArray.push_back( other.manifoldArray[ i ] );
}
// append constraints
for ( int i = 0; i < other.constraintArray.size(); ++i )
{
constraintArray.push_back( other.constraintArray[ i ] );
}
}
bool btIsBodyInIsland( const btSimulationIslandManagerMt::Island& island, const btCollisionObject* obj )
{
for ( int i = 0; i < island.bodyArray.size(); ++i )
{
if ( island.bodyArray[ i ] == obj )
{
return true;
}
}
return false;
}
void btSimulationIslandManagerMt::initIslandPools()
{
// reset island pools
int numElem = getUnionFind().getNumElements();
m_lookupIslandFromId.resize( numElem );
for ( int i = 0; i < m_lookupIslandFromId.size(); ++i )
{
m_lookupIslandFromId[ i ] = NULL;
}
m_activeIslands.resize( 0 );
m_freeIslands.resize( 0 );
// check whether allocated islands are sorted by body capacity (largest to smallest)
int lastCapacity = 0;
bool isSorted = true;
for ( int i = 0; i < m_allocatedIslands.size(); ++i )
{
Island* island = m_allocatedIslands[ i ];
int cap = island->bodyArray.capacity();
if ( cap > lastCapacity )
{
isSorted = false;
break;
}
lastCapacity = cap;
}
if ( !isSorted )
{
m_allocatedIslands.quickSort( IslandBodyCapacitySortPredicate() );
}
m_batchIsland = NULL;
// mark all islands free (but avoid deallocation)
for ( int i = 0; i < m_allocatedIslands.size(); ++i )
{
Island* island = m_allocatedIslands[ i ];
island->bodyArray.resize( 0 );
island->manifoldArray.resize( 0 );
island->constraintArray.resize( 0 );
island->id = -1;
island->isSleeping = true;
m_freeIslands.push_back( island );
}
}
btSimulationIslandManagerMt::Island* btSimulationIslandManagerMt::getIsland( int id )
{
Island* island = m_lookupIslandFromId[ id ];
if ( island == NULL )
{
// search for existing island
for ( int i = 0; i < m_activeIslands.size(); ++i )
{
if ( m_activeIslands[ i ]->id == id )
{
island = m_activeIslands[ i ];
break;
}
}
m_lookupIslandFromId[ id ] = island;
}
return island;
}
btSimulationIslandManagerMt::Island* btSimulationIslandManagerMt::allocateIsland( int id, int numBodies )
{
Island* island = NULL;
int allocSize = numBodies;
if ( numBodies < m_batchIslandMinBodyCount )
{
if ( m_batchIsland )
{
island = m_batchIsland;
m_lookupIslandFromId[ id ] = island;
// if we've made a large enough batch,
if ( island->bodyArray.size() + numBodies >= m_batchIslandMinBodyCount )
{
// next time start a new batch
m_batchIsland = NULL;
}
return island;
}
else
{
// need to allocate a batch island
allocSize = m_batchIslandMinBodyCount * 2;
}
}
btAlignedObjectArray<Island*>& freeIslands = m_freeIslands;
// search for free island
if ( freeIslands.size() > 0 )
{
// try to reuse a previously allocated island
int iFound = freeIslands.size();
// linear search for smallest island that can hold our bodies
for ( int i = freeIslands.size() - 1; i >= 0; --i )
{
if ( freeIslands[ i ]->bodyArray.capacity() >= allocSize )
{
iFound = i;
island = freeIslands[ i ];
island->id = id;
break;
}
}
// if found, shrink array while maintaining ordering
if ( island )
{
int iDest = iFound;
int iSrc = iDest + 1;
while ( iSrc < freeIslands.size() )
{
freeIslands[ iDest++ ] = freeIslands[ iSrc++ ];
}
freeIslands.pop_back();
}
}
if ( island == NULL )
{
// no free island found, allocate
island = new Island(); // TODO: change this to use the pool allocator
island->id = id;
island->bodyArray.reserve( allocSize );
m_allocatedIslands.push_back( island );
}
m_lookupIslandFromId[ id ] = island;
if ( numBodies < m_batchIslandMinBodyCount )
{
m_batchIsland = island;
}
m_activeIslands.push_back( island );
return island;
}
void btSimulationIslandManagerMt::buildIslands( btDispatcher* dispatcher, btCollisionWorld* collisionWorld )
{
BT_PROFILE("islandUnionFindAndQuickSort");
btCollisionObjectArray& collisionObjects = collisionWorld->getCollisionObjectArray();
//we are going to sort the unionfind array, and store the element id in the size
//afterwards, we clean unionfind, to make sure no-one uses it anymore
getUnionFind().sortIslands();
int numElem = getUnionFind().getNumElements();
int endIslandIndex=1;
int startIslandIndex;
//update the sleeping state for bodies, if all are sleeping
for ( startIslandIndex=0;startIslandIndex<numElem;startIslandIndex = endIslandIndex)
{
int islandId = getUnionFind().getElement(startIslandIndex).m_id;
for (endIslandIndex = startIslandIndex+1;(endIslandIndex<numElem) && (getUnionFind().getElement(endIslandIndex).m_id == islandId);endIslandIndex++)
{
}
//int numSleeping = 0;
bool allSleeping = true;
int idx;
for (idx=startIslandIndex;idx<endIslandIndex;idx++)
{
int i = getUnionFind().getElement(idx).m_sz;
btCollisionObject* colObj0 = collisionObjects[i];
if ((colObj0->getIslandTag() != islandId) && (colObj0->getIslandTag() != -1))
{
// printf("error in island management\n");
}
btAssert((colObj0->getIslandTag() == islandId) || (colObj0->getIslandTag() == -1));
if (colObj0->getIslandTag() == islandId)
{
if (colObj0->getActivationState()== ACTIVE_TAG)
{
allSleeping = false;
}
if (colObj0->getActivationState()== DISABLE_DEACTIVATION)
{
allSleeping = false;
}
}
}
if (allSleeping)
{
int idx;
for (idx=startIslandIndex;idx<endIslandIndex;idx++)
{
int i = getUnionFind().getElement(idx).m_sz;
btCollisionObject* colObj0 = collisionObjects[i];
if ((colObj0->getIslandTag() != islandId) && (colObj0->getIslandTag() != -1))
{
// printf("error in island management\n");
}
btAssert((colObj0->getIslandTag() == islandId) || (colObj0->getIslandTag() == -1));
if (colObj0->getIslandTag() == islandId)
{
colObj0->setActivationState( ISLAND_SLEEPING );
}
}
} else
{
int idx;
for (idx=startIslandIndex;idx<endIslandIndex;idx++)
{
int i = getUnionFind().getElement(idx).m_sz;
btCollisionObject* colObj0 = collisionObjects[i];
if ((colObj0->getIslandTag() != islandId) && (colObj0->getIslandTag() != -1))
{
// printf("error in island management\n");
}
btAssert((colObj0->getIslandTag() == islandId) || (colObj0->getIslandTag() == -1));
if (colObj0->getIslandTag() == islandId)
{
if ( colObj0->getActivationState() == ISLAND_SLEEPING)
{
colObj0->setActivationState( WANTS_DEACTIVATION);
colObj0->setDeactivationTime(0.f);
}
}
}
}
}
}
void btSimulationIslandManagerMt::addBodiesToIslands( btCollisionWorld* collisionWorld )
{
btCollisionObjectArray& collisionObjects = collisionWorld->getCollisionObjectArray();
int endIslandIndex = 1;
int startIslandIndex;
int numElem = getUnionFind().getNumElements();
// create explicit islands and add bodies to each
for ( startIslandIndex = 0; startIslandIndex < numElem; startIslandIndex = endIslandIndex )
{
int islandId = getUnionFind().getElement( startIslandIndex ).m_id;
// find end index
for ( endIslandIndex = startIslandIndex; ( endIslandIndex < numElem ) && ( getUnionFind().getElement( endIslandIndex ).m_id == islandId ); endIslandIndex++ )
{
}
// check if island is sleeping
bool islandSleeping = true;
for ( int iElem = startIslandIndex; iElem < endIslandIndex; iElem++ )
{
int i = getUnionFind().getElement( iElem ).m_sz;
btCollisionObject* colObj = collisionObjects[ i ];
if ( colObj->isActive() )
{
islandSleeping = false;
}
}
if ( !islandSleeping )
{
// want to count the number of bodies before allocating the island to optimize memory usage of the Island structures
int numBodies = endIslandIndex - startIslandIndex;
Island* island = allocateIsland( islandId, numBodies );
island->isSleeping = false;
// add bodies to island
for ( int iElem = startIslandIndex; iElem < endIslandIndex; iElem++ )
{
int i = getUnionFind().getElement( iElem ).m_sz;
btCollisionObject* colObj = collisionObjects[ i ];
island->bodyArray.push_back( colObj );
}
}
}
}
void btSimulationIslandManagerMt::addManifoldsToIslands( btDispatcher* dispatcher )
{
// walk all the manifolds, activating bodies touched by kinematic objects, and add each manifold to its Island
int maxNumManifolds = dispatcher->getNumManifolds();
for ( int i = 0; i < maxNumManifolds; i++ )
{
btPersistentManifold* manifold = dispatcher->getManifoldByIndexInternal( i );
const btCollisionObject* colObj0 = static_cast<const btCollisionObject*>( manifold->getBody0() );
const btCollisionObject* colObj1 = static_cast<const btCollisionObject*>( manifold->getBody1() );
///@todo: check sleeping conditions!
if ( ( ( colObj0 ) && colObj0->getActivationState() != ISLAND_SLEEPING ) ||
( ( colObj1 ) && colObj1->getActivationState() != ISLAND_SLEEPING ) )
{
//kinematic objects don't merge islands, but wake up all connected objects
if ( colObj0->isKinematicObject() && colObj0->getActivationState() != ISLAND_SLEEPING )
{
if ( colObj0->hasContactResponse() )
colObj1->activate();
}
if ( colObj1->isKinematicObject() && colObj1->getActivationState() != ISLAND_SLEEPING )
{
if ( colObj1->hasContactResponse() )
colObj0->activate();
}
//filtering for response
if ( dispatcher->needsResponse( colObj0, colObj1 ) )
{
// scatter manifolds into various islands
int islandId = getIslandId( manifold );
// if island not sleeping,
if ( Island* island = getIsland( islandId ) )
{
island->manifoldArray.push_back( manifold );
}
}
}
}
}
void btSimulationIslandManagerMt::addConstraintsToIslands( btAlignedObjectArray<btTypedConstraint*>& constraints )
{
// walk constraints
for ( int i = 0; i < constraints.size(); i++ )
{
// scatter constraints into various islands
btTypedConstraint* constraint = constraints[ i ];
if ( constraint->isEnabled() )
{
int islandId = btGetConstraintIslandId( constraint );
// if island is not sleeping,
if ( Island* island = getIsland( islandId ) )
{
island->constraintArray.push_back( constraint );
}
}
}
}
void btSimulationIslandManagerMt::mergeIslands()
{
// sort islands in order of decreasing batch size
m_activeIslands.quickSort( IslandBatchSizeSortPredicate() );
// merge small islands to satisfy minimum batch size
// find first small batch island
int destIslandIndex = m_activeIslands.size();
for ( int i = 0; i < m_activeIslands.size(); ++i )
{
Island* island = m_activeIslands[ i ];
int batchSize = calcBatchCost( island );
if ( batchSize < m_minimumSolverBatchSize )
{
destIslandIndex = i;
break;
}
}
int lastIndex = m_activeIslands.size() - 1;
while ( destIslandIndex < lastIndex )
{
// merge islands from the back of the list
Island* island = m_activeIslands[ destIslandIndex ];
int numBodies = island->bodyArray.size();
int numManifolds = island->manifoldArray.size();
int numConstraints = island->constraintArray.size();
int firstIndex = lastIndex;
// figure out how many islands we want to merge and find out how many bodies, manifolds and constraints we will have
while ( true )
{
Island* src = m_activeIslands[ firstIndex ];
numBodies += src->bodyArray.size();
numManifolds += src->manifoldArray.size();
numConstraints += src->constraintArray.size();
int batchCost = calcBatchCost( numBodies, numManifolds, numConstraints );
if ( batchCost >= m_minimumSolverBatchSize )
{
break;
}
if ( firstIndex - 1 == destIslandIndex )
{
break;
}
firstIndex--;
}
// reserve space for these pointers to minimize reallocation
island->bodyArray.reserve( numBodies );
island->manifoldArray.reserve( numManifolds );
island->constraintArray.reserve( numConstraints );
// merge islands
for ( int i = firstIndex; i <= lastIndex; ++i )
{
island->append( *m_activeIslands[ i ] );
}
// shrink array to exclude the islands that were merged from
m_activeIslands.resize( firstIndex );
lastIndex = firstIndex - 1;
destIslandIndex++;
}
}
void btSimulationIslandManagerMt::defaultIslandDispatch( btAlignedObjectArray<Island*>* islandsPtr, IslandCallback* callback )
{
// serial dispatch
btAlignedObjectArray<Island*>& islands = *islandsPtr;
for ( int i = 0; i < islands.size(); ++i )
{
Island* island = islands[ i ];
btPersistentManifold** manifolds = island->manifoldArray.size() ? &island->manifoldArray[ 0 ] : NULL;
btTypedConstraint** constraintsPtr = island->constraintArray.size() ? &island->constraintArray[ 0 ] : NULL;
callback->processIsland( &island->bodyArray[ 0 ],
island->bodyArray.size(),
manifolds,
island->manifoldArray.size(),
constraintsPtr,
island->constraintArray.size(),
island->id
);
}
}
///@todo: this is random access, it can be walked 'cache friendly'!
void btSimulationIslandManagerMt::buildAndProcessIslands( btDispatcher* dispatcher,
btCollisionWorld* collisionWorld,
btAlignedObjectArray<btTypedConstraint*>& constraints,
IslandCallback* callback
)
{
btCollisionObjectArray& collisionObjects = collisionWorld->getCollisionObjectArray();
buildIslands(dispatcher,collisionWorld);
BT_PROFILE("processIslands");
if(!getSplitIslands())
{
btPersistentManifold** manifolds = dispatcher->getInternalManifoldPointer();
int maxNumManifolds = dispatcher->getNumManifolds();
for ( int i = 0; i < maxNumManifolds; i++ )
{
btPersistentManifold* manifold = manifolds[ i ];
const btCollisionObject* colObj0 = static_cast<const btCollisionObject*>( manifold->getBody0() );
const btCollisionObject* colObj1 = static_cast<const btCollisionObject*>( manifold->getBody1() );
///@todo: check sleeping conditions!
if ( ( ( colObj0 ) && colObj0->getActivationState() != ISLAND_SLEEPING ) ||
( ( colObj1 ) && colObj1->getActivationState() != ISLAND_SLEEPING ) )
{
//kinematic objects don't merge islands, but wake up all connected objects
if ( colObj0->isKinematicObject() && colObj0->getActivationState() != ISLAND_SLEEPING )
{
if ( colObj0->hasContactResponse() )
colObj1->activate();
}
if ( colObj1->isKinematicObject() && colObj1->getActivationState() != ISLAND_SLEEPING )
{
if ( colObj1->hasContactResponse() )
colObj0->activate();
}
}
}
btTypedConstraint** constraintsPtr = constraints.size() ? &constraints[ 0 ] : NULL;
callback->processIsland(&collisionObjects[0],
collisionObjects.size(),
manifolds,
maxNumManifolds,
constraintsPtr,
constraints.size(),
-1
);
}
else
{
initIslandPools();
//traverse the simulation islands, and call the solver, unless all objects are sleeping/deactivated
addBodiesToIslands( collisionWorld );
addManifoldsToIslands( dispatcher );
addConstraintsToIslands( constraints );
// m_activeIslands array should now contain all non-sleeping Islands, and each Island should
// have all the necessary bodies, manifolds and constraints.
// if we want to merge islands with small batch counts,
if ( m_minimumSolverBatchSize > 1 )
{
mergeIslands();
}
// dispatch islands to solver
m_islandDispatch( &m_activeIslands, callback );
}
}

View File

@@ -0,0 +1,109 @@
/*
Bullet Continuous Collision Detection and Physics Library
Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/
This software is provided 'as-is', without any express or implied warranty.
In no event will the authors be held liable for any damages arising from the use of this software.
Permission is granted to anyone to use this software for any purpose,
including commercial applications, and to alter it and redistribute it freely,
subject to the following restrictions:
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.
2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software.
3. This notice may not be removed or altered from any source distribution.
*/
#ifndef BT_SIMULATION_ISLAND_MANAGER_MT_H
#define BT_SIMULATION_ISLAND_MANAGER_MT_H
#include "btSimulationIslandManager.h"
class btTypedConstraint;
///
/// SimulationIslandManagerMt -- Multithread capable version of SimulationIslandManager
/// Splits the world up into islands which can be solved in parallel.
/// In order to solve islands in parallel, an IslandDispatch function
/// must be provided which will dispatch calls to multiple threads.
/// The amount of parallelism that can be achieved depends on the number
/// of islands. If only a single island exists, then no parallelism is
/// possible.
///
class btSimulationIslandManagerMt : public btSimulationIslandManager
{
public:
struct Island
{
// a simulation island consisting of bodies, manifolds and constraints,
// to be passed into a constraint solver.
btAlignedObjectArray<btCollisionObject*> bodyArray;
btAlignedObjectArray<btPersistentManifold*> manifoldArray;
btAlignedObjectArray<btTypedConstraint*> constraintArray;
int id; // island id
bool isSleeping;
void append( const Island& other ); // add bodies, manifolds, constraints to my own
};
struct IslandCallback
{
virtual ~IslandCallback() {};
virtual void processIsland( btCollisionObject** bodies,
int numBodies,
btPersistentManifold** manifolds,
int numManifolds,
btTypedConstraint** constraints,
int numConstraints,
int islandId
) = 0;
};
typedef void( *IslandDispatchFunc ) ( btAlignedObjectArray<Island*>* islands, IslandCallback* callback );
static void defaultIslandDispatch( btAlignedObjectArray<Island*>* islands, IslandCallback* callback );
protected:
btAlignedObjectArray<Island*> m_allocatedIslands; // owner of all Islands
btAlignedObjectArray<Island*> m_activeIslands; // islands actively in use
btAlignedObjectArray<Island*> m_freeIslands; // islands ready to be reused
btAlignedObjectArray<Island*> m_lookupIslandFromId; // big lookup table to map islandId to Island pointer
Island* m_batchIsland;
int m_minimumSolverBatchSize;
int m_batchIslandMinBodyCount;
IslandDispatchFunc m_islandDispatch;
Island* getIsland( int id );
virtual Island* allocateIsland( int id, int numBodies );
virtual void initIslandPools();
virtual void addBodiesToIslands( btCollisionWorld* collisionWorld );
virtual void addManifoldsToIslands( btDispatcher* dispatcher );
virtual void addConstraintsToIslands( btAlignedObjectArray<btTypedConstraint*>& constraints );
virtual void mergeIslands();
public:
btSimulationIslandManagerMt();
virtual ~btSimulationIslandManagerMt();
virtual void buildAndProcessIslands( btDispatcher* dispatcher, btCollisionWorld* collisionWorld, btAlignedObjectArray<btTypedConstraint*>& constraints, IslandCallback* callback );
virtual void buildIslands(btDispatcher* dispatcher,btCollisionWorld* colWorld);
int getMinimumSolverBatchSize() const
{
return m_minimumSolverBatchSize;
}
void setMinimumSolverBatchSize( int sz )
{
m_minimumSolverBatchSize = sz;
}
IslandDispatchFunc getIslandDispatchFunction() const
{
return m_islandDispatch;
}
// allow users to set their own dispatch function for multithreaded dispatch
void setIslandDispatchFunction( IslandDispatchFunc func )
{
m_islandDispatch = func;
}
};
#endif //BT_SIMULATION_ISLAND_MANAGER_H

View File

@@ -23,6 +23,59 @@ subject to the following restrictions:
#include "btGImpactMassUtil.h"
btGImpactMeshShapePart::btGImpactMeshShapePart( btStridingMeshInterface * meshInterface, int part )
{
// moved from .h to .cpp because of conditional compilation
// (The setting of BT_THREADSAFE may differ between various cpp files, so it is best to
// avoid using it in h files)
m_primitive_manager.m_meshInterface = meshInterface;
m_primitive_manager.m_part = part;
m_box_set.setPrimitiveManager( &m_primitive_manager );
#if BT_THREADSAFE
// If threadsafe is requested, this object uses a different lock/unlock
// model with the btStridingMeshInterface -- lock once when the object is constructed
// and unlock once in the destructor.
// The other way of locking and unlocking for each collision check in the narrowphase
// is not threadsafe. Note these are not thread-locks, they are calls to the meshInterface's
// getLockedReadOnlyVertexIndexBase virtual function, which by default just returns a couple of
// pointers. In theory a client could override the lock function to do all sorts of
// things like reading data from GPU memory, or decompressing data on the fly, but such things
// do not seem all that likely or useful, given the performance cost.
m_primitive_manager.lock();
#endif
}
btGImpactMeshShapePart::~btGImpactMeshShapePart()
{
// moved from .h to .cpp because of conditional compilation
#if BT_THREADSAFE
m_primitive_manager.unlock();
#endif
}
void btGImpactMeshShapePart::lockChildShapes() const
{
// moved from .h to .cpp because of conditional compilation
#if ! BT_THREADSAFE
// called in the narrowphase -- not threadsafe!
void * dummy = (void*) ( m_box_set.getPrimitiveManager() );
TrimeshPrimitiveManager * dummymanager = static_cast<TrimeshPrimitiveManager *>( dummy );
dummymanager->lock();
#endif
}
void btGImpactMeshShapePart::unlockChildShapes() const
{
// moved from .h to .cpp because of conditional compilation
#if ! BT_THREADSAFE
// called in the narrowphase -- not threadsafe!
void * dummy = (void*) ( m_box_set.getPrimitiveManager() );
TrimeshPrimitiveManager * dummymanager = static_cast<TrimeshPrimitiveManager *>( dummy );
dummymanager->unlock();
#endif
}
#define CALC_EXACT_INERTIA 1

View File

@@ -722,17 +722,8 @@ public:
m_box_set.setPrimitiveManager(&m_primitive_manager);
}
btGImpactMeshShapePart(btStridingMeshInterface * meshInterface, int part)
{
m_primitive_manager.m_meshInterface = meshInterface;
m_primitive_manager.m_part = part;
m_box_set.setPrimitiveManager(&m_primitive_manager);
}
virtual ~btGImpactMeshShapePart()
{
}
btGImpactMeshShapePart( btStridingMeshInterface * meshInterface, int part );
virtual ~btGImpactMeshShapePart();
//! if true, then its children must get transforms.
virtual bool childrenHasTransform() const
@@ -742,19 +733,8 @@ public:
//! call when reading child shapes
virtual void lockChildShapes() const
{
void * dummy = (void*)(m_box_set.getPrimitiveManager());
TrimeshPrimitiveManager * dummymanager = static_cast<TrimeshPrimitiveManager *>(dummy);
dummymanager->lock();
}
virtual void unlockChildShapes() const
{
void * dummy = (void*)(m_box_set.getPrimitiveManager());
TrimeshPrimitiveManager * dummymanager = static_cast<TrimeshPrimitiveManager *>(dummy);
dummymanager->unlock();
}
virtual void lockChildShapes() const;
virtual void unlockChildShapes() const;
//! Gets the number of children
virtual int getNumChildShapes() const