Add setUserIndex/getUserIndex (int index) to btCollisionShape

Share physics setup of BasicDemo between different graphics frameworks, see Demos\BasicDemo\BasicDemoPhysicsSetup.*
Plan is to do this for all Bullet demos.
Improve gwen performance and cursor navigation for tree control.
tweak shadowmap size
SimpleOpenGL3App::registerCubeShape accepts half extents
This commit is contained in:
erwin coumans
2014-05-20 12:02:01 -07:00
parent f213b00022
commit eb74688c18
23 changed files with 657 additions and 303 deletions

View File

@@ -40,7 +40,7 @@ subject to the following restrictions:
static GLDebugDrawer gDebugDraw;
///The MyOverlapCallback is used to show how to collect object that overlap with a given bounding box defined by aabbMin and aabbMax.
///See m_dynamicsWorld->getBroadphase()->aabbTest.
///See m_physicsSetup.m_dynamicsWorld->getBroadphase()->aabbTest.
struct MyOverlapCallback : public btBroadphaseAabbCallback
{
btVector3 m_queryAabbMin;
@@ -68,23 +68,27 @@ void BasicDemo::clientMoveAndDisplay()
//simple dynamics world doesn't handle fixed-time-stepping
float ms = getDeltaTimeMicroseconds();
m_physicsSetup.stepSimulation(ms/1000000.f);
m_physicsSetup.m_dynamicsWorld->debugDrawWorld();
/*
///step the simulation
if (m_dynamicsWorld)
if (m_physicsSetup.m_dynamicsWorld)
{
m_dynamicsWorld->stepSimulation(ms / 1000000.f);
m_physicsSetup.m_dynamicsWorld->stepSimulation(ms / 1000000.f);
//optional but useful: debug drawing
m_dynamicsWorld->debugDrawWorld();
m_physicsSetup.m_dynamicsWorld->debugDrawWorld();
btVector3 aabbMin(1,1,1);
btVector3 aabbMax(2,2,2);
MyOverlapCallback aabbOverlap(aabbMin,aabbMax);
m_dynamicsWorld->getBroadphase()->aabbTest(aabbMin,aabbMax,aabbOverlap);
m_physicsSetup.m_dynamicsWorld->getBroadphase()->aabbTest(aabbMin,aabbMax,aabbOverlap);
//if (aabbOverlap.m_numOverlap)
// printf("#aabb overlap = %d\n", aabbOverlap.m_numOverlap);
}
*/
renderme();
glFlush();
@@ -102,8 +106,8 @@ void BasicDemo::displayCallback(void) {
renderme();
//optional but useful: debug drawing to detect problems
if (m_dynamicsWorld)
m_dynamicsWorld->debugDrawWorld();
if (m_physicsSetup.m_dynamicsWorld)
m_physicsSetup.m_dynamicsWorld->debugDrawWorld();
glFlush();
swapBuffers();
@@ -120,106 +124,11 @@ void BasicDemo::initPhysics()
setCameraDistance(btScalar(SCALING*50.));
///collision configuration contains default setup for memory, collision setup
m_collisionConfiguration = new btDefaultCollisionConfiguration();
//m_collisionConfiguration->setConvexConvexMultipointIterations();
m_physicsSetup.initPhysics();
///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 = m_physicsSetup.m_dynamicsWorld;
m_dynamicsWorld->setDebugDrawer(&gDebugDraw);
m_dynamicsWorld->setGravity(btVector3(0,-10,0));
///create a few basic rigid bodies
btBoxShape* groundShape = new btBoxShape(btVector3(btScalar(50.),btScalar(50.),btScalar(50.)));
//groundShape->initializePolyhedralFeatures();
// btCollisionShape* groundShape = new btStaticPlaneShape(btVector3(0,1,0),50);
m_collisionShapes.push_back(groundShape);
btTransform groundTransform;
groundTransform.setIdentity();
groundTransform.setOrigin(btVector3(0,-50,0));
//We can also use DemoApplication::localCreateRigidBody, but for clarity it is provided here:
{
btScalar mass(0.);
//rigidbody is dynamic if and only if mass is non zero, otherwise static
bool isDynamic = (mass != 0.f);
btVector3 localInertia(0,0,0);
if (isDynamic)
groundShape->calculateLocalInertia(mass,localInertia);
//using motionstate is recommended, it provides interpolation capabilities, and only synchronizes 'active' objects
btDefaultMotionState* myMotionState = new btDefaultMotionState(groundTransform);
btRigidBody::btRigidBodyConstructionInfo rbInfo(mass,myMotionState,groundShape,localInertia);
btRigidBody* body = new btRigidBody(rbInfo);
//add the body to the dynamics world
m_dynamicsWorld->addRigidBody(body);
}
{
//create a few dynamic rigidbodies
// Re-using the same collision is better for memory usage and performance
btBoxShape* colShape = new btBoxShape(btVector3(SCALING*1,SCALING*1,SCALING*1));
//btCollisionShape* colShape = new btSphereShape(btScalar(1.));
m_collisionShapes.push_back(colShape);
/// Create Dynamic Objects
btTransform startTransform;
startTransform.setIdentity();
btScalar mass(1.f);
//rigidbody is dynamic if and only if mass is non zero, otherwise static
bool isDynamic = (mass != 0.f);
btVector3 localInertia(0,0,0);
if (isDynamic)
colShape->calculateLocalInertia(mass,localInertia);
float start_x = START_POS_X - ARRAY_SIZE_X/2;
float start_y = START_POS_Y;
float start_z = START_POS_Z - ARRAY_SIZE_Z/2;
for (int k=0;k<ARRAY_SIZE_Y;k++)
{
for (int i=0;i<ARRAY_SIZE_X;i++)
{
for(int j = 0;j<ARRAY_SIZE_Z;j++)
{
startTransform.setOrigin(SCALING*btVector3(
btScalar(2.0*i + start_x),
btScalar(20+2.0*k + start_y),
btScalar(2.0*j + start_z)));
//using motionstate is recommended, it provides interpolation capabilities, and only synchronizes 'active' objects
btDefaultMotionState* myMotionState = new btDefaultMotionState(startTransform);
btRigidBody::btRigidBodyConstructionInfo rbInfo(mass,myMotionState,colShape,localInertia);
btRigidBody* body = new btRigidBody(rbInfo);
m_dynamicsWorld->addRigidBody(body);
}
}
}
}
}
void BasicDemo::clientResetScene()
{
@@ -230,42 +139,7 @@ void BasicDemo::clientResetScene()
void BasicDemo::exitPhysics()
{
//cleanup in the reverse order of creation/initialization
//remove the rigidbodies from the dynamics world and delete them
int i;
for (i=m_dynamicsWorld->getNumCollisionObjects()-1; i>=0 ;i--)
{
btCollisionObject* obj = m_dynamicsWorld->getCollisionObjectArray()[i];
btRigidBody* body = btRigidBody::upcast(obj);
if (body && body->getMotionState())
{
delete body->getMotionState();
}
m_dynamicsWorld->removeCollisionObject( obj );
delete obj;
}
//delete collision shapes
for (int j=0;j<m_collisionShapes.size();j++)
{
btCollisionShape* shape = m_collisionShapes[j];
delete shape;
}
m_collisionShapes.clear();
delete m_dynamicsWorld;
delete m_solver;
delete m_broadphase;
delete m_dispatcher;
delete m_collisionConfiguration;
m_physicsSetup.exitPhysics();
}

View File

@@ -24,30 +24,15 @@ subject to the following restrictions:
#endif
#include "LinearMath/btAlignedObjectArray.h"
#include "BasicDemoPhysicsSetup.h"
class btBroadphaseInterface;
class btCollisionShape;
class btOverlappingPairCache;
class btCollisionDispatcher;
class btConstraintSolver;
struct btCollisionAlgorithmCreateFunc;
class btDefaultCollisionConfiguration;
///BasicDemo is good starting point for learning the code base and porting.
class BasicDemo : public PlatformDemoApplication
{
//keep the collision shapes, for deletion/cleanup
btAlignedObjectArray<btCollisionShape*> m_collisionShapes;
btBroadphaseInterface* m_broadphase;
btCollisionDispatcher* m_dispatcher;
btConstraintSolver* m_solver;
btDefaultCollisionConfiguration* m_collisionConfiguration;
BasicDemoPhysicsSetup m_physicsSetup;
public:

View File

@@ -0,0 +1,171 @@
#include "BasicDemoPhysicsSetup.h"
#include "btBulletDynamicsCommon.h"
#define ARRAY_SIZE_Y 5
#define ARRAY_SIZE_X 5
#define ARRAY_SIZE_Z 5
void BasicDemoPhysicsSetup::initPhysics()
{
///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));
///create a few basic rigid bodies
btBoxShape* groundShape = createBoxShape(btVector3(btScalar(50.),btScalar(50.),btScalar(50.)));
//groundShape->initializePolyhedralFeatures();
// btCollisionShape* groundShape = new btStaticPlaneShape(btVector3(0,1,0),50);
m_collisionShapes.push_back(groundShape);
btTransform groundTransform;
groundTransform.setIdentity();
groundTransform.setOrigin(btVector3(0,-50,0));
{
btScalar mass(0.);
createRigidBody(mass,groundTransform,groundShape);
}
{
//create a few dynamic rigidbodies
// Re-using the same collision is better for memory usage and performance
btBoxShape* colShape = createBoxShape(btVector3(1,1,1));
//btCollisionShape* colShape = new btSphereShape(btScalar(1.));
m_collisionShapes.push_back(colShape);
/// Create Dynamic Objects
btTransform startTransform;
startTransform.setIdentity();
btScalar mass(1.f);
//rigidbody is dynamic if and only if mass is non zero, otherwise static
bool isDynamic = (mass != 0.f);
btVector3 localInertia(0,0,0);
if (isDynamic)
colShape->calculateLocalInertia(mass,localInertia);
for (int k=0;k<ARRAY_SIZE_Y;k++)
{
for (int i=0;i<ARRAY_SIZE_X;i++)
{
for(int j = 0;j<ARRAY_SIZE_Z;j++)
{
startTransform.setOrigin(btVector3(
btScalar(2.0*i),
btScalar(20+2.0*k),
btScalar(2.0*j)));
createRigidBody(mass,startTransform,colShape);
}
}
}
}
}
void BasicDemoPhysicsSetup::stepSimulation(float deltaTime)
{
m_dynamicsWorld->stepSimulation(deltaTime);
}
btBoxShape* BasicDemoPhysicsSetup::createBoxShape(const btVector3& halfExtents)
{
btBoxShape* box = new btBoxShape(halfExtents);
return box;
}
btRigidBody* BasicDemoPhysicsSetup::createRigidBody(float mass, const btTransform& startTransform,btCollisionShape* shape)
{
btAssert((!shape || shape->getShapeType() != INVALID_SHAPE_PROXYTYPE));
//rigidbody is dynamic if and only if mass is non zero, otherwise static
bool isDynamic = (mass != 0.f);
btVector3 localInertia(0,0,0);
if (isDynamic)
shape->calculateLocalInertia(mass,localInertia);
//using motionstate is recommended, it provides interpolation capabilities, and only synchronizes 'active' objects
#define USE_MOTIONSTATE 1
#ifdef USE_MOTIONSTATE
btDefaultMotionState* myMotionState = new btDefaultMotionState(startTransform);
btRigidBody::btRigidBodyConstructionInfo cInfo(mass,myMotionState,shape,localInertia);
btRigidBody* body = new btRigidBody(cInfo);
//body->setContactProcessingThreshold(m_defaultContactProcessingThreshold);
#else
btRigidBody* body = new btRigidBody(mass,0,shape,localInertia);
body->setWorldTransform(startTransform);
#endif//
body->setUserIndex(-1);
m_dynamicsWorld->addRigidBody(body);
return body;
}
void BasicDemoPhysicsSetup::exitPhysics()
{
//cleanup in the reverse order of creation/initialization
//remove the rigidbodies from the dynamics world and delete them
int i;
for (i=m_dynamicsWorld->getNumCollisionObjects()-1; i>=0 ;i--)
{
btCollisionObject* obj = m_dynamicsWorld->getCollisionObjectArray()[i];
btRigidBody* body = btRigidBody::upcast(obj);
if (body && body->getMotionState())
{
delete body->getMotionState();
}
m_dynamicsWorld->removeCollisionObject( obj );
delete obj;
}
//delete collision shapes
for (int j=0;j<m_collisionShapes.size();j++)
{
btCollisionShape* shape = m_collisionShapes[j];
delete shape;
}
m_collisionShapes.clear();
delete m_dynamicsWorld;
delete m_solver;
delete m_broadphase;
delete m_dispatcher;
delete m_collisionConfiguration;
}

View File

@@ -0,0 +1,94 @@
#ifndef BASIC_DEMO_PHYSICS_SETUP_H
#define BASIC_DEMO_PHYSICS_SETUP_H
class btRigidBody;
class btCollisionShape;
class btBroadphaseInterface;
class btConstraintSolver;
class btCollisionDispatcher;
class btDefaultCollisionConfiguration;
class btDiscreteDynamicsWorld;
class btTransform;
class btVector3;
class btBoxShape;
#include "LinearMath/btAlignedObjectArray.h"
struct BasicDemoPhysicsSetup
{
//keep the collision shapes, for deletion/cleanup
btAlignedObjectArray<btCollisionShape*> m_collisionShapes;
btBroadphaseInterface* m_broadphase;
btCollisionDispatcher* m_dispatcher;
btConstraintSolver* m_solver;
btDefaultCollisionConfiguration* m_collisionConfiguration;
btDiscreteDynamicsWorld* m_dynamicsWorld;
virtual void initPhysics();
virtual void exitPhysics();
virtual void stepSimulation(float deltaTime);
virtual btRigidBody* createRigidBody(float mass, const btTransform& startTransform,btCollisionShape* shape);
virtual btBoxShape* createBoxShape(const btVector3& halfExtents);
/*
//bodies
virtual btRigidBody* createRigidBody(bool isDynamic, btScalar mass, const btTransform& startTransform, btCollisionShape* shape,const char* bodyName);
virtual btCollisionObject* createCollisionObject( const btTransform& startTransform, btCollisionShape* shape,const char* bodyName);
///shapes
virtual btCollisionShape* createPlaneShape(const btVector3& planeNormal,btScalar planeConstant);
virtual btCollisionShape* createSphereShape(btScalar radius);
virtual btCollisionShape* createCapsuleShapeX(btScalar radius, btScalar height);
virtual btCollisionShape* createCapsuleShapeY(btScalar radius, btScalar height);
virtual btCollisionShape* createCapsuleShapeZ(btScalar radius, btScalar height);
virtual btCollisionShape* createCylinderShapeX(btScalar radius,btScalar height);
virtual btCollisionShape* createCylinderShapeY(btScalar radius,btScalar height);
virtual btCollisionShape* createCylinderShapeZ(btScalar radius,btScalar height);
virtual btCollisionShape* createConeShapeX(btScalar radius,btScalar height);
virtual btCollisionShape* createConeShapeY(btScalar radius,btScalar height);
virtual btCollisionShape* createConeShapeZ(btScalar radius,btScalar height);
virtual class btTriangleIndexVertexArray* createTriangleMeshContainer();
virtual btBvhTriangleMeshShape* createBvhTriangleMeshShape(btStridingMeshInterface* trimesh, btOptimizedBvh* bvh);
virtual btCollisionShape* createConvexTriangleMeshShape(btStridingMeshInterface* trimesh);
virtual btGImpactMeshShape* createGimpactShape(btStridingMeshInterface* trimesh);
virtual btStridingMeshInterfaceData* createStridingMeshInterfaceData(btStridingMeshInterfaceData* interfaceData);
virtual class btConvexHullShape* createConvexHullShape();
virtual class btCompoundShape* createCompoundShape();
virtual class btScaledBvhTriangleMeshShape* createScaledTrangleMeshShape(btBvhTriangleMeshShape* meshShape,const btVector3& localScalingbtBvhTriangleMeshShape);
virtual class btMultiSphereShape* createMultiSphereShape(const btVector3* positions,const btScalar* radi,int numSpheres);
virtual btTriangleIndexVertexArray* createMeshInterface(btStridingMeshInterfaceData& meshData);
///acceleration and connectivity structures
virtual btOptimizedBvh* createOptimizedBvh();
virtual btTriangleInfoMap* createTriangleInfoMap();
///constraints
virtual btPoint2PointConstraint* createPoint2PointConstraint(btRigidBody& rbA,btRigidBody& rbB, const btVector3& pivotInA,const btVector3& pivotInB);
virtual btPoint2PointConstraint* createPoint2PointConstraint(btRigidBody& rbA,const btVector3& pivotInA);
virtual btHingeConstraint* createHingeConstraint(btRigidBody& rbA,btRigidBody& rbB, const btTransform& rbAFrame, const btTransform& rbBFrame, bool useReferenceFrameA=false);
virtual btHingeConstraint* createHingeConstraint(btRigidBody& rbA,const btTransform& rbAFrame, bool useReferenceFrameA=false);
virtual btConeTwistConstraint* createConeTwistConstraint(btRigidBody& rbA,btRigidBody& rbB,const btTransform& rbAFrame, const btTransform& rbBFrame);
virtual btConeTwistConstraint* createConeTwistConstraint(btRigidBody& rbA,const btTransform& rbAFrame);
virtual btGeneric6DofConstraint* createGeneric6DofConstraint(btRigidBody& rbA, btRigidBody& rbB, const btTransform& frameInA, const btTransform& frameInB ,bool useLinearReferenceFrameA);
virtual btGeneric6DofConstraint* createGeneric6DofConstraint(btRigidBody& rbB, const btTransform& frameInB, bool useLinearReferenceFrameB);
virtual btGeneric6DofSpringConstraint* createGeneric6DofSpringConstraint(btRigidBody& rbA, btRigidBody& rbB, const btTransform& frameInA, const btTransform& frameInB ,bool useLinearReferenceFrameA);
virtual btSliderConstraint* createSliderConstraint(btRigidBody& rbA, btRigidBody& rbB, const btTransform& frameInA, const btTransform& frameInB ,bool useLinearReferenceFrameA);
virtual btSliderConstraint* createSliderConstraint(btRigidBody& rbB, const btTransform& frameInB, bool useLinearReferenceFrameA);
virtual btGearConstraint* createGearConstraint(btRigidBody& rbA, btRigidBody& rbB, const btVector3& axisInA,const btVector3& axisInB, btScalar ratio);
*/
};
#endif //BASIC_DEMO_PHYSICS_SETUP_H

View File

@@ -28,6 +28,8 @@ ADD_EXECUTABLE(AppBasicDemo
main.cpp
BasicDemo.cpp
BasicDemo.h
BasicDemoPhysicsSetup.cpp
BasicDemoPhysicsSetup.h
${BULLET_PHYSICS_SOURCE_DIR}/build3/bullet.rc
)
ELSE()
@@ -35,6 +37,8 @@ ELSE()
main.cpp
BasicDemo.cpp
BasicDemo.h
BasicDemoPhysicsSetup.cpp
BasicDemoPhysicsSetup.h
)
ENDIF()
ELSE (USE_GLUT)
@@ -52,6 +56,8 @@ ELSE (USE_GLUT)
Win32BasicDemo.cpp
BasicDemo.cpp
BasicDemo.h
BasicDemoPhysicsSetup.cpp
BasicDemoPhysicsSetup.h
${BULLET_PHYSICS_SOURCE_DIR}/build3/bullet.rc
)

View File

@@ -12,6 +12,8 @@ SET(App_AllBullet2Demos_SRCS
BulletDemoEntries.h
../bullet2/BasicDemo/Bullet2RigidBodyDemo.cpp
../bullet2/BasicDemo/Bullet2RigidBodyDemo.h
../../Demos/BasicDemo/BasicDemoPhysicsSetup.cpp
../../Demos/BasicDemo/BasicDemoPhysicsSetup.h
../bullet2/FeatherstoneMultiBodyDemo/BulletMultiBodyDemos.cpp
../bullet2/FeatherstoneMultiBodyDemo/BulletMultiBodyDemos.h
../bullet2/FeatherstoneMultiBodyDemo/MultiDofDemo.cpp

View File

@@ -217,7 +217,7 @@ int main(int argc, char* argv[])
app->swapBuffer();
} while (!app->m_window->requestedExit());
selectDemo(0);
// selectDemo(0);
delete gui;
delete app;
return 0;

View File

@@ -23,6 +23,8 @@
"**.h",
"../bullet2/BasicDemo/Bullet2RigidBodyDemo.cpp",
"../bullet2/BasicDemo/Bullet2RigidBodyDemo.h",
"../../Demos/BasicDemo/BasicDemoPhysicsSetup.cpp",
"../../Demos/BasicDemo/BasicDemoPhysicsSetup.h",
"../bullet2/FeatherstoneMultiBodyDemo/BulletMultiBodyDemos.cpp",
"../bullet2/FeatherstoneMultiBodyDemo/BulletMultiBodyDemos.h",
"../bullet2/FeatherstoneMultiBodyDemo/MultiDofDemo.cpp",

View File

@@ -32,6 +32,7 @@ void BasicDemo::createGround(int cubeShapeId)
groundTransform.setIdentity();
groundTransform.setOrigin(btVector3(0,-50,0));
m_glApp->m_instancingRenderer->registerGraphicsInstance(cubeShapeId,groundTransform.getOrigin(),groundTransform.getRotation(),color,halfExtents);
btBoxShape* groundShape = new btBoxShape(btVector3(btScalar(halfExtents[0]),btScalar(halfExtents[1]),btScalar(halfExtents[2])));
//We can also use DemoApplication::localCreateRigidBody, but for clarity it is provided here:
{
@@ -52,88 +53,60 @@ void BasicDemo::createGround(int cubeShapeId)
}
void BasicDemo::initPhysics()
{
// Bullet2RigidBodyDemo::initPhysics();
m_config = new btDefaultCollisionConfiguration;
m_dispatcher = new btCollisionDispatcher(m_config);
m_bp = new btDbvtBroadphase();
m_solver = new btNNCGConstraintSolver();
m_dynamicsWorld = new btDiscreteDynamicsWorld(m_dispatcher,m_bp,m_solver,m_config);
int curColor=0;
//create ground
int cubeShapeId = m_glApp->registerCubeShape();
float pos[]={0,0,0};
float orn[]={0,0,0,1};
createGround(cubeShapeId);
{
btVector4 halfExtents(scaling,scaling,scaling,1);
btVector4 colors[4] =
{
btVector4(1,0,0,1),
btVector4(0,1,0,1),
btVector4(0,1,1,1),
btVector4(1,1,0,1),
};
btTransform startTransform;
startTransform.setIdentity();
btScalar mass = 1.f;
btVector3 localInertia;
btBoxShape* colShape = new btBoxShape(btVector3(halfExtents[0],halfExtents[1],halfExtents[2]));
colShape ->calculateLocalInertia(mass,localInertia);
for (int k=0;k<ARRAY_SIZE_Y;k++)
{
for (int i=0;i<ARRAY_SIZE_X;i++)
{
for(int j = 0;j<ARRAY_SIZE_Z;j++)
{
btVector4 color = colors[curColor];
curColor++;
curColor&=3;
startTransform.setOrigin(btVector3(
btScalar(2.0*scaling*i),
btScalar(2.*scaling+2.0*scaling*k),
btScalar(2.0*scaling*j)));
m_glApp->m_instancingRenderer->registerGraphicsInstance(cubeShapeId,startTransform.getOrigin(),startTransform.getRotation(),color,halfExtents);
//using motionstate is recommended, it provides interpolation capabilities, and only synchronizes 'active' objects
btDefaultMotionState* myMotionState = new btDefaultMotionState(startTransform);
btRigidBody::btRigidBodyConstructionInfo rbInfo(mass,myMotionState,colShape,localInertia);
btRigidBody* body = new btRigidBody(rbInfo);
m_dynamicsWorld->addRigidBody(body);
}
}
}
}
m_physicsSetup.m_glApp = m_glApp;
m_physicsSetup.initPhysics();
m_dynamicsWorld = m_physicsSetup.m_dynamicsWorld;
m_glApp->m_instancingRenderer->writeTransforms();
}
void BasicDemo::exitPhysics()
{
Bullet2RigidBodyDemo::exitPhysics();
m_physicsSetup.exitPhysics();
m_dynamicsWorld = 0;
//Bullet2RigidBodyDemo::exitPhysics();
}
//SimpleOpenGL3App* m_glApp;
btRigidBody* MyBasicDemoPhysicsSetup::createRigidBody(float mass, const btTransform& startTransform,btCollisionShape* shape)
{
btRigidBody* body = BasicDemoPhysicsSetup::createRigidBody(mass,startTransform,shape);
int graphicsShapeId = shape->getUserIndex();
btAssert(graphicsShapeId>=0);
btVector3 localScaling = shape->getLocalScaling();
float color[]={0.3,0.3,1,1};
int graphicsInstanceId = m_glApp->m_instancingRenderer->registerGraphicsInstance(graphicsShapeId,startTransform.getOrigin(),startTransform.getRotation(),color,localScaling);
body->setUserIndex(graphicsInstanceId);
//todo: create graphics representation
return body;
}
btBoxShape* MyBasicDemoPhysicsSetup::createBoxShape(const btVector3& halfExtents)
{
btBoxShape* box = BasicDemoPhysicsSetup::createBoxShape(halfExtents);
int cubeShapeId = m_glApp->registerCubeShape(halfExtents.x(),halfExtents.y(),halfExtents.z());
box->setUserIndex(cubeShapeId);
//todo: create graphics representation
return box;
}
void BasicDemo::renderScene()
{
//sync graphics -> physics world transforms
{
for (int i=0;i<m_dynamicsWorld->getNumCollisionObjects();i++)
{
btVector3 pos = m_dynamicsWorld->getCollisionObjectArray()[i]->getWorldTransform().getOrigin();
btQuaternion orn = m_dynamicsWorld->getCollisionObjectArray()[i]->getWorldTransform().getRotation();
m_glApp->m_instancingRenderer->writeSingleInstanceTransformToCPU(pos,orn,i);
btCollisionObject* colObj = m_dynamicsWorld->getCollisionObjectArray()[i];
btVector3 pos = colObj->getWorldTransform().getOrigin();
btQuaternion orn = colObj->getWorldTransform().getRotation();
int index = colObj ->getUserIndex();
if (index>=0)
{
m_glApp->m_instancingRenderer->writeSingleInstanceTransformToCPU(pos,orn,index);
}
}
m_glApp->m_instancingRenderer->writeTransforms();
}
@@ -144,7 +117,10 @@ void BasicDemo::renderScene()
void BasicDemo::stepSimulation(float dt)
{
m_dynamicsWorld->stepSimulation(dt);
m_physicsSetup.stepSimulation(dt);
m_physicsSetup.m_dynamicsWorld->debugDrawWorld();
/*
//print applied force

View File

@@ -4,11 +4,23 @@
#include "LinearMath/btVector3.h"
#include "Bullet2RigidBodyDemo.h"
#include "../../../Demos/BasicDemo/BasicDemoPhysicsSetup.h"
struct MyBasicDemoPhysicsSetup : public BasicDemoPhysicsSetup
{
SimpleOpenGL3App* m_glApp;
virtual btRigidBody* createRigidBody(float mass, const btTransform& startTransform,btCollisionShape* shape);
virtual btBoxShape* createBoxShape(const btVector3& halfExtents);
};
class BasicDemo : public Bullet2RigidBodyDemo
{
MyBasicDemoPhysicsSetup m_physicsSetup;
public:
static BulletDemoInterface* MyCreateFunc(SimpleOpenGL3App* app)

View File

@@ -105,6 +105,8 @@ void Base::Invalidate()
{
m_bNeedsLayout = true;
m_bCacheTextureDirty = true;
extern int avoidUpdate;
avoidUpdate = -3;
}
void Base::DelayedDelete()
@@ -403,12 +405,13 @@ void Base::OnBoundsChanged(Gwen::Rect oldBounds)
//Anything that needs to update on size changes
//Iterate my children and tell them I've changed
//
if ( GetParent() )
GetParent()->OnChildBoundsChanged( oldBounds, this );
if ( m_Bounds.w != oldBounds.w || m_Bounds.h != oldBounds.h )
{
if ( GetParent() )
GetParent()->OnChildBoundsChanged( oldBounds, this );
Invalidate();
}
@@ -694,6 +697,8 @@ void Base::Layout( Skin::Base* skin )
skin->GetRender()->GetCTT()->CreateControlCacheTexture( this );
}
int avoidUpdate = -15;
void Base::RecurseLayout( Skin::Base* skin )
{
if ( m_Skin ) skin = m_Skin;
@@ -705,6 +710,10 @@ void Base::RecurseLayout( Skin::Base* skin )
Layout( skin );
}
if (avoidUpdate>0)
return;
Gwen::Rect rBounds = GetRenderBounds();
// Adjust bounds for padding
@@ -713,13 +722,21 @@ void Base::RecurseLayout( Skin::Base* skin )
rBounds.y += m_Padding.top;
rBounds.h -= m_Padding.top + m_Padding.bottom;
int sz = Children.size();
if (sz>100)
{
// printf("!\n");
}
int curChild = 0;
for (Base::List::iterator iter = Children.begin(); iter != Children.end(); ++iter)
{
Base* pChild = *iter;
curChild++;
if ( pChild->Hidden() )
continue;
int iDock = pChild->GetDock();
if ( iDock & Pos::Fill )
@@ -768,10 +785,12 @@ void Base::RecurseLayout( Skin::Base* skin )
}
pChild->RecurseLayout( skin );
}
m_InnerBounds = rBounds;
curChild = 0;
//
// Fill uses the left over space, so do that now.
//
@@ -779,10 +798,12 @@ void Base::RecurseLayout( Skin::Base* skin )
{
Base* pChild = *iter;
int iDock = pChild->GetDock();
curChild++;
if ( !(iDock & Pos::Fill) )
continue;
const Margin& margin = pChild->GetMargin();
pChild->SetBounds( rBounds.x + margin.left, rBounds.y + margin.top, rBounds.w - margin.left - margin.right, rBounds.h - margin.top - margin.bottom );

View File

@@ -164,19 +164,43 @@ namespace Gwen
virtual void RestrictToParent( bool restrict ) { m_bRestrictToParent = restrict; }
virtual bool ShouldRestrictToParent() { return m_bRestrictToParent; }
virtual int X() const { return m_Bounds.x; }
virtual int Y() const { return m_Bounds.y; }
virtual int Width() const { return m_Bounds.w; }
virtual int Height() const { return m_Bounds.h; }
virtual int Bottom() const { return m_Bounds.y + m_Bounds.h + m_Margin.bottom; }
virtual int Right() const { return m_Bounds.x + m_Bounds.w + m_Margin.right; }
virtual int X() const
{
return m_Bounds.x;
}
virtual int Y() const
{
return m_Bounds.y;
}
virtual int Width() const
{
return m_Bounds.w;
}
virtual int Height() const
{
return m_Bounds.h;
}
virtual int Bottom() const
{
return m_Bounds.y + m_Bounds.h + m_Margin.bottom;
}
virtual int Right() const
{
return m_Bounds.x + m_Bounds.w + m_Margin.right;
}
virtual const Margin& GetMargin() const { return m_Margin; }
virtual const Padding& GetPadding() const { return m_Padding; }
virtual void SetPos( int x, int y );
virtual void SetWidth( int w ) { SetSize( w, Height()); }
virtual void SetHeight( int h ) { SetSize( Width(), h); }
virtual void SetWidth( int w )
{
SetSize( w, Height());
}
virtual void SetHeight( int h )
{
SetSize( Width(), h);
}
virtual bool SetSize( int w, int h );
virtual bool SetBounds( int x, int y, int w, int h );
virtual bool SetBounds( const Gwen::Rect& bounds );
@@ -188,7 +212,10 @@ namespace Gwen
virtual void MoveTo (int x, int y );
virtual void MoveBy (int x, int y );
virtual const Gwen::Rect& GetBounds() const { return m_Bounds; }
virtual const Gwen::Rect& GetBounds() const
{
return m_Bounds;
}
virtual Controls::Base* GetControlAt( int x, int y );

View File

@@ -61,6 +61,16 @@ namespace Gwen
Gwen::Event::Caller onBarMoved;
float getContentSize()
{
return m_fContentSize;
}
float getViewableContentSize() const
{
return m_fViewableContentSize;
}
protected:
ControlsInternal::ScrollBarButton* m_ScrollButton[2];

View File

@@ -42,11 +42,16 @@ void TreeControl::Render( Skin::Base* skin )
skin->DrawTreeControl( this );
}
void TreeControl::OnChildBoundsChanged( Gwen::Rect /*oldChildBounds*/, Base* /*pChild*/ )
void TreeControl::ForceUpdateScrollBars()
{
m_ScrollControl->UpdateScrollBars();
}
void TreeControl::OnChildBoundsChanged( Gwen::Rect /*oldChildBounds*/, Base* /*pChild*/ )
{
//m_ScrollControl->UpdateScrollBars();
}
void TreeControl::Clear()
{
m_ScrollControl->Clear();
@@ -74,7 +79,7 @@ void TreeControl::OnNodeSelection( Controls::Base* /*control*/ )
}
void TreeControl::iterate(int action, int* curIndex, int* targetIndex)
void TreeControl::iterate(int action, int* maxItem, int* curItem)
{
Base::List& children = m_InnerPanel->GetChildren();
@@ -83,7 +88,7 @@ void TreeControl::iterate(int action, int* curIndex, int* targetIndex)
TreeNode* pChild = (*iter)->DynamicCastTreeNode();
if ( !pChild )
continue;
pChild->iterate(action ,curIndex, targetIndex);
pChild->iterate(action ,maxItem, curItem);
}
}
@@ -93,26 +98,52 @@ bool TreeControl::OnKeyUp( bool bDown )
{
if (bDown)
{
ForceUpdateScrollBars();
int maxIndex = 0;
int newIndex = 0;
int curIndex=0;
int targetIndex=-1;
iterate(ITERATE_ACTION_FIND_SELECTED_INDEX,&curIndex,&targetIndex);
maxIndex = curIndex;
if (targetIndex>0)
int maxItem=0;
int curItem=-1;
iterate(ITERATE_ACTION_FIND_SELECTED_INDEX,&maxItem,&curItem);
maxIndex = maxItem;
int targetItem = curItem;
if (curItem>0)
{
curIndex=0;
int deselectIndex = targetIndex;
targetIndex--;
newIndex = targetIndex;
iterate(ITERATE_ACTION_SELECT,&curIndex,&targetIndex);
if (targetIndex<0)
maxItem=0;
int deselectIndex = targetItem;
targetItem--;
newIndex = targetItem;
iterate(ITERATE_ACTION_SELECT,&maxItem,&targetItem);
if (targetItem<0)
{
curIndex=0;
iterate(ITERATE_ACTION_DESELECT_INDEX,&curIndex,&deselectIndex);
maxItem=0;
iterate(ITERATE_ACTION_DESELECT_INDEX,&maxItem,&deselectIndex);
}
curItem = newIndex;
float amount = float(newIndex)/float(maxIndex);
m_ScrollControl->m_VerticalScrollBar->SetScrolledAmount(amount,true);
float viewSize = m_ScrollControl->m_VerticalScrollBar->getViewableContentSize();
float contSize = m_ScrollControl->m_VerticalScrollBar->getContentSize();
float curAmount = m_ScrollControl->m_VerticalScrollBar->GetScrolledAmount();
float minCoordViewableWindow = curAmount*contSize;
float maxCoordViewableWindow = minCoordViewableWindow+viewSize;
float minCoordSelectedItem = curItem*16.f;
float maxCoordSelectedItem = (curItem+1)*16.f;
{
float newAmount = float(minCoordSelectedItem)/(contSize-viewSize);
if (newAmount<curAmount)
{
m_ScrollControl->m_VerticalScrollBar->SetScrolledAmount(newAmount,true);
}
}
{
int numItems = (viewSize)/16-1;
float newAmount = float((curItem-numItems)*16)/(contSize-viewSize);
if (newAmount>curAmount)
{
m_ScrollControl->m_VerticalScrollBar->SetScrolledAmount(newAmount,true);
}
}
}
}
return true;
@@ -123,26 +154,52 @@ bool TreeControl::OnKeyDown( bool bDown )
{
if (bDown)
{
ForceUpdateScrollBars();
int maxIndex = 0;
int newIndex = 0;
int curIndex=0;
int targetIndex=-1;
iterate(ITERATE_ACTION_FIND_SELECTED_INDEX,&curIndex,&targetIndex);
maxIndex = curIndex;
if (targetIndex>=0)
int maxItem=0;
int curItem=-1;
iterate(ITERATE_ACTION_FIND_SELECTED_INDEX,&maxItem,&curItem);
maxIndex = maxItem;
int targetItem = curItem;
if (curItem>=0)
{
curIndex=0;
int deselectIndex = targetIndex;
targetIndex++;
newIndex = targetIndex;
iterate(ITERATE_ACTION_SELECT,&curIndex,&targetIndex);
if (targetIndex<0)
maxItem=0;
int deselectIndex = targetItem;
targetItem++;
newIndex = targetItem;
iterate(ITERATE_ACTION_SELECT,&maxItem,&targetItem);
if (targetItem<0)
{
curIndex=0;
iterate(ITERATE_ACTION_DESELECT_INDEX,&curIndex,&deselectIndex);
maxItem=0;
iterate(ITERATE_ACTION_DESELECT_INDEX,&maxItem,&deselectIndex);
}
curItem= newIndex;
float amount = (int)float(newIndex)/float(maxIndex);
float viewSize = m_ScrollControl->m_VerticalScrollBar->getViewableContentSize();
float contSize = m_ScrollControl->m_VerticalScrollBar->getContentSize();
float curAmount = m_ScrollControl->m_VerticalScrollBar->GetScrolledAmount();
float minCoordViewableWindow = curAmount*contSize;
float maxCoordViewableWindow = minCoordViewableWindow+viewSize;
float minCoordSelectedItem = curItem*16.f;
float maxCoordSelectedItem = (curItem+1)*16.f;
{
float newAmount = float(minCoordSelectedItem)/(contSize-viewSize);
if (newAmount<curAmount)
{
m_ScrollControl->m_VerticalScrollBar->SetScrolledAmount(newAmount,true);
}
}
{
int numItems = (viewSize)/16-1;
float newAmount = float((curItem-numItems)*16)/(contSize-viewSize);
if (newAmount>curAmount)
{
m_ScrollControl->m_VerticalScrollBar->SetScrolledAmount(newAmount,true);
}
}
float amount = float(newIndex)/float(maxIndex);
m_ScrollControl->m_VerticalScrollBar->SetScrolledAmount(amount,true);
}
}
return true;
@@ -153,12 +210,39 @@ bool TreeControl::OnKeyRight( bool bDown )
{
if (bDown)
{
extern int avoidUpdate;
avoidUpdate = -3;
ForceUpdateScrollBars();
iterate(ITERATE_ACTION_OPEN,0,0);
int curIndex=0;
int targetIndex=0;
iterate(ITERATE_ACTION_FIND_SELECTED_INDEX,&curIndex,&targetIndex);
float amount = float(targetIndex)/float(curIndex);
m_ScrollControl->m_VerticalScrollBar->SetScrolledAmount(amount,true);
int maxItem=0;
int curItem=0;
iterate(ITERATE_ACTION_FIND_SELECTED_INDEX,&maxItem,&curItem);
float amount = float(curItem)/float(maxItem);
float viewSize = m_ScrollControl->m_VerticalScrollBar->getViewableContentSize();
float contSize = m_ScrollControl->m_VerticalScrollBar->getContentSize();
float curAmount = m_ScrollControl->m_VerticalScrollBar->GetScrolledAmount();
float minCoordViewableWindow = curAmount*contSize;
float maxCoordViewableWindow = minCoordViewableWindow+viewSize;
float minCoordSelectedItem = curItem*16.f;
float maxCoordSelectedItem = (curItem+1)*16.f;
{
float newAmount = float(minCoordSelectedItem)/(contSize-viewSize);
if (newAmount<curAmount)
{
m_ScrollControl->m_VerticalScrollBar->SetScrolledAmount(newAmount,true);
}
}
{
int numItems = (viewSize)/16-1;
float newAmount = float((curItem-numItems)*16)/(contSize-viewSize);
if (newAmount>curAmount)
{
m_ScrollControl->m_VerticalScrollBar->SetScrolledAmount(newAmount,true);
}
}
Invalidate();
}
return true;
}
@@ -166,13 +250,51 @@ bool TreeControl::OnKeyLeft( bool bDown )
{
if (bDown)
{
extern int avoidUpdate;
avoidUpdate = -3;
ForceUpdateScrollBars();
iterate(ITERATE_ACTION_CLOSE,0,0);
int curIndex=0;
int targetIndex=0;
iterate(ITERATE_ACTION_FIND_SELECTED_INDEX,&curIndex,&targetIndex);
float amount = float(targetIndex)/float(curIndex);
m_ScrollControl->m_VerticalScrollBar->SetScrolledAmount(amount,true);
int maxItems=0;
int curItem=0;
iterate(ITERATE_ACTION_FIND_SELECTED_INDEX,&maxItems,&curItem);
float amount = float(curItem)/float(maxItems);
// m_ScrollControl->m_VerticalScrollBar->SetScrolledAmount(amount,true);
float viewSize = m_ScrollControl->m_VerticalScrollBar->getViewableContentSize();
float contSize = m_ScrollControl->m_VerticalScrollBar->getContentSize();
float curAmount = m_ScrollControl->m_VerticalScrollBar->GetScrolledAmount();
float minCoordViewableWindow = curAmount*contSize;
float maxCoordViewableWindow = minCoordViewableWindow+viewSize;
float minCoordSelectedItem = curItem*16.f;
float maxCoordSelectedItem = (curItem+1)*16.f;
{
float newAmount = float(minCoordSelectedItem)/(contSize-viewSize);
if (newAmount<curAmount)
{
m_ScrollControl->m_VerticalScrollBar->SetScrolledAmount(newAmount,true);
}
}
{
int numItems = (viewSize)/16-1;
float newAmount = float((curItem-numItems)*16)/(contSize-viewSize);
if (newAmount>curAmount)
{
m_ScrollControl->m_VerticalScrollBar->SetScrolledAmount(newAmount,true);
}
Invalidate();
}
//viewSize/contSize
printf("!\n");
//this->Layout(0);
}
return true;

View File

@@ -43,6 +43,7 @@ namespace Gwen
virtual void iterate(int action,int* curIndex, int* resultIndex);
virtual void ForceUpdateScrollBars();
private:

View File

@@ -73,6 +73,7 @@ void TreeNode::Render( Skin::Base* skin )
TreeNode* TreeNode::AddNode( const UnicodeString& strLabel )
{
int sz = sizeof(TreeNode);
TreeNode* node = new TreeNode( this );
node->SetText( strLabel );
node->Dock( Pos::Top );
@@ -112,9 +113,16 @@ void TreeNode::Layout( Skin::Base* skin )
BaseClass::Layout( skin );
}
//too many calls to PostLayout...
//int numCalls = 0xfd;
void TreeNode::PostLayout( Skin::Base* /*skin*/ )
{
//int bla = numCalls&0xffff;
//if (bla==0)
// printf("TreeNode::PostLayout numCalls = %d\n", numCalls);
//numCalls++;
if ( SizeToChildren( false, true ) )
{
InvalidateParent();

View File

@@ -456,6 +456,9 @@ int main()
pCanvas->RenderCanvas();
extern int avoidUpdate;
if (avoidUpdate<=0)
avoidUpdate++;
// SwapBuffers( GetDC( g_pHWND ) );
}

View File

@@ -84,8 +84,10 @@ GWEN_CONTROL_CONSTRUCTOR( UnitTest )
ctrl->Focus();
ctrl->SetKeyboardInputEnabled(true);
ctrl->SetBounds( 30, 30, 200, 200 );
ctrl->ExpandAll();
ctrl->SetBounds( 30, 30, 200, 30+16*10 );
//ctrl->ExpandAll();
ctrl->ForceUpdateScrollBars();
ctrl->OnKeyDown(true);
}

View File

@@ -16,9 +16,9 @@ subject to the following restrictions:
///todo: make this configurable in the gui
bool useShadowMap=true;
float shadowMapWidth=16384;
float shadowMapHeight=16384;
float shadowMapWorldSize=1000;
float shadowMapWidth=8192;
float shadowMapHeight=8192;
float shadowMapWorldSize=200;
float WHEEL_MULTIPLIER=0.01f;
float MOUSE_MOVE_MULTIPLIER = 0.4f;
#define MAX_POINTS_IN_BATCH 1024

View File

@@ -86,14 +86,14 @@ public:
{
float pos[4];
float orn[4];
pos[0] = position[0];
pos[1] = position[1];
pos[2] = position[2];
pos[3] = position[3];
orn[0] =orientation[0];
orn[1] =orientation[1];
orn[2] =orientation[2];
orn[3] =orientation[3];
pos[0] = (float)position[0];
pos[1] = (float)position[1];
pos[2] = (float)position[2];
pos[3] = (float)position[3];
orn[0] =(float)orientation[0];
orn[1] =(float)orientation[1];
orn[2] =(float)orientation[2];
orn[3] =(float)orientation[3];
writeSingleInstanceTransformToCPU(pos,orn,srcIndex);
}

View File

@@ -210,12 +210,35 @@ void SimpleOpenGL3App::drawText( const char* txt, int posX, int posY)
glDisable(GL_BLEND);
}
int SimpleOpenGL3App::registerCubeShape()
int SimpleOpenGL3App::registerCubeShape(float halfExtentsX,float halfExtentsY, float halfExtentsZ)
{
struct GfxVertex
{
float x,y,z,w;
float nx,ny,nz;
float u,v;
};
int strideInBytes = 9*sizeof(float);
int numVertices = sizeof(cube_vertices)/strideInBytes;
int numIndices = sizeof(cube_indices)/sizeof(int);
int shapeId = m_instancingRenderer->registerShape(&cube_vertices[0],numVertices,cube_indices,numIndices);
b3AlignedObjectArray<GfxVertex> verts;
verts.resize(numVertices);
for (int i=0;i<numVertices;i++)
{
verts[i].x = halfExtentsX*cube_vertices[i*9];
verts[i].y = halfExtentsY*cube_vertices[i*9+1];
verts[i].z = halfExtentsZ*cube_vertices[i*9+2];
verts[i].w = cube_vertices[i*9+3];
verts[i].nx = cube_vertices[i*9+4];
verts[i].ny = cube_vertices[i*9+5];
verts[i].nz = cube_vertices[i*9+6];
verts[i].u = cube_vertices[i*9+7];
verts[i].v = cube_vertices[i*9+8];
}
int shapeId = m_instancingRenderer->registerShape(&verts[0].x,numVertices,cube_indices,numIndices);
return shapeId;
}

View File

@@ -16,7 +16,7 @@ struct SimpleOpenGL3App
SimpleOpenGL3App(const char* title, int width,int height);
virtual ~SimpleOpenGL3App();
int registerCubeShape();
int registerCubeShape(float halfExtentsX=1.f,float halfExtentsY=1.f, float halfExtentsZ = 1.f);
int registerGraphicsSphereShape(float radius, bool usePointSprites=true, int largeSphereThreshold=100, int mediumSphereThreshold=10);
void drawGrid(int gridSize=10, float yOffset=0.001);

View File

@@ -28,7 +28,12 @@ ATTRIBUTE_ALIGNED16(class) btCollisionShape
{
protected:
int m_shapeType;
union
{
void* m_userPointer;
int m_userIndex;
};
public:
@@ -131,6 +136,16 @@ public:
return m_userPointer;
}
void setUserIndex(int index)
{
m_userIndex = index;
}
int getUserIndex() const
{
return m_userIndex;
}
virtual int calculateSerializeBufferSize() const;
///fills the dataBuffer and returns the struct name (and 0 on failure)