Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
19 changes: 17 additions & 2 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -28,6 +28,7 @@ OPTION(USE_DOUBLE_PRECISION "Use double precision" OFF)
OPTION(USE_GRAPHICAL_BENCHMARK "Use Graphical Benchmark" ON)
OPTION(BUILD_SHARED_LIBS "Use shared libraries" OFF)
OPTION(USE_SOFT_BODY_MULTI_BODY_DYNAMICS_WORLD "Use btSoftMultiBodyDynamicsWorld" OFF)
OPTION(BULLET2_USE_THREAD_LOCKS "Build Bullet 2 libraries with mutex locking around certain operations" OFF)

OPTION(USE_MSVC_INCREMENTAL_LINKING "Use MSVC Incremental Linking" OFF)
OPTION(USE_CUSTOM_VECTOR_MATH "Use custom vectormath library" OFF)
Expand Down Expand Up @@ -155,6 +156,13 @@ IF(USE_GRAPHICAL_BENCHMARK)
ADD_DEFINITIONS( -DUSE_GRAPHICAL_BENCHMARK)
ENDIF (USE_GRAPHICAL_BENCHMARK)

IF(BULLET2_USE_THREAD_LOCKS)
ADD_DEFINITIONS( -DBT_THREADSAFE=1 )
IF (NOT MSVC)
SET(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++11")
ENDIF (NOT MSVC)
ENDIF (BULLET2_USE_THREAD_LOCKS)

IF (WIN32)
OPTION(USE_GLUT "Use Glut" ON)
ADD_DEFINITIONS( -D_CRT_SECURE_NO_WARNINGS )
Expand Down Expand Up @@ -195,8 +203,6 @@ ENDIF (OPENGL_FOUND)
#FIND_PACKAGE(GLU)




IF (APPLE)
FIND_LIBRARY(COCOA_LIBRARY Cocoa)
ENDIF()
Expand Down Expand Up @@ -264,6 +270,15 @@ IF(BUILD_BULLET2_DEMOS)
IF(EXISTS ${BULLET_PHYSICS_SOURCE_DIR}/examples AND IS_DIRECTORY ${BULLET_PHYSICS_SOURCE_DIR}/examples)
SUBDIRS(examples)
ENDIF()

IF (BULLET2_USE_THREAD_LOCKS)
OPTION(BULLET2_MULTITHREADED_OPEN_MP_DEMO "Build Bullet 2 MultithreadedDemo using OpenMP (requires a compiler with OpenMP support)" OFF)
OPTION(BULLET2_MULTITHREADED_TBB_DEMO "Build Bullet 2 MultithreadedDemo using Intel Threading Building Blocks (requires the TBB library to be already installed)" OFF)
IF (MSVC)
OPTION(BULLET2_MULTITHREADED_PPL_DEMO "Build Bullet 2 MultithreadedDemo using Microsoft Parallel Patterns Library (requires MSVC compiler)" OFF)
ENDIF (MSVC)
ENDIF (BULLET2_USE_THREAD_LOCKS)

ENDIF(BUILD_BULLET2_DEMOS)


Expand Down
3 changes: 3 additions & 0 deletions examples/BasicDemo/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -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()

Expand Down Expand Up @@ -53,6 +55,7 @@ SET(AppBasicExampleGui_SRCS
../ExampleBrowser/OpenGLGuiHelper.cpp
../ExampleBrowser/GL_ShapeDrawer.cpp
../ExampleBrowser/CollisionShape2TriangleMesh.cpp
../CommonInterfaces/CommonRigidBodyBase.cpp
../Utils/b3Clock.cpp
)

Expand Down
7 changes: 6 additions & 1 deletion examples/BasicDemo/premake4.lua
Original file line number Diff line number Diff line change
Expand Up @@ -18,6 +18,7 @@ language "C++"
files {
"**.cpp",
"**.h",
"../CommonInterfaces/*",
}


Expand Down Expand Up @@ -49,6 +50,7 @@ files {
"../ExampleBrowser/OpenGLGuiHelper.cpp",
"../ExampleBrowser/GL_ShapeDrawer.cpp",
"../ExampleBrowser/CollisionShape2TriangleMesh.cpp",
"../CommonInterfaces/*",
"../Utils/b3Clock.cpp",
"../Utils/b3Clock.h",
}
Expand Down Expand Up @@ -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",
Expand Down Expand Up @@ -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",
Expand Down Expand Up @@ -175,6 +179,7 @@ files {
"BasicExample.cpp",
"*.h",
"../StandaloneMain/hellovr_opengl_main.cpp",
"../CommonInterfaces/*",
"../ExampleBrowser/OpenGLGuiHelper.cpp",
"../ExampleBrowser/GL_ShapeDrawer.cpp",
"../ExampleBrowser/CollisionShape2TriangleMesh.cpp",
Expand All @@ -200,4 +205,4 @@ if os.is("MacOSX") then
links{"Cocoa.framework"}
end

end
end
108 changes: 70 additions & 38 deletions examples/Benchmarks/BenchmarkDemo.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand Down Expand Up @@ -204,7 +206,39 @@ class btRaycastBar2
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 ();
Expand All @@ -228,22 +262,19 @@ class btRaycastBar2
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
Expand Down Expand Up @@ -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);

Expand Down Expand Up @@ -1242,7 +1274,7 @@ void BenchmarkDemo::initRays()

void BenchmarkDemo::castRays()
{
raycastBar.cast (m_dynamicsWorld);
raycastBar.cast (m_dynamicsWorld, m_multithreadedWorld);
}

void BenchmarkDemo::createTest7()
Expand Down
2 changes: 1 addition & 1 deletion examples/CommonInterfaces/CommonGraphicsAppInterface.h
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand Down
Loading