Merge remote-tracking branch 'upstream/master'

This commit is contained in:
yunfeibai
2016-11-03 10:26:52 -07:00
49 changed files with 4167 additions and 1191 deletions

View File

@@ -12,12 +12,14 @@ IF (WIN32)
ADD_EXECUTABLE(App_BasicExample
BasicExample.cpp
main.cpp
../CommonInterfaces/CommonRigidBodyBase.cpp
${BULLET_PHYSICS_SOURCE_DIR}/build3/bullet.rc
)
ELSE()
ADD_EXECUTABLE(App_BasicExample
BasicExample.cpp
main.cpp
../CommonInterfaces/CommonRigidBodyBase.cpp
)
ENDIF()
@@ -53,6 +55,7 @@ SET(AppBasicExampleGui_SRCS
../ExampleBrowser/OpenGLGuiHelper.cpp
../ExampleBrowser/GL_ShapeDrawer.cpp
../ExampleBrowser/CollisionShape2TriangleMesh.cpp
../CommonInterfaces/CommonRigidBodyBase.cpp
../Utils/b3Clock.cpp
)

View File

@@ -18,6 +18,7 @@ language "C++"
files {
"**.cpp",
"**.h",
"../CommonInterfaces/*",
}
@@ -49,6 +50,7 @@ files {
"../ExampleBrowser/OpenGLGuiHelper.cpp",
"../ExampleBrowser/GL_ShapeDrawer.cpp",
"../ExampleBrowser/CollisionShape2TriangleMesh.cpp",
"../CommonInterfaces/*",
"../Utils/b3Clock.cpp",
"../Utils/b3Clock.h",
}
@@ -90,6 +92,7 @@ files {
"../ExampleBrowser/OpenGLGuiHelper.cpp",
"../ExampleBrowser/GL_ShapeDrawer.cpp",
"../ExampleBrowser/CollisionShape2TriangleMesh.cpp",
"../CommonInterfaces/*",
"../TinyRenderer/geometry.cpp",
"../TinyRenderer/model.cpp",
"../TinyRenderer/tgaimage.cpp",
@@ -130,6 +133,7 @@ files {
"*.h",
"../StandaloneMain/main_tinyrenderer_single_example.cpp",
"../ExampleBrowser/CollisionShape2TriangleMesh.cpp",
"../CommonInterfaces/*",
"../OpenGLWindow/SimpleCamera.cpp",
"../TinyRenderer/geometry.cpp",
"../TinyRenderer/model.cpp",
@@ -175,6 +179,7 @@ files {
"BasicExample.cpp",
"*.h",
"../StandaloneMain/hellovr_opengl_main.cpp",
"../CommonInterfaces/*",
"../ExampleBrowser/OpenGLGuiHelper.cpp",
"../ExampleBrowser/GL_ShapeDrawer.cpp",
"../ExampleBrowser/CollisionShape2TriangleMesh.cpp",
@@ -200,4 +205,4 @@ if os.is("MacOSX") then
links{"Cocoa.framework"}
end
end
end

View File

@@ -32,10 +32,12 @@ subject to the following restrictions:
#include "LinearMath/btAlignedObjectArray.h"
#include "LinearMath/btTransform.h"
#include "../CommonInterfaces/ParallelFor.h"
class btDynamicsWorld;
#define NUMRAYS 500
#define USE_PARALLEL_RAYCASTS 1
class btRigidBody;
class btBroadphaseInterface;
@@ -204,7 +206,39 @@ public:
sign = -1.0;
}
void cast (btCollisionWorld* cw)
void castRays( btCollisionWorld* cw, int iBegin, int iEnd )
{
for ( int i = iBegin; i < iEnd; ++i )
{
btCollisionWorld::ClosestRayResultCallback cb(source[i], dest[i]);
cw->rayTest (source[i], dest[i], cb);
if (cb.hasHit ())
{
hit[i] = cb.m_hitPointWorld;
normal[i] = cb.m_hitNormalWorld;
normal[i].normalize ();
} else {
hit[i] = dest[i];
normal[i] = btVector3(1.0, 0.0, 0.0);
}
}
}
struct CastRaysLoopBody
{
btRaycastBar2* mRaycasts;
btCollisionWorld* mWorld;
CastRaysLoopBody(btCollisionWorld* cw, btRaycastBar2* rb) : mWorld(cw), mRaycasts(rb) {}
void forLoop( int iBegin, int iEnd ) const
{
mRaycasts->castRays(mWorld, iBegin, iEnd);
}
};
void cast (btCollisionWorld* cw, bool multiThreading = false)
{
#ifdef USE_BT_CLOCK
frame_timer.reset ();
@@ -228,22 +262,19 @@ public:
normal[i].normalize ();
}
#else
for (int i = 0; i < NUMRAYS; i++)
{
btCollisionWorld::ClosestRayResultCallback cb(source[i], dest[i]);
cw->rayTest (source[i], dest[i], cb);
if (cb.hasHit ())
{
hit[i] = cb.m_hitPointWorld;
normal[i] = cb.m_hitNormalWorld;
normal[i].normalize ();
} else {
hit[i] = dest[i];
normal[i] = btVector3(1.0, 0.0, 0.0);
}
}
#if USE_PARALLEL_RAYCASTS
if ( multiThreading )
{
CastRaysLoopBody rayLooper(cw, this);
int grainSize = 20; // number of raycasts per task
parallelFor( 0, NUMRAYS, grainSize, rayLooper );
}
else
#endif // USE_PARALLEL_RAYCASTS
{
// single threaded
castRays(cw, 0, NUMRAYS);
}
#ifdef USE_BT_CLOCK
ms += frame_timer.getTimeMilliseconds ();
#endif //USE_BT_CLOCK
@@ -354,42 +385,43 @@ void BenchmarkDemo::initPhysics()
setCameraDistance(btScalar(100.));
///collision configuration contains default setup for memory, collision setup
btDefaultCollisionConstructionInfo cci;
cci.m_defaultMaxPersistentManifoldPoolSize = 32768;
m_collisionConfiguration = new btDefaultCollisionConfiguration(cci);
createEmptyDynamicsWorld();
/////collision configuration contains default setup for memory, collision setup
//btDefaultCollisionConstructionInfo cci;
//cci.m_defaultMaxPersistentManifoldPoolSize = 32768;
//m_collisionConfiguration = new btDefaultCollisionConfiguration(cci);
///use the default collision dispatcher. For parallel processing you can use a diffent dispatcher (see Extras/BulletMultiThreaded)
m_dispatcher = new btCollisionDispatcher(m_collisionConfiguration);
m_dispatcher->setDispatcherFlags(btCollisionDispatcher::CD_DISABLE_CONTACTPOOL_DYNAMIC_ALLOCATION);
/////use the default collision dispatcher. For parallel processing you can use a diffent dispatcher (see Extras/BulletMultiThreaded)
//m_dispatcher = new btCollisionDispatcher(m_collisionConfiguration);
//
//m_dispatcher->setDispatcherFlags(btCollisionDispatcher::CD_DISABLE_CONTACTPOOL_DYNAMIC_ALLOCATION);
///the maximum size of the collision world. Make sure objects stay within these boundaries
///Don't make the world AABB size too large, it will harm simulation quality and performance
btVector3 worldAabbMin(-1000,-1000,-1000);
btVector3 worldAabbMax(1000,1000,1000);
btHashedOverlappingPairCache* pairCache = new btHashedOverlappingPairCache();
m_broadphase = new btAxisSweep3(worldAabbMin,worldAabbMax,3500,pairCache);
/////the maximum size of the collision world. Make sure objects stay within these boundaries
/////Don't make the world AABB size too large, it will harm simulation quality and performance
//btVector3 worldAabbMin(-1000,-1000,-1000);
//btVector3 worldAabbMax(1000,1000,1000);
//
//btHashedOverlappingPairCache* pairCache = new btHashedOverlappingPairCache();
//m_broadphase = new btAxisSweep3(worldAabbMin,worldAabbMax,3500,pairCache);
// m_broadphase = new btSimpleBroadphase();
// m_broadphase = new btDbvtBroadphase();
///the default constraint solver. For parallel processing you can use a different solver (see Extras/BulletMultiThreaded)
btSequentialImpulseConstraintSolver* sol = new btSequentialImpulseConstraintSolver;
//btSequentialImpulseConstraintSolver* sol = new btSequentialImpulseConstraintSolver;
m_solver = sol;
//m_solver = sol;
btDiscreteDynamicsWorld* dynamicsWorld;
m_dynamicsWorld = dynamicsWorld = new btDiscreteDynamicsWorld(m_dispatcher,m_broadphase,m_solver,m_collisionConfiguration);
//btDiscreteDynamicsWorld* dynamicsWorld;
//m_dynamicsWorld = dynamicsWorld = new btDiscreteDynamicsWorld(m_dispatcher,m_broadphase,m_solver,m_collisionConfiguration);
///the following 3 lines increase the performance dramatically, with a little bit of loss of quality
m_dynamicsWorld->getSolverInfo().m_solverMode |=SOLVER_ENABLE_FRICTION_DIRECTION_CACHING; //don't recalculate friction values each frame
dynamicsWorld->getSolverInfo().m_numIterations = 5; //few solver iterations
m_dynamicsWorld->getSolverInfo().m_numIterations = 5; //few solver iterations
//m_defaultContactProcessingThreshold = 0.f;//used when creating bodies: body->setContactProcessingThreshold(...);
m_guiHelper->createPhysicsDebugDrawer(m_dynamicsWorld);
@@ -1242,7 +1274,7 @@ void BenchmarkDemo::initRays()
void BenchmarkDemo::castRays()
{
raycastBar.cast (m_dynamicsWorld);
raycastBar.cast (m_dynamicsWorld, m_multithreadedWorld);
}
void BenchmarkDemo::createTest7()

View File

@@ -120,7 +120,7 @@ struct CommonGraphicsApp
virtual int getUpAxis() const = 0;
virtual void swapBuffer() = 0;
virtual void drawText( const char* txt, int posX, int posY) = 0;
virtual void drawText( const char* txt, int posX, int posY, float size = 1.0f) = 0;
virtual void drawText3D( const char* txt, float posX, float posZY, float posZ, float size)=0;
virtual void drawTexturedRect(float x0, float y0, float x1, float y1, float color[4], float u0,float v0, float u1, float v1, int useRGBA)=0;
virtual int registerCubeShape(float halfExtentsX,float halfExtentsY, float halfExtentsZ, int textureIndex = -1, float textureScaling = 1)=0;

View File

@@ -0,0 +1,855 @@
/*
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 "btBulletDynamicsCommon.h"
#include "LinearMath/btIDebugDraw.h"
#include <stdio.h>
#include <algorithm>
class btCollisionShape;
#include "CommonExampleInterface.h"
#include "CommonRigidBodyBase.h"
#include "CommonParameterInterface.h"
#include "CommonGUIHelperInterface.h"
#include "CommonRenderInterface.h"
#include "CommonWindowInterface.h"
#include "CommonGraphicsAppInterface.h"
#include "ParallelFor.h"
#include "LinearMath/btAlignedObjectArray.h"
#include "LinearMath/btPoolAllocator.h"
#include "btBulletCollisionCommon.h"
#include "BulletCollision/CollisionDispatch/btSimulationIslandManagerMt.h" // for setSplitIslands()
#include "BulletDynamics/Dynamics/btDiscreteDynamicsWorldMt.h"
#include "BulletDynamics/ConstraintSolver/btSequentialImpulseConstraintSolver.h"
TaskManager gTaskMgr;
#define USE_PARALLEL_NARROWPHASE 1 // detect collisions in parallel
#define USE_PARALLEL_ISLAND_SOLVER 1 // solve simulation islands in parallel
#define USE_PARALLEL_CREATE_PREDICTIVE_CONTACTS 1
#define USE_PARALLEL_INTEGRATE_TRANSFORMS 1
#define USE_PARALLEL_PREDICT_UNCONSTRAINED_MOTION 1
#if defined (_MSC_VER) && _MSC_VER >= 1600
// give us a compile error if any signatures of overriden methods is changed
#define BT_OVERRIDE override
#else
#define BT_OVERRIDE
#endif
class Profiler
{
public:
enum RecordType
{
kRecordInternalTimeStep,
kRecordDispatchAllCollisionPairs,
kRecordDispatchIslands,
kRecordPredictUnconstrainedMotion,
kRecordCreatePredictiveContacts,
kRecordIntegrateTransforms,
kRecordCount
};
private:
btClock mClock;
struct Record
{
int mCallCount;
unsigned long long mAccum;
unsigned int mStartTime;
unsigned int mHistory[8];
void begin(unsigned int curTime)
{
mStartTime = curTime;
}
void end(unsigned int curTime)
{
unsigned int endTime = curTime;
unsigned int elapsed = endTime - mStartTime;
mAccum += elapsed;
mHistory[ mCallCount & 7 ] = elapsed;
++mCallCount;
}
float getAverageTime() const
{
int count = btMin( 8, mCallCount );
if ( count > 0 )
{
unsigned int sum = 0;
for ( int i = 0; i < count; ++i )
{
sum += mHistory[ i ];
}
float avg = float( sum ) / float( count );
return avg;
}
return 0.0;
}
};
Record mRecords[ kRecordCount ];
public:
void begin(RecordType rt)
{
mRecords[rt].begin(mClock.getTimeMicroseconds());
}
void end(RecordType rt)
{
mRecords[rt].end(mClock.getTimeMicroseconds());
}
float getAverageTime(RecordType rt) const
{
return mRecords[rt].getAverageTime();
}
};
Profiler gProfiler;
class ProfileHelper
{
Profiler::RecordType mRecType;
public:
ProfileHelper(Profiler::RecordType rt)
{
mRecType = rt;
gProfiler.begin( mRecType );
}
~ProfileHelper()
{
gProfiler.end( mRecType );
}
};
int gThreadsRunningCounter = 0;
btSpinMutex gThreadsRunningCounterMutex;
void btPushThreadsAreRunning()
{
gThreadsRunningCounterMutex.lock();
gThreadsRunningCounter++;
gThreadsRunningCounterMutex.unlock();
}
void btPopThreadsAreRunning()
{
gThreadsRunningCounterMutex.lock();
gThreadsRunningCounter--;
gThreadsRunningCounterMutex.unlock();
}
bool btThreadsAreRunning()
{
return gThreadsRunningCounter != 0;
}
#if USE_PARALLEL_NARROWPHASE
class MyCollisionDispatcher : public btCollisionDispatcher
{
btSpinMutex m_manifoldPtrsMutex;
public:
MyCollisionDispatcher( btCollisionConfiguration* config ) : btCollisionDispatcher( config )
{
}
virtual ~MyCollisionDispatcher()
{
}
btPersistentManifold* getNewManifold( const btCollisionObject* body0, const btCollisionObject* body1 ) BT_OVERRIDE
{
// added spin-locks
//optional relative contact breaking threshold, turned on by default (use setDispatcherFlags to switch off feature for improved performance)
btScalar contactBreakingThreshold = ( m_dispatcherFlags & btCollisionDispatcher::CD_USE_RELATIVE_CONTACT_BREAKING_THRESHOLD ) ?
btMin( body0->getCollisionShape()->getContactBreakingThreshold( gContactBreakingThreshold ), body1->getCollisionShape()->getContactBreakingThreshold( gContactBreakingThreshold ) )
: gContactBreakingThreshold;
btScalar contactProcessingThreshold = btMin( body0->getContactProcessingThreshold(), body1->getContactProcessingThreshold() );
void* mem = m_persistentManifoldPoolAllocator->allocate( sizeof( btPersistentManifold ) );
if (NULL == mem)
{
//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 );
}
else
{
btAssert( 0 );
//make sure to increase the m_defaultMaxPersistentManifoldPoolSize in the btDefaultCollisionConstructionInfo/btDefaultCollisionConfiguration
return 0;
}
}
btPersistentManifold* manifold = new(mem) btPersistentManifold( body0, body1, 0, contactBreakingThreshold, contactProcessingThreshold );
m_manifoldPtrsMutex.lock();
manifold->m_index1a = m_manifoldsPtr.size();
m_manifoldsPtr.push_back( manifold );
m_manifoldPtrsMutex.unlock();
return manifold;
}
void releaseManifold( btPersistentManifold* manifold ) BT_OVERRIDE
{
clearManifold( manifold );
m_manifoldPtrsMutex.lock();
int findIndex = manifold->m_index1a;
btAssert( findIndex < m_manifoldsPtr.size() );
m_manifoldsPtr.swap( findIndex, m_manifoldsPtr.size() - 1 );
m_manifoldsPtr[ findIndex ]->m_index1a = findIndex;
m_manifoldsPtr.pop_back();
m_manifoldPtrsMutex.unlock();
manifold->~btPersistentManifold();
if ( m_persistentManifoldPoolAllocator->validPtr( manifold ) )
{
m_persistentManifoldPoolAllocator->freeMemory( manifold );
}
else
{
btAlignedFree( manifold );
}
}
struct Updater
{
btBroadphasePair* mPairArray;
btNearCallback mCallback;
btCollisionDispatcher* mDispatcher;
const btDispatcherInfo* mInfo;
Updater()
{
mPairArray = NULL;
mCallback = NULL;
mDispatcher = NULL;
mInfo = NULL;
}
void forLoop( int iBegin, int iEnd ) const
{
for ( int i = iBegin; i < iEnd; ++i )
{
btBroadphasePair* pair = &mPairArray[ i ];
mCallback( *pair, *mDispatcher, *mInfo );
}
}
};
virtual void dispatchAllCollisionPairs( btOverlappingPairCache* pairCache, const btDispatcherInfo& info, btDispatcher* dispatcher ) BT_OVERRIDE
{
ProfileHelper prof(Profiler::kRecordDispatchAllCollisionPairs);
int grainSize = 40; // iterations per task
int pairCount = pairCache->getNumOverlappingPairs();
Updater updater;
updater.mCallback = getNearCallback();
updater.mPairArray = pairCount > 0 ? pairCache->getOverlappingPairArrayPtr() : NULL;
updater.mDispatcher = this;
updater.mInfo = &info;
btPushThreadsAreRunning();
parallelFor( 0, pairCount, grainSize, updater );
btPopThreadsAreRunning();
if (m_manifoldsPtr.size() < 1)
return;
// reconstruct the manifolds array to ensure determinism
m_manifoldsPtr.resizeNoInitialize(0);
btBroadphasePair* pairs = pairCache->getOverlappingPairArrayPtr();
for (int i = 0; i < pairCount; ++i)
{
btCollisionAlgorithm* algo = pairs[i].m_algorithm;
if (algo) algo->getAllContactManifolds(m_manifoldsPtr);
}
// update the indices (used when releasing manifolds)
for (int i = 0; i < m_manifoldsPtr.size(); ++i)
m_manifoldsPtr[i]->m_index1a = i;
}
};
#endif
#if USE_PARALLEL_ISLAND_SOLVER
///
/// MyConstraintSolverPool - masquerades as a constraint solver, but really it is a threadsafe pool of them.
///
/// Each solver in the pool is protected by a mutex. When solveGroup is called from a thread,
/// the pool looks for a solver that isn't being used by another thread, locks it, and dispatches the
/// call to the solver.
/// So long as there are at least as many solvers as there are hardware threads, it should never need to
/// spin wait.
///
class MyConstraintSolverPool : public btConstraintSolver
{
const static size_t kCacheLineSize = 128;
struct ThreadSolver
{
btConstraintSolver* solver;
btSpinMutex mutex;
char _cachelinePadding[ kCacheLineSize - sizeof( btSpinMutex ) - sizeof( void* ) ]; // keep mutexes from sharing a cache line
};
btAlignedObjectArray<ThreadSolver> m_solvers;
btConstraintSolverType m_solverType;
ThreadSolver* getAndLockThreadSolver()
{
while ( true )
{
for ( int i = 0; i < m_solvers.size(); ++i )
{
ThreadSolver& solver = m_solvers[ i ];
if ( solver.mutex.tryLock() )
{
return &solver;
}
}
}
return NULL;
}
void init( btConstraintSolver** solvers, int numSolvers )
{
m_solverType = BT_SEQUENTIAL_IMPULSE_SOLVER;
m_solvers.resize( numSolvers );
for ( int i = 0; i < numSolvers; ++i )
{
m_solvers[ i ].solver = solvers[ i ];
}
if ( numSolvers > 0 )
{
m_solverType = solvers[ 0 ]->getSolverType();
}
}
public:
// create the solvers for me
explicit MyConstraintSolverPool( int numSolvers )
{
btAlignedObjectArray<btConstraintSolver*> solvers;
solvers.reserve( numSolvers );
for ( int i = 0; i < numSolvers; ++i )
{
btConstraintSolver* solver = new btSequentialImpulseConstraintSolver();
solvers.push_back( solver );
}
init( &solvers[ 0 ], numSolvers );
}
// pass in fully constructed solvers (destructor will delete them)
MyConstraintSolverPool( btConstraintSolver** solvers, int numSolvers )
{
init( solvers, numSolvers );
}
virtual ~MyConstraintSolverPool()
{
// delete all solvers
for ( int i = 0; i < m_solvers.size(); ++i )
{
ThreadSolver& solver = m_solvers[ i ];
delete solver.solver;
solver.solver = NULL;
}
}
//virtual void prepareSolve( int /* numBodies */, int /* numManifolds */ ) { ; } // does nothing
///solve a group of constraints
virtual btScalar solveGroup( btCollisionObject** bodies,
int numBodies,
btPersistentManifold** manifolds,
int numManifolds,
btTypedConstraint** constraints,
int numConstraints,
const btContactSolverInfo& info,
btIDebugDraw* debugDrawer,
btDispatcher* dispatcher
)
{
ThreadSolver* solver = getAndLockThreadSolver();
solver->solver->solveGroup( bodies, numBodies, manifolds, numManifolds, constraints, numConstraints, info, debugDrawer, dispatcher );
solver->mutex.unlock();
return 0.0f;
}
//virtual void allSolved( const btContactSolverInfo& /* info */, class btIDebugDraw* /* debugDrawer */ ) { ; } // does nothing
///clear internal cached data and reset random seed
virtual void reset()
{
for ( int i = 0; i < m_solvers.size(); ++i )
{
ThreadSolver& solver = m_solvers[ i ];
solver.mutex.lock();
solver.solver->reset();
solver.mutex.unlock();
}
}
virtual btConstraintSolverType getSolverType() const
{
return m_solverType;
}
};
struct UpdateIslandDispatcher
{
btAlignedObjectArray<btSimulationIslandManagerMt::Island*>* islandsPtr;
btSimulationIslandManagerMt::IslandCallback* callback;
void forLoop( int iBegin, int iEnd ) const
{
for ( int i = iBegin; i < iEnd; ++i )
{
btSimulationIslandManagerMt::Island* island = ( *islandsPtr )[ 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
);
}
}
};
static int gNumIslands = 0;
void parallelIslandDispatch( btAlignedObjectArray<btSimulationIslandManagerMt::Island*>* islandsPtr, btSimulationIslandManagerMt::IslandCallback* callback )
{
ProfileHelper prof(Profiler::kRecordDispatchIslands);
gNumIslands = islandsPtr->size();
int grainSize = 1; // iterations per task
UpdateIslandDispatcher dispatcher;
dispatcher.islandsPtr = islandsPtr;
dispatcher.callback = callback;
btPushThreadsAreRunning();
parallelFor( 0, islandsPtr->size(), grainSize, dispatcher );
btPopThreadsAreRunning();
}
#endif //#if USE_PARALLEL_ISLAND_SOLVER
void profileBeginCallback(btDynamicsWorld *world, btScalar timeStep)
{
gProfiler.begin(Profiler::kRecordInternalTimeStep);
}
void profileEndCallback(btDynamicsWorld *world, btScalar timeStep)
{
gProfiler.end(Profiler::kRecordInternalTimeStep);
}
///
/// MyDiscreteDynamicsWorld
///
/// Should function exactly like btDiscreteDynamicsWorld.
/// 3 methods that iterate over all of the rigidbodies can run in parallel:
/// - predictUnconstraintMotion
/// - integrateTransforms
/// - createPredictiveContacts
///
ATTRIBUTE_ALIGNED16( class ) MyDiscreteDynamicsWorld : public btDiscreteDynamicsWorldMt
{
typedef btDiscreteDynamicsWorld ParentClass;
protected:
#if USE_PARALLEL_PREDICT_UNCONSTRAINED_MOTION
struct UpdaterUnconstrainedMotion
{
btScalar timeStep;
btRigidBody** rigidBodies;
void forLoop( int iBegin, int iEnd ) const
{
for ( int i = iBegin; i < iEnd; ++i )
{
btRigidBody* body = rigidBodies[ i ];
if ( !body->isStaticOrKinematicObject() )
{
//don't integrate/update velocities here, it happens in the constraint solver
body->applyDamping( timeStep );
body->predictIntegratedTransform( timeStep, body->getInterpolationWorldTransform() );
}
}
}
};
virtual void predictUnconstraintMotion( btScalar timeStep ) BT_OVERRIDE
{
ProfileHelper prof( Profiler::kRecordPredictUnconstrainedMotion );
BT_PROFILE( "predictUnconstraintMotion" );
int grainSize = 50; // num of iterations per task for TBB
int bodyCount = m_nonStaticRigidBodies.size();
UpdaterUnconstrainedMotion update;
update.timeStep = timeStep;
update.rigidBodies = bodyCount ? &m_nonStaticRigidBodies[ 0 ] : NULL;
btPushThreadsAreRunning();
parallelFor( 0, bodyCount, grainSize, update );
btPopThreadsAreRunning();
}
#endif // #if USE_PARALLEL_PREDICT_UNCONSTRAINED_MOTION
#if USE_PARALLEL_CREATE_PREDICTIVE_CONTACTS
struct UpdaterCreatePredictiveContacts
{
btScalar timeStep;
btRigidBody** rigidBodies;
MyDiscreteDynamicsWorld* world;
void forLoop( int iBegin, int iEnd ) const
{
world->createPredictiveContactsInternal( &rigidBodies[ iBegin ], iEnd - iBegin, timeStep );
}
};
virtual void createPredictiveContacts( btScalar timeStep )
{
ProfileHelper prof( Profiler::kRecordCreatePredictiveContacts );
releasePredictiveContacts();
int grainSize = 50; // num of iterations per task for TBB or OPENMP
if ( int bodyCount = m_nonStaticRigidBodies.size() )
{
UpdaterCreatePredictiveContacts update;
update.world = this;
update.timeStep = timeStep;
update.rigidBodies = &m_nonStaticRigidBodies[ 0 ];
btPushThreadsAreRunning();
parallelFor( 0, bodyCount, grainSize, update );
btPopThreadsAreRunning();
}
}
#endif // #if USE_PARALLEL_CREATE_PREDICTIVE_CONTACTS
#if USE_PARALLEL_INTEGRATE_TRANSFORMS
struct UpdaterIntegrateTransforms
{
btScalar timeStep;
btRigidBody** rigidBodies;
MyDiscreteDynamicsWorld* world;
void forLoop( int iBegin, int iEnd ) const
{
world->integrateTransformsInternal( &rigidBodies[ iBegin ], iEnd - iBegin, timeStep );
}
};
virtual void integrateTransforms( btScalar timeStep ) BT_OVERRIDE
{
ProfileHelper prof( Profiler::kRecordIntegrateTransforms );
BT_PROFILE( "integrateTransforms" );
int grainSize = 50; // num of iterations per task for TBB or OPENMP
if ( int bodyCount = m_nonStaticRigidBodies.size() )
{
UpdaterIntegrateTransforms update;
update.world = this;
update.timeStep = timeStep;
update.rigidBodies = &m_nonStaticRigidBodies[ 0 ];
btPushThreadsAreRunning();
parallelFor( 0, bodyCount, grainSize, update );
btPopThreadsAreRunning();
}
}
#endif // #if USE_PARALLEL_INTEGRATE_TRANSFORMS
public:
BT_DECLARE_ALIGNED_ALLOCATOR();
MyDiscreteDynamicsWorld( btDispatcher* dispatcher,
btBroadphaseInterface* pairCache,
btConstraintSolver* constraintSolver,
btCollisionConfiguration* collisionConfiguration
) :
btDiscreteDynamicsWorldMt( dispatcher, pairCache, constraintSolver, collisionConfiguration )
{
}
};
static bool gMultithreadedWorld = false;
static bool gDisplayProfileInfo = false;
static btScalar gSliderNumThreads = 1.0f; // should be int
////////////////////////////////////
CommonRigidBodyBase::CommonRigidBodyBase( struct GUIHelperInterface* helper )
:m_broadphase( 0 ),
m_dispatcher( 0 ),
m_solver( 0 ),
m_collisionConfiguration( 0 ),
m_dynamicsWorld( 0 ),
m_pickedBody( 0 ),
m_pickedConstraint( 0 ),
m_guiHelper( helper )
{
m_multithreadedWorld = false;
m_multithreadCapable = false;
gTaskMgr.init();
}
CommonRigidBodyBase::~CommonRigidBodyBase()
{
gTaskMgr.shutdown();
}
void boolPtrButtonCallback(int buttonId, bool buttonState, void* userPointer)
{
if (bool* val = static_cast<bool*>(userPointer))
{
*val = ! *val;
}
}
void apiSelectButtonCallback(int buttonId, bool buttonState, void* userPointer)
{
gTaskMgr.setApi(static_cast<TaskManager::Api>(buttonId));
if (gTaskMgr.getApi()==TaskManager::apiNone)
{
gSliderNumThreads = 1.0f;
}
else
{
gSliderNumThreads = float(gTaskMgr.getNumThreads());
}
}
void setThreadCountCallback(float val)
{
if (gTaskMgr.getApi()==TaskManager::apiNone)
{
gSliderNumThreads = 1.0f;
}
else
{
gTaskMgr.setNumThreads( int( gSliderNumThreads ) );
gSliderNumThreads = float(gTaskMgr.getNumThreads());
}
}
void CommonRigidBodyBase::createEmptyDynamicsWorld()
{
gNumIslands = 0;
#if BT_THREADSAFE && (BT_USE_OPENMP || BT_USE_PPL || BT_USE_TBB)
m_multithreadCapable = true;
#endif
if ( gMultithreadedWorld )
{
m_dispatcher = NULL;
btDefaultCollisionConstructionInfo cci;
cci.m_defaultMaxPersistentManifoldPoolSize = 80000;
cci.m_defaultMaxCollisionAlgorithmPoolSize = 80000;
m_collisionConfiguration = new btDefaultCollisionConfiguration( cci );
#if USE_PARALLEL_NARROWPHASE
m_dispatcher = new MyCollisionDispatcher( m_collisionConfiguration );
#else
m_dispatcher = new btCollisionDispatcher( m_collisionConfiguration );
#endif //USE_PARALLEL_NARROWPHASE
m_broadphase = new btDbvtBroadphase();
#if USE_PARALLEL_ISLAND_SOLVER
m_solver = new MyConstraintSolverPool( TaskManager::getMaxNumThreads() );
#else
m_solver = new btSequentialImpulseConstraintSolver();
#endif //#if USE_PARALLEL_ISLAND_SOLVER
btDiscreteDynamicsWorld* world = new MyDiscreteDynamicsWorld( m_dispatcher, m_broadphase, m_solver, m_collisionConfiguration );
m_dynamicsWorld = world;
#if USE_PARALLEL_ISLAND_SOLVER
if ( btSimulationIslandManagerMt* islandMgr = dynamic_cast<btSimulationIslandManagerMt*>( world->getSimulationIslandManager() ) )
{
islandMgr->setIslandDispatchFunction( parallelIslandDispatch );
m_multithreadedWorld = true;
}
#endif //#if USE_PARALLEL_ISLAND_SOLVER
}
else
{
// single threaded world
m_multithreadedWorld = false;
///collision configuration contains default setup for memory, collision setup
m_collisionConfiguration = new btDefaultCollisionConfiguration();
//m_collisionConfiguration->setConvexConvexMultipointIterations();
///use the default collision dispatcher. For parallel processing you can use a diffent dispatcher (see Extras/BulletMultiThreaded)
m_dispatcher = new btCollisionDispatcher( m_collisionConfiguration );
m_broadphase = new btDbvtBroadphase();
///the default constraint solver. For parallel processing you can use a different solver (see Extras/BulletMultiThreaded)
btSequentialImpulseConstraintSolver* sol = new btSequentialImpulseConstraintSolver;
m_solver = sol;
m_dynamicsWorld = new btDiscreteDynamicsWorld( m_dispatcher, m_broadphase, m_solver, m_collisionConfiguration );
}
m_dynamicsWorld->setInternalTickCallback( profileBeginCallback, NULL, true );
m_dynamicsWorld->setInternalTickCallback( profileEndCallback, NULL, false );
m_dynamicsWorld->setGravity( btVector3( 0, -10, 0 ) );
createDefaultParameters();
}
void CommonRigidBodyBase::createDefaultParameters()
{
if (m_multithreadCapable)
{
// create a button to toggle multithreaded world
ButtonParams button( "Multithreaded world enable", 0, true );
button.m_userPointer = &gMultithreadedWorld;
button.m_callback = boolPtrButtonCallback;
m_guiHelper->getParameterInterface()->registerButtonParameter( button );
}
{
// create a button to toggle profile printing
ButtonParams button( "Display profile timings", 0, true );
button.m_userPointer = &gDisplayProfileInfo;
button.m_callback = boolPtrButtonCallback;
m_guiHelper->getParameterInterface()->registerButtonParameter( button );
}
if (m_multithreadedWorld)
{
// create a button for each supported threading API
for (int iApi = 0; iApi < TaskManager::apiCount; ++iApi)
{
TaskManager::Api api = static_cast<TaskManager::Api>(iApi);
if (gTaskMgr.isSupported(api))
{
char str[1024];
sprintf(str, "API %s", gTaskMgr.getApiName(api));
ButtonParams button( str, iApi, false );
button.m_callback = apiSelectButtonCallback;
m_guiHelper->getParameterInterface()->registerButtonParameter( button );
}
}
{
// create a slider to set the number of threads to use
gSliderNumThreads = float(gTaskMgr.getNumThreads());
SliderParams slider("Thread count", &gSliderNumThreads);
slider.m_minVal = 1.0f;
slider.m_maxVal = float(gTaskMgr.getMaxNumThreads()*2);
slider.m_callback = setThreadCountCallback;
slider.m_clampToNotches = false;
m_guiHelper->getParameterInterface()->registerSliderFloatParameter( slider );
}
}
}
void CommonRigidBodyBase::physicsDebugDraw(int debugFlags)
{
if (m_dynamicsWorld && m_dynamicsWorld->getDebugDrawer())
{
m_dynamicsWorld->getDebugDrawer()->setDebugMode(debugFlags);
m_dynamicsWorld->debugDrawWorld();
}
char msg[ 1024 ];
int xCoord = 400;
int yCoord = 30;
int yStep = 30;
if (m_multithreadCapable)
{
if ( m_multithreadedWorld != gMultithreadedWorld )
{
sprintf( msg, "restart example to begin in %s mode",
gMultithreadedWorld ? "multithreaded" : "single threaded"
);
m_guiHelper->getAppInterface()->drawText( msg, 300, yCoord, 0.4f );
yCoord += yStep;
}
}
if (gDisplayProfileInfo)
{
if ( m_multithreadedWorld )
{
int numManifolds = m_dispatcher->getNumManifolds();
int numContacts = 0;
for ( int i = 0; i < numManifolds; ++i )
{
const btPersistentManifold* man = m_dispatcher->getManifoldByIndexInternal( i );
numContacts += man->getNumContacts();
}
const char* mtApi = TaskManager::getApiName( gTaskMgr.getApi() );
sprintf( msg, "islands=%d bodies=%d manifolds=%d contacts=%d [%s] threads=%d",
gNumIslands,
m_dynamicsWorld->getNumCollisionObjects(),
numManifolds,
numContacts,
mtApi,
gTaskMgr.getApi() == TaskManager::apiNone ? 1 : gTaskMgr.getNumThreads()
);
m_guiHelper->getAppInterface()->drawText( msg, 100, yCoord, 0.4f );
yCoord += yStep;
}
sprintf( msg, "internalSimStep %5.3f ms",
gProfiler.getAverageTime( Profiler::kRecordInternalTimeStep )*0.001f
);
m_guiHelper->getAppInterface()->drawText( msg, xCoord, yCoord, 0.4f );
yCoord += yStep;
if ( m_multithreadedWorld )
{
sprintf( msg,
"DispatchCollisionPairs %5.3f ms",
gProfiler.getAverageTime( Profiler::kRecordDispatchAllCollisionPairs )*0.001f
);
m_guiHelper->getAppInterface()->drawText( msg, xCoord, yCoord, 0.4f );
yCoord += yStep;
sprintf( msg,
"SolveAllIslands %5.3f ms",
gProfiler.getAverageTime( Profiler::kRecordDispatchIslands )*0.001f
);
m_guiHelper->getAppInterface()->drawText( msg, xCoord, yCoord, 0.4f );
yCoord += yStep;
sprintf( msg,
"PredictUnconstrainedMotion %5.3f ms",
gProfiler.getAverageTime( Profiler::kRecordPredictUnconstrainedMotion )*0.001f
);
m_guiHelper->getAppInterface()->drawText( msg, xCoord, yCoord, 0.4f );
yCoord += yStep;
sprintf( msg,
"CreatePredictiveContacts %5.3f ms",
gProfiler.getAverageTime( Profiler::kRecordCreatePredictiveContacts )*0.001f
);
m_guiHelper->getAppInterface()->drawText( msg, xCoord, yCoord, 0.4f );
yCoord += yStep;
sprintf( msg,
"IntegrateTransforms %5.3f ms",
gProfiler.getAverageTime( Profiler::kRecordIntegrateTransforms )*0.001f
);
m_guiHelper->getAppInterface()->drawText( msg, xCoord, yCoord, 0.4f );
yCoord += yStep;
}
}
}

View File

@@ -21,6 +21,8 @@ struct CommonRigidBodyBase : public CommonExampleInterface
btConstraintSolver* m_solver;
btDefaultCollisionConfiguration* m_collisionConfiguration;
btDiscreteDynamicsWorld* m_dynamicsWorld;
bool m_multithreadedWorld;
bool m_multithreadCapable;
//data for picking objects
class btRigidBody* m_pickedBody;
@@ -31,20 +33,8 @@ struct CommonRigidBodyBase : public CommonExampleInterface
btScalar m_oldPickingDist;
struct GUIHelperInterface* m_guiHelper;
CommonRigidBodyBase(struct GUIHelperInterface* helper)
:m_broadphase(0),
m_dispatcher(0),
m_solver(0),
m_collisionConfiguration(0),
m_dynamicsWorld(0),
m_pickedBody(0),
m_pickedConstraint(0),
m_guiHelper(helper)
{
}
virtual ~CommonRigidBodyBase()
{
}
CommonRigidBodyBase(struct GUIHelperInterface* helper);
virtual ~CommonRigidBodyBase();
btDiscreteDynamicsWorld* getDynamicsWorld()
@@ -52,26 +42,8 @@ struct CommonRigidBodyBase : public CommonExampleInterface
return m_dynamicsWorld;
}
virtual void createEmptyDynamicsWorld()
{
///collision configuration contains default setup for memory, collision setup
m_collisionConfiguration = new btDefaultCollisionConfiguration();
//m_collisionConfiguration->setConvexConvexMultipointIterations();
///use the default collision dispatcher. For parallel processing you can use a diffent dispatcher (see Extras/BulletMultiThreaded)
m_dispatcher = new btCollisionDispatcher(m_collisionConfiguration);
m_broadphase = new btDbvtBroadphase();
///the default constraint solver. For parallel processing you can use a different solver (see Extras/BulletMultiThreaded)
btSequentialImpulseConstraintSolver* sol = new btSequentialImpulseConstraintSolver;
m_solver = sol;
m_dynamicsWorld = new btDiscreteDynamicsWorld(m_dispatcher, m_broadphase, m_solver, m_collisionConfiguration);
m_dynamicsWorld->setGravity(btVector3(0, -10, 0));
}
virtual void createDefaultParameters();
virtual void createEmptyDynamicsWorld();
virtual void stepSimulation(float deltaTime)
{
@@ -81,14 +53,7 @@ struct CommonRigidBodyBase : public CommonExampleInterface
}
}
virtual void physicsDebugDraw(int debugFlags)
{
if (m_dynamicsWorld && m_dynamicsWorld->getDebugDrawer())
{
m_dynamicsWorld->getDebugDrawer()->setDebugMode(debugFlags);
m_dynamicsWorld->debugDrawWorld();
}
}
virtual void physicsDebugDraw(int debugFlags);
virtual void exitPhysics()
{

View File

@@ -0,0 +1,336 @@
/*
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 <stdio.h> //printf debugging
#include <algorithm>
// choose threading providers:
#if BT_USE_TBB
#define USE_TBB 1 // use Intel Threading Building Blocks for thread management
#endif
#if BT_USE_PPL
#define USE_PPL 1 // use Microsoft Parallel Patterns Library (installed with Visual Studio 2010 and later)
#endif // BT_USE_PPL
#if BT_USE_OPENMP
#define USE_OPENMP 1 // use OpenMP (also need to change compiler options for OpenMP support)
#endif
#if USE_OPENMP
#include <omp.h>
#endif // #if USE_OPENMP
#if USE_PPL
#include <ppl.h> // if you get a compile error here, check whether your version of Visual Studio includes PPL
// Visual Studio 2010 and later should come with it
#include <concrtrm.h> // for GetProcessorCount()
#endif // #if USE_PPL
#if USE_TBB
#define __TBB_NO_IMPLICIT_LINKAGE 1
#include <tbb/tbb.h>
#include <tbb/task_scheduler_init.h>
#include <tbb/parallel_for.h>
#include <tbb/blocked_range.h>
#endif // #if USE_TBB
class TaskManager
{
public:
enum Api
{
apiNone,
apiOpenMP,
apiTbb,
apiPpl,
apiCount
};
static const char* getApiName( Api api )
{
switch ( api )
{
case apiNone: return "None";
case apiOpenMP: return "OpenMP";
case apiTbb: return "Intel TBB";
case apiPpl: return "MS PPL";
default: return "unknown";
}
}
TaskManager()
{
m_api = apiNone;
m_numThreads = 0;
#if USE_TBB
m_tbbSchedulerInit = NULL;
#endif // #if USE_TBB
}
Api getApi() const
{
return m_api;
}
bool isSupported( Api api ) const
{
#if USE_OPENMP
if ( api == apiOpenMP )
{
return true;
}
#endif
#if USE_TBB
if ( api == apiTbb )
{
return true;
}
#endif
#if USE_PPL
if ( api == apiPpl )
{
return true;
}
#endif
// apiNone is always "supported"
return api == apiNone;
}
void setApi( Api api )
{
if (isSupported(api))
{
m_api = api;
}
else
{
// no compile time support for selected API, fallback to "none"
m_api = apiNone;
}
}
static int getMaxNumThreads()
{
#if USE_OPENMP
return omp_get_max_threads();
#elif USE_PPL
return concurrency::GetProcessorCount();
#elif USE_TBB
return tbb::task_scheduler_init::default_num_threads();
#endif
return 1;
}
int getNumThreads() const
{
return m_numThreads;
}
int setNumThreads( int numThreads )
{
m_numThreads = ( std::max )( 1, numThreads );
#if USE_OPENMP
omp_set_num_threads( m_numThreads );
#endif
#if USE_PPL
{
using namespace concurrency;
if ( CurrentScheduler::Id() != -1 )
{
CurrentScheduler::Detach();
}
SchedulerPolicy policy;
policy.SetConcurrencyLimits( m_numThreads, m_numThreads );
CurrentScheduler::Create( policy );
}
#endif
#if USE_TBB
if ( m_tbbSchedulerInit )
{
delete m_tbbSchedulerInit;
m_tbbSchedulerInit = NULL;
}
m_tbbSchedulerInit = new tbb::task_scheduler_init( m_numThreads );
#endif
return m_numThreads;
}
void init()
{
if (m_numThreads == 0)
{
#if USE_PPL
setApi( apiPpl );
#endif
#if USE_TBB
setApi( apiTbb );
#endif
#if USE_OPENMP
setApi( apiOpenMP );
#endif
setNumThreads(getMaxNumThreads());
}
else
{
setNumThreads(m_numThreads);
}
}
void shutdown()
{
#if USE_TBB
if ( m_tbbSchedulerInit )
{
delete m_tbbSchedulerInit;
m_tbbSchedulerInit = NULL;
}
#endif
}
private:
Api m_api;
int m_numThreads;
#if USE_TBB
tbb::task_scheduler_init* m_tbbSchedulerInit;
#endif // #if USE_TBB
};
extern TaskManager gTaskMgr;
static void initTaskScheduler()
{
gTaskMgr.init();
}
static void cleanupTaskScheduler()
{
gTaskMgr.shutdown();
}
#if USE_TBB
///
/// TbbBodyAdapter -- Converts a body object that implements the
/// "forLoop(int iBegin, int iEnd) const" function
/// into a TBB compatible object that takes a tbb::blocked_range<int> type.
///
template <class TBody>
struct TbbBodyAdapter
{
const TBody* mBody;
void operator()( const tbb::blocked_range<int>& range ) const
{
mBody->forLoop( range.begin(), range.end() );
}
};
#endif // #if USE_TBB
#if USE_PPL
///
/// PplBodyAdapter -- Converts a body object that implements the
/// "forLoop(int iBegin, int iEnd) const" function
/// into a PPL compatible object that implements "void operator()( int ) const"
///
template <class TBody>
struct PplBodyAdapter
{
const TBody* mBody;
int mGrainSize;
int mIndexEnd;
void operator()( int i ) const
{
mBody->forLoop( i, (std::min)(i + mGrainSize, mIndexEnd) );
}
};
#endif // #if USE_PPL
///
/// parallelFor -- interface for submitting work expressed as a for loop to the worker threads
///
template <class TBody>
void parallelFor( int iBegin, int iEnd, int grainSize, const TBody& body )
{
#if USE_OPENMP
if ( gTaskMgr.getApi() == TaskManager::apiOpenMP )
{
#pragma omp parallel for schedule(static, 1)
for ( int i = iBegin; i < iEnd; i += grainSize )
{
body.forLoop( i, (std::min)( i + grainSize, iEnd ) );
}
return;
}
#endif // #if USE_OPENMP
#if USE_PPL
if ( gTaskMgr.getApi() == TaskManager::apiPpl )
{
// PPL dispatch
PplBodyAdapter<TBody> pplBody;
pplBody.mBody = &body;
pplBody.mGrainSize = grainSize;
pplBody.mIndexEnd = iEnd;
// note: MSVC 2010 doesn't support partitioner args, so avoid them
concurrency::parallel_for( iBegin,
iEnd,
grainSize,
pplBody
);
return;
}
#endif //#if USE_PPL
#if USE_TBB
if ( gTaskMgr.getApi() == TaskManager::apiTbb )
{
// TBB dispatch
TbbBodyAdapter<TBody> tbbBody;
tbbBody.mBody = &body;
tbb::parallel_for( tbb::blocked_range<int>( iBegin, iEnd, grainSize ),
tbbBody,
tbb::simple_partitioner()
);
return;
}
#endif // #if USE_TBB
{
// run on main thread
body.forLoop( iBegin, iEnd );
}
}

View File

@@ -32,6 +32,7 @@ ADD_LIBRARY(BulletExampleBrowserLib
GL_ShapeDrawer.cpp
CollisionShape2TriangleMesh.cpp
CollisionShape2TriangleMesh.h
../CommonInterfaces/CommonRigidBodyBase.cpp
../Utils/b3Clock.cpp
../Utils/b3Clock.h
../Utils/b3ResourcePath.cpp
@@ -108,6 +109,29 @@ ELSE(WIN32)
ENDIF(APPLE)
ENDIF(WIN32)
IF (BULLET2_MULTITHREADED_OPEN_MP_DEMO)
ADD_DEFINITIONS("-DBT_USE_OPENMP=1")
IF (MSVC)
SET(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} /openmp")
ELSE (MSVC)
# GCC, Clang
SET(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -fopenmp")
ENDIF (MSVC)
ENDIF (BULLET2_MULTITHREADED_OPEN_MP_DEMO)
IF (BULLET2_MULTITHREADED_PPL_DEMO)
ADD_DEFINITIONS("-DBT_USE_PPL=1")
ENDIF (BULLET2_MULTITHREADED_PPL_DEMO)
IF (BULLET2_MULTITHREADED_TBB_DEMO)
SET (BULLET2_TBB_INCLUDE_DIR "not found" CACHE PATH "Directory for Intel TBB includes.")
SET (BULLET2_TBB_LIB_DIR "not found" CACHE PATH "Directory for Intel TBB libraries.")
find_library(TBB_LIBRARY tbb PATHS ${BULLET2_TBB_LIB_DIR})
find_library(TBBMALLOC_LIBRARY tbbmalloc PATHS ${BULLET2_TBB_LIB_DIR})
ADD_DEFINITIONS("-DBT_USE_TBB=1")
INCLUDE_DIRECTORIES( ${BULLET2_TBB_INCLUDE_DIR} )
LINK_LIBRARIES( ${TBB_LIBRARY} ${TBBMALLOC_LIBRARY} )
ENDIF (BULLET2_MULTITHREADED_TBB_DEMO)
SET(ExtendedTutorialsSources
../ExtendedTutorials/Chain.cpp
@@ -173,6 +197,8 @@ SET(BulletExampleBrowser_SRCS
../InverseKinematics/InverseKinematicsExample.h
../ForkLift/ForkLiftDemo.cpp
../ForkLift/ForkLiftDemo.h
../MultiThreadedDemo/MultiThreadedDemo.cpp
../MultiThreadedDemo/MultiThreadedDemo.h
../Tutorial/Tutorial.cpp
../Tutorial/Tutorial.h
../Tutorial/Dof6ConstraintTutorial.cpp
@@ -346,9 +372,26 @@ ADD_CUSTOM_COMMAND(
COMMAND ${CMAKE_COMMAND} ARGS -E copy_directory ${BULLET_PHYSICS_SOURCE_DIR}/data ${PROJECT_BINARY_DIR}/data
)
IF (BULLET2_MULTITHREADED_TBB_DEMO AND WIN32)
# add a post build command to copy some dlls to the executable directory
set(TBB_VC_VER "vc12")
set(TBB_VC_ARCH "ia32")
# assume 32-bit build in VC12 for now
# checks can be added here at a later time
ADD_CUSTOM_COMMAND(TARGET App_ExampleBrowser POST_BUILD
COMMAND ${CMAKE_COMMAND} -E copy_if_different
"${BULLET2_TBB_INCLUDE_DIR}/../bin/${TBB_VC_ARCH}/${TBB_VC_VER}/tbb.dll"
$<TARGET_FILE_DIR:App_ExampleBrowser>)
ADD_CUSTOM_COMMAND(TARGET App_ExampleBrowser POST_BUILD
COMMAND ${CMAKE_COMMAND} -E copy_if_different
"${BULLET2_TBB_INCLUDE_DIR}/../bin/${TBB_VC_ARCH}/${TBB_VC_VER}/tbbmalloc.dll"
$<TARGET_FILE_DIR:App_ExampleBrowser>)
ENDIF (BULLET2_MULTITHREADED_TBB_DEMO AND WIN32)
IF (INTERNAL_ADD_POSTFIX_EXECUTABLE_NAMES)
SET_TARGET_PROPERTIES(App_ExampleBrowser PROPERTIES DEBUG_POSTFIX "_Debug")
SET_TARGET_PROPERTIES(App_ExampleBrowser PROPERTIES MINSIZEREL_POSTFIX "_MinsizeRel")
SET_TARGET_PROPERTIES(App_ExampleBrowser PROPERTIES RELWITHDEBINFO_POSTFIX "_RelWithDebugInfo")
ENDIF(INTERNAL_ADD_POSTFIX_EXECUTABLE_NAMES)

View File

@@ -8,6 +8,7 @@
#include "../RenderingExamples/TinyRendererSetup.h"
#include "../RenderingExamples/DynamicTexturedCubeDemo.h"
#include "../ForkLift/ForkLiftDemo.h"
#include "../MultiThreadedDemo/MultiThreadedDemo.h"
#include "../BasicDemo/BasicExample.h"
#include "../Planar2D/Planar2D.h"
#include "../Benchmarks/BenchmarkDemo.h"
@@ -285,7 +286,13 @@ static ExampleEntry gDefaultExamples[]=
ExampleEntry(1,"Fracture demo", "Create a basic custom implementation to model fracturing objects, based on a btCompoundShape. It explicitly propagates the collision impulses and breaks the rigid body into multiple rigid bodies. Press F to toggle fracture and glue mode.", FractureDemoCreateFunc),
ExampleEntry(1,"Planar 2D","Show the use of 2D collision shapes and rigid body simulation. The collision shape is wrapped into a btConvex2dShape. The rigid bodies are restricted in a plane using the 'setAngularFactor' and 'setLinearFactor' API call.",Planar2DCreateFunc),
#if BT_USE_OPENMP || BT_USE_TBB || BT_USE_PPL
// only enable MultiThreaded demo if a task scheduler is available
ExampleEntry( 1, "Multithreaded Demo",
"Stacks of boxes that do not sleep. Good for testing performance with large numbers of bodies and contacts. Sliders can be used to change the number of stacks (restart needed after each change)."
,
MultiThreadedDemoCreateFunc ),
#endif
ExampleEntry(0,"Rendering"),

View File

@@ -95,6 +95,7 @@ project "App_BulletExampleBrowser"
"../RoboticsLearning/*",
"../Collision/Internal/*",
"../Benchmarks/*",
"../MultiThreadedDemo/*",
"../CommonInterfaces/*",
"../ForkLift/ForkLiftDemo.*",
"../Importers/**",

View File

@@ -17,6 +17,7 @@ language "C++"
files {
"RigidBodyFromObj.cpp",
"../CommonInterfaces/*",
"**.h",
"../StandaloneMain/main_console_single_example.cpp",
"../Utils/b3ResourcePath.cpp",
@@ -68,6 +69,7 @@ files {
"RigidBodyFromObj.cpp",
"*.h",
"../StandaloneMain/main_opengl_single_example.cpp",
"../CommonInterfaces/*",
"../ExampleBrowser/OpenGLGuiHelper.cpp",
"../ExampleBrowser/GL_ShapeDrawer.cpp",
"../ExampleBrowser/CollisionShape2TriangleMesh.cpp",
@@ -132,6 +134,7 @@ files {
"../ExampleBrowser/OpenGLGuiHelper.cpp",
"../ExampleBrowser/GL_ShapeDrawer.cpp",
"../ExampleBrowser/CollisionShape2TriangleMesh.cpp",
"../CommonInterfaces/*",
"../TinyRenderer/geometry.cpp",
"../TinyRenderer/model.cpp",
"../TinyRenderer/tgaimage.cpp",
@@ -193,6 +196,7 @@ files {
"../StandaloneMain/main_tinyrenderer_single_example.cpp",
"../OpenGLWindow/SimpleCamera.cpp",
"../ExampleBrowser/CollisionShape2TriangleMesh.cpp",
"../CommonInterfaces/*",
"../TinyRenderer/geometry.cpp",
"../TinyRenderer/model.cpp",
"../TinyRenderer/tgaimage.cpp",

View File

@@ -0,0 +1,229 @@
/*
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 "btBulletDynamicsCommon.h"
#include "LinearMath/btQuickprof.h"
#include "LinearMath/btIDebugDraw.h"
#include <stdio.h> //printf debugging
#include <algorithm>
class btCollisionShape;
#include "../CommonInterfaces/CommonExampleInterface.h"
#include "../CommonInterfaces/CommonRigidBodyBase.h"
#include "../CommonInterfaces/CommonParameterInterface.h"
#include "../CommonInterfaces/CommonGUIHelperInterface.h"
#include "../CommonInterfaces/CommonRenderInterface.h"
#include "../CommonInterfaces/CommonWindowInterface.h"
#include "../CommonInterfaces/CommonGraphicsAppInterface.h"
#include "MultiThreadedDemo.h"
#include "LinearMath/btAlignedObjectArray.h"
#include "btBulletCollisionCommon.h"
#define BT_OVERRIDE
/// MultiThreadedDemo shows how to setup and use multithreading
class MultiThreadedDemo : public CommonRigidBodyBase
{
static const int kUpAxis = 1;
btRigidBody* localCreateRigidBody(btScalar mass, const btTransform& worldTransform, btCollisionShape* colSape);
btVector3 m_cameraTargetPos;
float m_cameraPitch;
float m_cameraYaw;
float m_cameraDist;
void createStack( const btVector3& pos, btCollisionShape* boxShape, const btVector3& halfBoxSize, int size );
void createSceneObjects();
void destroySceneObjects();
public:
BT_DECLARE_ALIGNED_ALLOCATOR();
MultiThreadedDemo( struct GUIHelperInterface* helper );
virtual ~MultiThreadedDemo() {}
virtual void stepSimulation( float deltaTime ) BT_OVERRIDE
{
if ( m_dynamicsWorld )
{
// always step by 1/60 for benchmarking
m_dynamicsWorld->stepSimulation( 1.0f / 60.0f, 0 );
}
}
virtual void initPhysics() BT_OVERRIDE;
virtual void resetCamera() BT_OVERRIDE
{
m_guiHelper->resetCamera( m_cameraDist,
m_cameraPitch,
m_cameraYaw,
m_cameraTargetPos.x(),
m_cameraTargetPos.y(),
m_cameraTargetPos.z()
);
}
};
MultiThreadedDemo::MultiThreadedDemo(struct GUIHelperInterface* helper)
: CommonRigidBodyBase( helper )
{
m_cameraTargetPos = btVector3( 0.0f, 0.0f, 0.0f );
m_cameraPitch = 90.0f;
m_cameraYaw = 30.0f;
m_cameraDist = 48.0f;
helper->setUpAxis( kUpAxis );
}
static btScalar gSliderStackRows = 8.0f;
static btScalar gSliderStackColumns = 6.0f;
void MultiThreadedDemo::initPhysics()
{
createEmptyDynamicsWorld();
m_dynamicsWorld->setGravity( btVector3( 0, -10, 0 ) );
{
SliderParams slider( "Stack rows", &gSliderStackRows );
slider.m_minVal = 1.0f;
slider.m_maxVal = 20.0f;
slider.m_clampToNotches = false;
m_guiHelper->getParameterInterface()->registerSliderFloatParameter( slider );
}
{
SliderParams slider( "Stack columns", &gSliderStackColumns );
slider.m_minVal = 1.0f;
slider.m_maxVal = 20.0f;
slider.m_clampToNotches = false;
m_guiHelper->getParameterInterface()->registerSliderFloatParameter( slider );
}
createSceneObjects();
m_guiHelper->createPhysicsDebugDrawer( m_dynamicsWorld );
}
btRigidBody* MultiThreadedDemo::localCreateRigidBody(btScalar mass, const btTransform& startTransform, btCollisionShape* shape)
{
btRigidBody* body = createRigidBody(mass, startTransform, shape);
if ( mass > 0.0f )
{
// prevent bodies from sleeping to make profiling/benchmarking easier
body->forceActivationState( DISABLE_DEACTIVATION );
}
return body;
}
void MultiThreadedDemo::createStack( const btVector3& center, btCollisionShape* boxShape, const btVector3& halfBoxSize, int size )
{
btTransform trans;
trans.setIdentity();
float halfBoxHeight = halfBoxSize.y();
float halfBoxWidth = halfBoxSize.x();
for ( int i = 0; i<size; i++ )
{
// This constructs a row, from left to right
int rowSize = size - i;
for ( int j = 0; j< rowSize; j++ )
{
btVector3 pos = center + btVector3( halfBoxWidth*( 1 + j * 2 - rowSize ),
halfBoxHeight * ( 1 + i * 2),
0.0f
);
trans.setOrigin( pos );
btScalar mass = 1.f;
btRigidBody* body = localCreateRigidBody( mass, trans, boxShape );
}
}
}
void MultiThreadedDemo::createSceneObjects()
{
{
// create ground box
btTransform tr;
tr.setIdentity();
tr.setOrigin( btVector3( 0, -3, 0 ) );
//either use heightfield or triangle mesh
btVector3 groundExtents( 400, 400, 400 );
groundExtents[ kUpAxis ] = 3;
btCollisionShape* groundShape = new btBoxShape( groundExtents );
m_collisionShapes.push_back( groundShape );
//create ground object
localCreateRigidBody( 0, tr, groundShape );
}
{
// create walls of cubes
const btVector3 halfExtents = btVector3( 0.5f, 0.25f, 0.5f );
int numStackRows = btMax(1, int(gSliderStackRows));
int numStackCols = btMax(1, int(gSliderStackColumns));
int stackHeight = 15;
float stackZSpacing = 3.0f;
float stackXSpacing = 20.0f;
btBoxShape* boxShape = new btBoxShape( halfExtents );
m_collisionShapes.push_back( boxShape );
for ( int iX = 0; iX < numStackCols; ++iX )
{
for ( int iZ = 0; iZ < numStackRows; ++iZ )
{
btVector3 center = btVector3( iX * stackXSpacing, 0.0f, ( iZ - numStackRows / 2 ) * stackZSpacing );
createStack( center, boxShape, halfExtents, stackHeight );
}
}
}
if ( false )
{
// destroyer ball
btTransform sphereTrans;
sphereTrans.setIdentity();
sphereTrans.setOrigin( btVector3( 0, 2, 40 ) );
btSphereShape* ball = new btSphereShape( 2.f );
m_collisionShapes.push_back( ball );
btRigidBody* ballBody = localCreateRigidBody( 10000.f, sphereTrans, ball );
ballBody->setLinearVelocity( btVector3( 0, 0, -10 ) );
}
m_guiHelper->autogenerateGraphicsObjects( m_dynamicsWorld );
}
CommonExampleInterface* MultiThreadedDemoCreateFunc( struct CommonExampleOptions& options )
{
return new MultiThreadedDemo(options.m_guiHelper);
}

View File

@@ -0,0 +1,22 @@
/*
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 MULTITHREADED_DEMO_H
#define MULTITHREADED_DEMO_H
class CommonExampleInterface* MultiThreadedDemoCreateFunc(struct CommonExampleOptions& options);
#endif // MULTITHREADED_DEMO_H

View File

@@ -280,7 +280,7 @@ void SimpleOpenGL2App::swapBuffer()
m_window->startRendering();
}
void SimpleOpenGL2App::drawText( const char* txt, int posX, int posY)
void SimpleOpenGL2App::drawText( const char* txt, int posX, int posY, float size)
{
}

View File

@@ -17,7 +17,7 @@ public:
virtual int getUpAxis() const;
virtual void swapBuffer();
virtual void drawText( const char* txt, int posX, int posY);
virtual void drawText( const char* txt, int posX, int posY, float size);
virtual void drawTexturedRect(float x0, float y0, float x1, float y1, float color[4], float u0,float v0, float u1, float v1, int useRGBA){};
virtual void setBackgroundColor(float red, float green, float blue);
virtual int registerCubeShape(float halfExtentsX,float halfExtentsY, float halfExtentsZ, int textureIndex = -1, float textureScaling = 1)

View File

@@ -352,7 +352,7 @@ void SimpleOpenGL3App::drawText3D( const char* txt, float worldPosX, float world
}
void SimpleOpenGL3App::drawText( const char* txt, int posXi, int posYi)
void SimpleOpenGL3App::drawText( const char* txt, int posXi, int posYi, float size)
{
float posX = (float)posXi;
@@ -374,7 +374,7 @@ void SimpleOpenGL3App::drawText( const char* txt, int posXi, int posYi)
{
bool measureOnly = false;
float fontSize= 64;//512;//128;
float fontSize= 64*size;//512;//128;
sth_draw_text(m_data->m_fontStash,
m_data->m_droidRegular,fontSize,posX,posY,
txt,&dx, this->m_instancingRenderer->getScreenWidth(),

View File

@@ -31,7 +31,7 @@ struct SimpleOpenGL3App : public CommonGraphicsApp
virtual int getUpAxis() const;
virtual void swapBuffer();
virtual void drawText( const char* txt, int posX, int posY);
virtual void drawText( const char* txt, int posX, int posY, float size=1.0f);
virtual void drawText3D( const char* txt, float posX, float posZY, float posZ, float size);
virtual void drawTexturedRect(float x0, float y0, float x1, float y1, float color[4], float u0,float v0, float u1, float v1, int useRGBA);
struct sth_stash* getFontStash();