add Bullet 2.x constraint solver tests for hinge, with large mass ratio

experiment with Midi controls in PairBenchmark to tune variables (will move it into a utility class, so every demo can easier use it in the future)
fix issue with broadphase, not initializing all pairs properly at pair array overflow
This commit is contained in:
Erwin Coumans 2014-01-28 10:25:04 -08:00
parent e3ee9e5b2e
commit 71f0537c6e
20 changed files with 719 additions and 38 deletions

View File

@ -4,6 +4,7 @@
#include "BulletDemoInterface.h"
#include "../bullet2/BasicDemo/BasicDemo.h"
#include "../bullet2/BasicDemo/HingeDemo.h"
#include "../bullet2/FeatherstoneMultiBodyDemo/BulletMultiBodyDemos.h"
#include "../bullet2/FeatherstoneMultiBodyDemo/MultiDofDemo.h"
@ -22,6 +23,7 @@ static BulletDemoEntry allDemos[]=
//{"emptydemo",EmptyBulletDemo::MyCreateFunc},
{"BasicDemo",BasicDemo::MyCreateFunc},
{"HingeDemo",HingeDemo::MyCreateFunc},
{"Ragdoll",RagDollDemo::MyCreateFunc},
{"MultiBody1",FeatherstoneDemo1::MyCreateFunc},
{"MultiDofDemo",MultiDofDemo::MyCreateFunc},

View File

@ -40,7 +40,7 @@ void MyKeyboardCallback(int key, int state)
glPolygonMode( GL_FRONT_AND_BACK, GL_FILL );
}
}
if (key=='I' && state)
if (key=='i' && state)
{
pauseSimulation = !pauseSimulation;
}

View File

@ -28,6 +28,8 @@
"../bullet2/FeatherstoneMultiBodyDemo/MultiDofDemo.h",
"../bullet2/BasicDemo/BasicDemo.cpp",
"../bullet2/BasicDemo/BasicDemo.h",
"../bullet2/BasicDemo/HingeDemo.cpp",
"../bullet2/BasicDemo/HingeDemo.h",
"../bullet2/RagdollDemo/RagdollDemo.cpp",
"../bullet2/RagdollDemo/RagdollDemo.h",
"../../src/Bullet3Common/**.cpp",

View File

@ -21,6 +21,55 @@
#include "pairsKernel.h"
#ifdef B3_USE_MIDI
#include "../../../btgui/MidiTest/RtMidi.h"
bool chooseMidiPort( RtMidiIn *rtmidi )
{
if (!rtmidi)
return false;
/*
std::cout << "\nWould you like to open a virtual input port? [y/N] ";
std::string keyHit;
std::getline( std::cin, keyHit );
if ( keyHit == "y" ) {
rtmidi->openVirtualPort();
return true;
}
*/
std::string portName;
unsigned int i = 0, nPorts = rtmidi->getPortCount();
if ( nPorts == 0 ) {
std::cout << "No input ports available!" << std::endl;
return false;
}
if ( nPorts == 1 ) {
std::cout << "\nOpening " << rtmidi->getPortName() << std::endl;
}
else {
for ( i=0; i<nPorts; i++ ) {
portName = rtmidi->getPortName(i);
std::cout << " Input port #" << i << ": " << portName << '\n';
}
do {
std::cout << "\nChoose a port number: ";
std::cin >> i;
} while ( i >= nPorts );
}
// std::getline( std::cin, keyHit ); // used to clear out stdin
rtmidi->openPort( i );
return true;
}
#endif
static b3KeyboardCallback oldCallback = 0;
char* gPairBenchFileName = 0;
@ -50,8 +99,8 @@ static PairBench* sPairDemo = 0;
static int curSelectedBroadphase = 0;
static BroadphaseEntry allBroadphases[]=
{
{"Gpu Grid",b3GpuGridBroadphase::CreateFunc},
{"Gpu 1-Sap",b3GpuSapBroadphase::CreateFunc},
{"Gpu Grid",b3GpuGridBroadphase::CreateFunc},
};
@ -83,6 +132,9 @@ struct PairBenchInternalData
int m_oldYposition;
b3AlignedObjectArray<Gwen::Controls::Base*> m_myControls;
#ifdef B3_USE_MIDI
RtMidiIn* m_midiIn;
#endif //B3_USE_MIDI
};
@ -177,11 +229,13 @@ template<typename T>
struct MySliderEventHandler : public Gwen::Event::Handler
{
Gwen::Controls::TextBox* m_label;
Gwen::Controls::Slider* m_pSlider;
char m_variableName[1024];
T* m_targetValue;
MySliderEventHandler(const char* varName, Gwen::Controls::TextBox* label, T* target)
MySliderEventHandler(const char* varName, Gwen::Controls::TextBox* label, Gwen::Controls::Slider* pSlider,T* target)
:m_label(label),
m_pSlider(pSlider),
m_targetValue(target)
{
memcpy(m_variableName,varName,strlen(varName)+1);
@ -192,19 +246,69 @@ struct MySliderEventHandler : public Gwen::Event::Handler
{
Gwen::Controls::Slider* pSlider = (Gwen::Controls::Slider*)pControl;
//printf("value = %f\n", pSlider->GetValue());//UnitPrint( Utility::Format( L"Slider Value: %.2f", pSlider->GetValue() ) );
char txt[1024];
T v = T(pSlider->GetValue());
SetValue(v);
}
void SetValue(T v)
{
if (v < m_pSlider->GetRangeMin())
{
printf("?\n");
}
if (v > m_pSlider->GetRangeMax())
{
printf("?\n");
}
m_pSlider->SetValue(v,true);
(*m_targetValue) = v;
int val = int(v);//todo: specialize on template type
char txt[1024];
sprintf(txt,"%s : %d", m_variableName,val);
m_label->SetText(txt);
}
};
MySliderEventHandler<float>* test = 0;
#ifdef B3_USE_MIDI
//todo: create a mapping from midi channel to variable 'slider' or 'knob'
void PairMidiCallback( double deltatime, std::vector< unsigned char > *message, void *userData )
{
unsigned int nBytes = message->size();
if (nBytes==3)
{
if (test && message->at(1)==16)
{
test->SetValue(message->at(2));
}
}
}
#endif
void PairBench::initPhysics(const ConstructionInfo& ci)
{
#ifdef B3_USE_MIDI
m_data->m_midiIn = new RtMidiIn();
if (!chooseMidiPort(m_data->m_midiIn))
{
delete m_data->m_midiIn;
m_data->m_midiIn = 0;
} else
{
m_data->m_midiIn->setCallback( &PairMidiCallback,this );
// Don't ignore sysex, timing, or active sensing messages.
m_data->m_midiIn->ignoreTypes( false, false, false );
}
#endif //B3_USE_MIDI
m_instancingRenderer = ci.m_instancingRenderer;
sPairDemo = this;
useShadowMap = false;
@ -269,7 +373,7 @@ void PairBench::initPhysics(const ConstructionInfo& ci)
pSlider->SetValue( dimensions[i] );
char labelName[1024];
sprintf(labelName,"%s",axisNames[0]);
MySliderEventHandler<int>* handler = new MySliderEventHandler<int>(labelName,label,&dimensions[i]);
MySliderEventHandler<int>* handler = new MySliderEventHandler<int>(labelName,label,pSlider,&dimensions[i]);
pSlider->onValueChanged.Add( handler, &MySliderEventHandler<int>::SliderMoved );
handler->SliderMoved(pSlider);
float v = pSlider->GetValue();
@ -295,7 +399,8 @@ void PairBench::initPhysics(const ConstructionInfo& ci)
pSlider->SetRange( 0, 300);
pSlider->SetValue( mAmplitude );
MySliderEventHandler<float>* handler = new MySliderEventHandler<float>(labelName,label,&mAmplitude);
MySliderEventHandler<float>* handler = new MySliderEventHandler<float>(labelName,label,pSlider,&mAmplitude);
test = handler;
pSlider->onValueChanged.Add( handler, &MySliderEventHandler<float>::SliderMoved );
handler->SliderMoved(pSlider);
float v = pSlider->GetValue();
@ -537,7 +642,13 @@ void PairBench::deleteBroadphase()
void PairBench::exitPhysics()
{
#ifdef B3_USE_MIDI
if (m_data->m_midiIn)
{
delete m_data->m_midiIn;
m_data->m_midiIn = 0;
}
#endif //B3_USE_MIDI
m_data->m_gui->getInternalData()->m_curYposition = m_data->m_oldYposition;
for (int i=0;i<m_data->m_myControls.size();i++)
@ -628,7 +739,7 @@ void PairBench::clientMoveAndDisplay()
}
}
bool updateOnGpu=false;//true;
bool updateOnGpu=true;
if (updateOnGpu)
{

View File

@ -65,6 +65,23 @@ function createProject(vendor)
"../../btgui/Timing/b3Clock.h",
}
if _OPTIONS["midi"] then
if os.is("Windows") then
files {"../../btgui/MidiTest/RtMidi.cpp"}
links {"winmm"}
defines {"__WINDOWS_MM__", "WIN32","B3_USE_MIDI"}
end
if os.is("Linux") then
end
if os.is("MacOSX") then
files {"../../btgui/MidiTest/RtMidi.cpp"}
links{"CoreAudio.framework", "coreMIDI.framework", "Cocoa.framework"}
defines {"__MACOSX_CORE__","B3_USE_MIDI"}
end
end
if os.is("Windows") then
files{
"../../btgui/OpenGLWindow/Win32OpenGLWindow.cpp",

View File

@ -19,12 +19,13 @@
#include "Bullet3Collision/NarrowPhaseCollision/shared/b3RigidBodyData.h"
#include "Bullet3OpenCL/RigidBody/b3GpuNarrowPhaseInternalData.h"
#include "OpenGLWindow/GLPrimitiveRenderer.h"
static b3KeyboardCallback oldCallback = 0;
extern bool gReset;
bool useUniformGrid = false;
bool convertOnCpu = false;
static bool sShowShadowMap = true;
#define MSTRINGIFY(A) #A
static const char* s_rigidBodyKernelString = MSTRINGIFY(
@ -103,7 +104,7 @@ void GpuRigidBodyDemo::initPhysics(const ConstructionInfo& ci)
}
m_instancingRenderer = ci.m_instancingRenderer;
m_primRenderer = ci.m_primRenderer;
initCL(ci.preferredOpenCLDeviceIndex,ci.preferredOpenCLPlatformIndex);
if (m_clData->m_clContext)
@ -175,6 +176,23 @@ void GpuRigidBodyDemo::exitPhysics()
void GpuRigidBodyDemo::renderScene()
{
m_instancingRenderer->renderScene();
if (sShowShadowMap)
{
glDisable(GL_DEPTH_TEST);
float borderColor[4]={0,0,0,1};
m_primRenderer->drawRect(9,29,191,211,borderColor);
float color[4]={1,1,1,1};
//m_shadowData->m_instancingRenderer->renderScene();
m_instancingRenderer->enableShadowMap();
glTexParameteri( GL_TEXTURE_2D, GL_TEXTURE_COMPARE_MODE, GL_NONE );
// glTexParameteri( GL_TEXTURE_2D, GL_DEPTH_TEXTURE_MODE, GL_LUMINANCE );
m_primRenderer->drawTexturedRect(10,30,190,210,color,0,0,1,1,true);
glTexParameteri( GL_TEXTURE_2D, GL_TEXTURE_COMPARE_MODE, GL_COMPARE_REF_TO_TEXTURE);
glEnable(GL_DEPTH_TEST);
}
}
void GpuRigidBodyDemo::clientMoveAndDisplay()

View File

@ -8,6 +8,7 @@ class GpuRigidBodyDemo : public GpuDemo
{
protected:
class GLInstancingRenderer* m_instancingRenderer;
class GLPrimitiveRenderer* m_primRenderer;
class b3gWindowInterface* m_window;
struct GpuRigidBodyDemoInternalData* m_data;

View File

@ -1,9 +1,13 @@
#include "BasicDemo.h"
#include "OpenGLWindow/SimpleOpenGL3App.h"
#include "btBulletDynamicsCommon.h"
#include "Bullet3Common/b3Vector3.h"
#include "LinearMath/btVector3.h"
#include "BulletDynamics/ConstraintSolver/btNNCGConstraintSolver.h"
#define ARRAY_SIZE_X 5
#define ARRAY_SIZE_Y 5
#define ARRAY_SIZE_Z 5
@ -68,12 +72,12 @@ void BasicDemo::initPhysics()
{
float halfExtents[]={scaling,scaling,scaling,1};
b3Vector4 colors[4] =
btVector4 colors[4] =
{
b3MakeVector4(1,0,0,1),
b3MakeVector4(0,1,0,1),
b3MakeVector4(0,1,1,1),
b3MakeVector4(1,1,0,1),
btVector4(1,0,0,1),
btVector4(0,1,0,1),
btVector4(0,1,1,1),
btVector4(1,1,0,1),
};
@ -92,7 +96,7 @@ void BasicDemo::initPhysics()
for(int j = 0;j<ARRAY_SIZE_Z;j++)
{
b3Vector4 color = colors[curColor];
btVector4 color = colors[curColor];
curColor++;
curColor&=3;
startTransform.setOrigin(btVector3(
@ -142,3 +146,6 @@ void BasicDemo::stepSimulation(float dt)
{
m_dynamicsWorld->stepSimulation(dt);
}

View File

@ -21,10 +21,10 @@ public:
void createGround(int cubeShapeId);
void initPhysics();
void exitPhysics();
void renderScene();
void stepSimulation(float dt);
virtual void initPhysics();
virtual void exitPhysics();
virtual void renderScene();
virtual void stepSimulation(float dt);
};

View File

@ -36,6 +36,11 @@ void Bullet2RigidBodyDemo::exitPhysics()
m_config=0;
}
void Bullet2RigidBodyDemo::stepSimulation(float deltaTime)
{
m_dynamicsWorld->stepSimulation(deltaTime);
}
Bullet2RigidBodyDemo::~Bullet2RigidBodyDemo()
{
btAssert(m_config == 0);

View File

@ -38,6 +38,8 @@ public:
return false;
}
virtual void stepSimulation(float deltaTime);
};
#endif //BULLET2_RIGIDBODY_DEMO_H

View File

@ -0,0 +1,423 @@
#include "HingeDemo.h"
#include "OpenGLWindow/SimpleOpenGL3App.h"
#include "MyDebugDrawer.h"
#include "btBulletDynamicsCommon.h"
#include "BulletDynamics/MLCPSolvers/btDantzigSolver.h"
#include "BulletDynamics/MLCPSolvers/btLemkeSolver.h"
#include "BulletDynamics/MLCPSolvers/btSolveProjectedGaussSeidel.h"
#include "BulletDynamics/MLCPSolvers/btMLCPSolver.h"
#include "BulletDynamics/Featherstone/btMultiBody.h"
#include "BulletDynamics/Featherstone/btMultiBodyConstraintSolver.h"
#include "BulletDynamics/Featherstone/btMultiBodyDynamicsWorld.h"
#include "BulletDynamics/Featherstone/btMultiBodyLinkCollider.h"
#include "BulletDynamics/Featherstone/btMultiBodyLink.h"
#include "BulletDynamics/Featherstone/btMultiBodyJointLimitConstraint.h"
#include "BulletDynamics/Featherstone/btMultiBodyJointMotor.h"
#include "BulletDynamics/Featherstone/btMultiBodyPoint2Point.h"
#include "OpenGLWindow/GLInstancingRenderer.h"
#include "BulletCollision/CollisionShapes/btShapeHull.h"
static float scaling = .2f;
static float friction = 1.f;
struct GraphicsVertex
{
float pos[4];
float normal[3];
float texcoord[2];
};
static btVector4 colors[4] =
{
btVector4(1,0,0,1),
btVector4(0,1,0,1),
btVector4(0,1,1,1),
btVector4(1,1,0,1),
};
HingeDemo::HingeDemo(SimpleOpenGL3App* app)
:BasicDemo(app)
{
}
struct btMultiBodySettings2
{
btMultiBodySettings2()
{
m_numLinks = 0;
m_basePosition.setZero();
m_isFixedBase = true;
m_usePrismatic = false;
m_canSleep = true;
m_createConstraints = false;
m_disableParentCollision = false;
}
int m_numLinks;
btVector3 m_basePosition;
bool m_isFixedBase;
bool m_usePrismatic;
bool m_canSleep;
bool m_createConstraints;
bool m_disableParentCollision;
};
btMultiBody* HingeDemo::createFeatherstoneHinge(class btMultiBodyDynamicsWorld* world, const btMultiBodySettings2& settings)
{
int curColor=0;
int cubeShapeId = m_glApp->registerCubeShape();
int n_links = settings.m_numLinks;
float mass = 13.5*scaling;
btVector3 inertia = btVector3 (91,344,253)*scaling*scaling;
bool isMultiDof = false;
btMultiBody * bod = new btMultiBody(n_links, mass, inertia, settings.m_isFixedBase, settings.m_canSleep, isMultiDof);
// bod->setHasSelfCollision(false);
//btQuaternion orn(btVector3(0,0,1),-0.25*SIMD_HALF_PI);//0,0,0,1);
btQuaternion orn(0,0,0,1);
bod->setBasePos(settings.m_basePosition);
bod->setWorldToBaseRot(orn);
btVector3 vel(0,0,0);
bod->setBaseVel(vel);
{
btVector3 joint_axis_hinge(1,0,0);
btVector3 joint_axis_prismatic(0,0,1);
btQuaternion parent_to_child = orn.inverse();
btVector3 joint_axis_child_prismatic = quatRotate(parent_to_child ,joint_axis_prismatic);
btVector3 joint_axis_child_hinge = quatRotate(parent_to_child , joint_axis_hinge);
int this_link_num = -1;
int link_num_counter = 0;
btVector3 pos = btVector3 (0,0,9.0500002)*scaling;
btVector3 joint_axis_position = btVector3 (0,0,4.5250001)*scaling;
for (int i=0;i<n_links;i++)
{
float initial_joint_angle=0.3;
if (i>0)
initial_joint_angle = -0.06f;
const int child_link_num = link_num_counter++;
if (settings.m_usePrismatic)// && i==(n_links-1))
{
bod->setupPrismatic(child_link_num, mass, inertia, this_link_num,
parent_to_child, joint_axis_child_prismatic, quatRotate(parent_to_child , pos),settings.m_disableParentCollision);
} else
{
bod->setupRevolute(child_link_num, mass, inertia, this_link_num,parent_to_child, joint_axis_child_hinge,
joint_axis_position,quatRotate(parent_to_child , (pos - joint_axis_position)),settings.m_disableParentCollision);
}
bod->setJointPos(child_link_num, initial_joint_angle);
this_link_num = i;
if (0)//!useGroundShape && i==4)
{
btVector3 pivotInAworld(0,20,46);
btVector3 pivotInAlocal = bod->worldPosToLocal(i, pivotInAworld);
btVector3 pivotInBworld = pivotInAworld;
btMultiBodyPoint2Point* p2p = new btMultiBodyPoint2Point(bod,i,&btTypedConstraint::getFixedBody(),pivotInAlocal,pivotInBworld);
world->addMultiBodyConstraint(p2p);
}
//add some constraint limit
if (settings.m_usePrismatic)
{
// btMultiBodyConstraint* con = new btMultiBodyJointLimitConstraint(bod,n_links-1,2,3);
if (settings.m_createConstraints)
{
btMultiBodyConstraint* con = new btMultiBodyJointLimitConstraint(bod,i,-1,1);
world->addMultiBodyConstraint(con);
}
} else
{
if (settings.m_createConstraints)
{
if (1)
{
btMultiBodyJointMotor* con = new btMultiBodyJointMotor(bod,i,0,0,500000);
world->addMultiBodyConstraint(con);
}
btMultiBodyConstraint* con = new btMultiBodyJointLimitConstraint(bod,i,-1,1);
world->addMultiBodyConstraint(con);
}
}
}
}
//add a collider for the base
{
btAlignedObjectArray<btQuaternion> world_to_local;
world_to_local.resize(n_links+1);
btAlignedObjectArray<btVector3> local_origin;
local_origin.resize(n_links+1);
world_to_local[0] = bod->getWorldToBaseRot();
local_origin[0] = bod->getBasePos();
//float halfExtents[3]={7.5,0.05,4.5};
btVector3 halfExtents(7.5,0.45,4.5);
{
float pos[4]={local_origin[0].x(),local_origin[0].y(),local_origin[0].z(),1};
float quat[4]={-world_to_local[0].x(),-world_to_local[0].y(),-world_to_local[0].z(),world_to_local[0].w()};
if (0)
{
btCollisionShape* box = new btBoxShape(btVector3(halfExtents[0],halfExtents[1],halfExtents[2])*scaling);
btMultiBodyLinkCollider* col= new btMultiBodyLinkCollider(bod,-1);
col->setCollisionShape(box);
btTransform tr;
tr.setIdentity();
tr.setOrigin(local_origin[0]);
tr.setRotation(btQuaternion(quat[0],quat[1],quat[2],quat[3]));
col->setWorldTransform(tr);
btVector4 color = colors[curColor++];
curColor&=3;
int index = m_glApp->m_instancingRenderer->registerGraphicsInstance(cubeShapeId,tr.getOrigin(),tr.getRotation(),color,halfExtents*scaling);
col->setUserIndex(index);
world->addCollisionObject(col,short(btBroadphaseProxy::DefaultFilter),short(btBroadphaseProxy::AllFilter));
col->setFriction(friction);
bod->setBaseCollider(col);
}
}
for (int i=0;i<bod->getNumLinks();i++)
{
const int parent = bod->getParent(i);
world_to_local[i+1] = bod->getParentToLocalRot(i) * world_to_local[parent+1];
local_origin[i+1] = local_origin[parent+1] + (quatRotate(world_to_local[i+1].inverse() , bod->getRVector(i)));
}
for (int i=0;i<bod->getNumLinks();i++)
{
btVector3 posr = local_origin[i+1];
float pos[4]={posr.x(),posr.y(),posr.z(),1};
float quat[4]={-world_to_local[i+1].x(),-world_to_local[i+1].y(),-world_to_local[i+1].z(),world_to_local[i+1].w()};
btCollisionShape* box = new btBoxShape(btVector3(halfExtents[0],halfExtents[1],halfExtents[2])*scaling);
btMultiBodyLinkCollider* col = new btMultiBodyLinkCollider(bod,i);
col->setCollisionShape(box);
btTransform tr;
tr.setIdentity();
tr.setOrigin(posr);
tr.setRotation(btQuaternion(quat[0],quat[1],quat[2],quat[3]));
col->setWorldTransform(tr);
col->setFriction(friction);
btVector4 color = colors[curColor++];
curColor&=3;
int index = m_glApp->m_instancingRenderer->registerGraphicsInstance(cubeShapeId,tr.getOrigin(),tr.getRotation(),color,halfExtents*scaling);
col->setUserIndex(index);
world->addCollisionObject(col,short(btBroadphaseProxy::DefaultFilter),short(btBroadphaseProxy::AllFilter));
bod->getLink(i).m_collider=col;
//app->drawBox(halfExtents, pos,quat);
}
}
world->addMultiBody(bod);
return bod;
}
void HingeDemo::initPhysics()
{
m_config = new btDefaultCollisionConfiguration;
m_dispatcher = new btCollisionDispatcher(m_config);
m_bp = new btDbvtBroadphase();
// btDantzigSolver* mlcp = new btDantzigSolver();
btLemkeSolver* mlcp = new btLemkeSolver();
m_solver = new btMLCPSolver(mlcp);
// m_solver = new btSequentialImpulseConstraintSolver();
//btMultiBodyConstraintSolver* solver = new btMultiBodyConstraintSolver();
//m_solver = solver;
m_dynamicsWorld = new btDiscreteDynamicsWorld(m_dispatcher,m_bp,m_solver,m_config);
//btMultiBodyDynamicsWorld* world = new btMultiBodyDynamicsWorld(m_dispatcher,m_bp,solver,m_config);
// m_dynamicsWorld = world;
m_dynamicsWorld->setDebugDrawer(new MyDebugDrawer(m_glApp));
int cubeShapeId = m_glApp->registerCubeShape();
if (1)
{
btVector4 color(0,1,0,1);
btTransform startTransform;
startTransform.setIdentity();
startTransform.setOrigin(btVector3(0,5,0));
startTransform.setRotation(btQuaternion(btVector3(0,1,0),0.2*SIMD_HALF_PI));
btVector3 halfExtents(1,1,1);
int index = m_glApp->m_instancingRenderer->registerGraphicsInstance(cubeShapeId,startTransform.getOrigin(),startTransform.getRotation(),color,halfExtents);
btBoxShape* box1 = new btBoxShape(halfExtents);
btCompoundShape* box = new btCompoundShape();
btTransform shiftTrans;shiftTrans.setIdentity();
btVector3 centerOfMassShift(0,0,0);//1.5,1.5,1.5);
shiftTrans.setOrigin(centerOfMassShift);
// shiftTrans.setRotation(btQuaternion(btVector3(0,1,0),0.2*SIMD_HALF_PI));
box->addChildShape(shiftTrans,box1);
float mass = 1.f;
btVector3 localInertia;
box->calculateLocalInertia(mass,localInertia);
//localInertia[0] = 0;
//localInertia[1] = 0;
btDefaultMotionState* motionState = new btDefaultMotionState();
motionState->m_centerOfMassOffset = shiftTrans;
motionState->setWorldTransform(startTransform);
btRigidBody* body = new btRigidBody(mass,motionState,box,localInertia);
body->setUserIndex(index);
m_dynamicsWorld->addRigidBody(body);
m_dynamicsWorld->getSolverInfo().m_splitImpulse = true;
// m_dynamicsWorld->getSolverInfo().m_erp2 = 1;
// m_dynamicsWorld->getSolverInfo().m_erp = 1;
m_dynamicsWorld->getSolverInfo().m_numIterations = 100;
bool useHinge = true;
if (useHinge)
{
btVector3 pivotInA(1,1,0);
btVector3 axisInA(0,0,1);
btHingeConstraint* hinge = new btHingeConstraint(*body,pivotInA,axisInA);
hinge->setOverrideNumSolverIterations(10);
m_dynamicsWorld->addConstraint(hinge);
} else
{
body->setLinearFactor(btVector3(0,0,0));
btVector3 ax = btVector3(0,0,1);
//body->setAngularFactor(ax);
}
}
if (1)
{
btVector4 color(0,0,1,1);
btTransform startTransform;
startTransform.setIdentity();
startTransform.setOrigin(btVector3(0,15,0));
btVector3 halfExtents(5,5,5);
int index = m_glApp->m_instancingRenderer->registerGraphicsInstance(cubeShapeId,startTransform.getOrigin(),startTransform.getRotation(),color,halfExtents);
btBoxShape* box = new btBoxShape(halfExtents);
float mass = 1000.f;
btVector3 localInertia;
box->calculateLocalInertia(mass,localInertia);
btRigidBody* body = new btRigidBody(mass,0,box,localInertia);
body->getMotionState();
body->setWorldTransform(startTransform);
body->setUserIndex(index);
m_dynamicsWorld->addRigidBody(body);
}
btMultiBodySettings2 settings;
settings.m_numLinks = 1;
// btMultiBody* multibody = createFeatherstoneHinge(world, settings);
m_glApp->m_instancingRenderer->writeTransforms();
}
void HingeDemo::renderScene()
{
// m_glApp->drawGrid();
// m_glApp->drawText("test",10,10);
//sync graphics -> physics world transforms
{
for (int i=0;i<m_dynamicsWorld->getNumCollisionObjects();i++)
{
btRigidBody* body = btRigidBody::upcast(m_dynamicsWorld->getCollisionObjectArray()[i]);
const btDefaultMotionState* state = (btDefaultMotionState*)(body ? body->getMotionState() : 0);
if (state)
{
btTransform tr = state->m_graphicsWorldTrans;
btVector3 pos = tr.getOrigin();
btQuaternion orn = tr.getRotation();
m_glApp->m_instancingRenderer->writeSingleInstanceTransformToCPU(pos,orn,i);
} else
{
btVector3 pos = m_dynamicsWorld->getCollisionObjectArray()[i]->getWorldTransform().getOrigin();
btQuaternion orn = m_dynamicsWorld->getCollisionObjectArray()[i]->getWorldTransform().getRotation();
m_glApp->m_instancingRenderer->writeSingleInstanceTransformToCPU(pos,orn,i);
}
}
m_glApp->m_instancingRenderer->writeTransforms();
}
static bool debugRender = false;
{
m_dynamicsWorld->debugDrawWorld();
}
debugRender = !debugRender ;
{
m_glApp->m_instancingRenderer->renderScene();
}
// if (debugRender)
// else
}
void HingeDemo::exitPhysics()
{
Bullet2RigidBodyDemo::exitPhysics();
}

View File

@ -0,0 +1,28 @@
#ifndef HINGE_DEMO_H
#define HINGE_DEMO_H
#include "BasicDemo.h"
class HingeDemo : public BasicDemo
{
public:
static BulletDemoInterface* MyCreateFunc(SimpleOpenGL3App* app)
{
return new HingeDemo(app);
}
HingeDemo(SimpleOpenGL3App* app);
class btMultiBody* createFeatherstoneHinge(class btMultiBodyDynamicsWorld* world, const struct btMultiBodySettings2& settings);
virtual void initPhysics();
virtual void exitPhysics();
virtual void renderScene();
};
#endif //HINGE_DEMO_H

View File

@ -0,0 +1,48 @@
#ifndef MY_DEBUG_DRAWER_H
#define MY_DEBUG_DRAWER_H
#include "LinearMath/btIDebugDraw.h"
class MyDebugDrawer : public btIDebugDraw
{
SimpleOpenGL3App* m_glApp;
int m_debugMode;
public:
MyDebugDrawer(SimpleOpenGL3App* app)
: m_glApp(app)
,m_debugMode(btIDebugDraw::DBG_DrawWireframe|btIDebugDraw::DBG_DrawAabb)
{
}
virtual void drawLine(const btVector3& from,const btVector3& to,const btVector3& color)
{
m_glApp->m_instancingRenderer->drawLine(from,to,color);
}
virtual void drawContactPoint(const btVector3& PointOnB,const btVector3& normalOnB,btScalar distance,int lifeTime,const btVector3& color)
{
}
virtual void reportErrorWarning(const char* warningString)
{
}
virtual void draw3dText(const btVector3& location,const char* textString)
{
}
virtual void setDebugMode(int debugMode)
{
m_debugMode = debugMode;
}
virtual int getDebugMode() const
{
return m_debugMode;
}
};
#endif //MY_DEBUG_DRAWER_H

View File

@ -42,6 +42,14 @@ namespace Gwen
virtual int GetNotchCount() { return m_iNumNotches; }
virtual void SetRange( float fMin, float fMax );
virtual float GetRangeMin() const
{
return m_fMin;
}
virtual float GetRangeMax() const
{
return m_fMax;
}
virtual float GetValue();
virtual void SetValue( float val, bool forceUpdate = true );

View File

@ -58,7 +58,7 @@ int main( int argc, char *argv[] )
std::cout << "\nReading MIDI input ... press <enter> to quit.\n";
char input;
std::cin.get(input);
getchar();
// getchar();
cleanup:

View File

@ -13,6 +13,13 @@
end
newoption
{
trigger = "midi",
description = "Use Midi controller to control parameters"
}
--_OPTIONS["midi"] = "1";
newoption
{
@ -95,7 +102,7 @@ include "../Demos3/SimpleOpenGL3"
-- include "../demo/gpudemo"
-- include "../btgui/MidiTest"
include "../btgui/MidiTest"
-- include "../opencl/vector_add_simplified"
-- include "../opencl/vector_add"
include "../btgui/Gwen"

View File

@ -1246,6 +1246,8 @@ void b3GpuSapBroadphase::calculateOverlappingPairs(int maxPairs)
{
b3Error("Error running out of pairs: numPairs = %d, maxPairs = %d.\n", numPairs, maxPairs);
numPairs = maxPairs;
m_pairCount.resize(0);
m_pairCount.push_back(maxPairs);
}
}

View File

@ -399,16 +399,16 @@ __kernel void computePairsKernel( __global const btAabbCL* aabbs, volatile __g
if (curNumPairs==64)
{
int curPair = atomic_add(pairCount,curNumPairs);
//avoid a buffer overrun
if ((curPair+curNumPairs)<maxPairs)
for (int p=0;p<curNumPairs;p++)
{
for (int p=0;p<curNumPairs;p++)
if ((curPair+p)<maxPairs)
{
int4 tmpPair;
tmpPair.x = myPairs[p].x;
tmpPair.y = myPairs[p].y;
tmpPair.z = NEW_PAIR_MARKER;
tmpPair.w = NEW_PAIR_MARKER;
pairsOut[curPair+p] = tmpPair; //flush to main memory
}
@ -436,17 +436,17 @@ __kernel void computePairsKernel( __global const btAabbCL* aabbs, volatile __g
{
//avoid a buffer overrun
int curPair = atomic_add(pairCount,curNumPairs);
if ((curPair+curNumPairs)<maxPairs)
for (int p=0;p<curNumPairs;p++)
{
for (int p=0;p<curNumPairs;p++)
{
if ((curPair+p)<maxPairs)
{
int4 tmpPair;
tmpPair.x = myPairs[p].x;
tmpPair.y = myPairs[p].y;
tmpPair.z = NEW_PAIR_MARKER;
tmpPair.w = NEW_PAIR_MARKER;
pairsOut[curPair+p] = tmpPair; //flush to main memory
}
}
}
curNumPairs = 0;
}

View File

@ -366,16 +366,16 @@ static const char* sapFastCL= \
" if (curNumPairs==64)\n"
" {\n"
" int curPair = atomic_add(pairCount,curNumPairs);\n"
" //avoid a buffer overrun\n"
" if ((curPair+curNumPairs)<maxPairs)\n"
" for (int p=0;p<curNumPairs;p++)\n"
" {\n"
" for (int p=0;p<curNumPairs;p++)\n"
" if ((curPair+p)<maxPairs)\n"
" {\n"
" int4 tmpPair;\n"
" tmpPair.x = myPairs[p].x;\n"
" tmpPair.y = myPairs[p].y;\n"
" tmpPair.z = NEW_PAIR_MARKER;\n"
" tmpPair.w = NEW_PAIR_MARKER;\n"
" \n"
" pairsOut[curPair+p] = tmpPair; //flush to main memory\n"
" }\n"
" }\n"
@ -402,17 +402,17 @@ static const char* sapFastCL= \
" {\n"
" //avoid a buffer overrun\n"
" int curPair = atomic_add(pairCount,curNumPairs);\n"
" if ((curPair+curNumPairs)<maxPairs)\n"
" for (int p=0;p<curNumPairs;p++)\n"
" {\n"
" for (int p=0;p<curNumPairs;p++)\n"
" {\n"
" if ((curPair+p)<maxPairs)\n"
" {\n"
" int4 tmpPair;\n"
" tmpPair.x = myPairs[p].x;\n"
" tmpPair.y = myPairs[p].y;\n"
" tmpPair.z = NEW_PAIR_MARKER;\n"
" tmpPair.w = NEW_PAIR_MARKER;\n"
" pairsOut[curPair+p] = tmpPair; //flush to main memory\n"
" }\n"
" }\n"
" }\n"
" curNumPairs = 0;\n"
" }\n"