Merge pull request #299 from erwincoumans/master

fix crash in BasicDemo and some other minor things (see commits)
This commit is contained in:
erwincoumans
2014-12-16 16:32:39 -08:00
25 changed files with 1272 additions and 184 deletions

View File

@@ -10,7 +10,8 @@ void BasicDemoPhysicsSetup::initPhysics(GraphicsPhysicsBridge& gfxBridge)
{
createEmptyDynamicsWorld();
gfxBridge.createPhysicsDebugDrawer(m_dynamicsWorld);
m_dynamicsWorld->getDebugDrawer()->setDebugMode(btIDebugDraw::DBG_DrawWireframe+btIDebugDraw::DBG_DrawContactPoints);
if (m_dynamicsWorld->getDebugDrawer())
m_dynamicsWorld->getDebugDrawer()->setDebugMode(btIDebugDraw::DBG_DrawWireframe+btIDebugDraw::DBG_DrawContactPoints);
///create a few basic rigid bodies
btBoxShape* groundShape = createBoxShape(btVector3(btScalar(50.),btScalar(50.),btScalar(50.)));

View File

@@ -4,6 +4,9 @@
#include "Bullet3AppSupport/BulletDemoInterface.h"
#include "../bullet2/BasicDemo/BasicDemo.h"
#include "../bullet2/CoordinateFrameDemo/CoordinateFrameDemoPhysicsSetup.h"
#include "../bullet2/BasicDemo/HingeDemo.h"
#include "../bullet2/BasicDemo/HingeDemo.h"
@@ -28,60 +31,35 @@
#include "../bullet2/BasicConcepts/CoordinateSystemDemo.h"
#include "../../Demos3/FiniteElementMethod/FiniteElementDemo.h"
//#include "../../Demos3/bullet2/SoftDemo/SoftDemo.h"
#include "../Geometry/SphereCreation.h"
#include "../Geometry/DistributePoints.h"
static BulletDemoInterface* TestJointTorqueCreateFunc(CommonGraphicsApp* app)
{
CommonPhysicsSetup* physicsSetup = new TestJointTorqueSetup();
return new BasicDemo(app, physicsSetup);
}
static BulletDemoInterface* MultiBodyVehicleCreateFunc(CommonGraphicsApp* app)
{
CommonPhysicsSetup* physicsSetup = new MultiBodyVehicleSetup();
return new BasicDemo(app, physicsSetup);
}
static BulletDemoInterface* LuaDemoCreateFunc(CommonGraphicsApp* app)
{
CommonPhysicsSetup* physicsSetup = new LuaPhysicsSetup(app);
return new BasicDemo(app, physicsSetup);
#define MYCREATEFUNC(func) \
static BulletDemoInterface* func##CreateFunc(CommonGraphicsApp* app)\
{\
CommonPhysicsSetup* physicsSetup = new func##Setup();\
return new BasicDemo(app, physicsSetup);\
}
static BulletDemoInterface* MyCcdPhysicsDemoCreateFunc(CommonGraphicsApp* app)
{
CommonPhysicsSetup* physicsSetup = new CcdPhysicsSetup();
return new BasicDemo(app, physicsSetup);
#define MYCREATEFUNC2(func,setup) \
static BulletDemoInterface* func(CommonGraphicsApp* app)\
{\
CommonPhysicsSetup* physicsSetup = new setup(app);\
return new BasicDemo(app, physicsSetup);\
}
static BulletDemoInterface* MyKinematicObjectCreateFunc(CommonGraphicsApp* app)
{
CommonPhysicsSetup* physicsSetup = new KinematicObjectSetup();
return new BasicDemo(app, physicsSetup);
}
static BulletDemoInterface* MySerializeCreateFunc(CommonGraphicsApp* app)
{
CommonPhysicsSetup* physicsSetup = new SerializeSetup();
return new BasicDemo(app, physicsSetup);
}
static BulletDemoInterface* MyConstraintCreateFunc(CommonGraphicsApp* app)
{
CommonPhysicsSetup* physicsSetup = new ConstraintPhysicsSetup();
return new BasicDemo(app, physicsSetup);
}
MYCREATEFUNC(TestJointTorque);
MYCREATEFUNC(MultiBodyVehicle);
MYCREATEFUNC2(LuaDemoCreateFunc,LuaPhysicsSetup);
MYCREATEFUNC(Serialize);
MYCREATEFUNC(CcdPhysics);
MYCREATEFUNC(KinematicObject);
MYCREATEFUNC(ConstraintPhysics);
MYCREATEFUNC(ImportUrdf);
MYCREATEFUNC2(ImportObjCreateFunc,ImportObjSetup);
MYCREATEFUNC2(ImportSTLCreateFunc,ImportSTLSetup);
MYCREATEFUNC(CoordinateFrameDemoPhysics);
static BulletDemoInterface* MyImportUrdfCreateFunc(CommonGraphicsApp* app)
{
CommonPhysicsSetup* physicsSetup = new ImportUrdfDemo();
return new BasicDemo(app, physicsSetup);
}
static BulletDemoInterface* MyImportObjCreateFunc(CommonGraphicsApp* app)
{
CommonPhysicsSetup* physicsSetup = new ImportObjDemo(app);
return new BasicDemo(app, physicsSetup);
}
static BulletDemoInterface* MyImportSTLCreateFunc(CommonGraphicsApp* app)
{
CommonPhysicsSetup* physicsSetup = new ImportSTLDemo(app);
return new BasicDemo(app, physicsSetup);
}
static BulletDemoInterface* MyImportColladaCreateFunc(CommonGraphicsApp* app)
{
@@ -92,7 +70,6 @@ static BulletDemoInterface* MyImportColladaCreateFunc(CommonGraphicsApp* app)
struct BulletDemoEntry
{
int m_menuLevel;
@@ -107,24 +84,27 @@ static BulletDemoEntry allDemos[]=
{0,"Basic Concepts",0},
{1,"Basis Frame", &CoordinateSystemDemo::CreateFunc},
{1,"SupportFunc", &MySupportFuncDemo::CreateFunc},
//{"emptydemo",EmptyBulletDemo::MyCreateFunc},
{0,"API Demos", 0},
{1,"BasicDemo",BasicDemo::MyCreateFunc},
{ 1, "CcdDemo", MyCcdPhysicsDemoCreateFunc },
{ 1, "Kinematic", MyKinematicObjectCreateFunc },
{ 1, "Constraints", MyConstraintCreateFunc },
{ 1, "CcdDemo", CcdPhysicsCreateFunc },
{ 1, "Kinematic", KinematicObjectCreateFunc },
{ 1, "Constraints", ConstraintPhysicsCreateFunc },
{ 1, "LuaDemo",LuaDemoCreateFunc},
{0,"File Formats", 0},
{ 1, ".bullet",MySerializeCreateFunc},
{ 1, "Wavefront Obj", MyImportObjCreateFunc},
{ 1, "URDF", MyImportUrdfCreateFunc },
{ 1, "STL", MyImportSTLCreateFunc},
{ 1, ".bullet",SerializeCreateFunc},
{ 1, "Wavefront Obj", ImportObjCreateFunc},
{ 1, "URDF", ImportUrdfCreateFunc },
{ 1, "STL", ImportSTLCreateFunc},
{ 1, "COLLADA", MyImportColladaCreateFunc},
{0,"Experiments", 0},
{1, "Finite Element Demo", FiniteElementDemo::CreateFunc},
{1,"SphereCreation", &SphereCreation::CreateFunc},
{1,"DistributePoints", &DistributePoints::CreateFunc},
{1,"Coordinate Frames", CoordinateFrameDemoPhysicsCreateFunc},
// {0,"Soft Body", 0},
// {1,"Cloth1", SoftDemo::CreateFunc},

View File

@@ -25,6 +25,8 @@ SET(App_AllBullet2Demos_SRCS
../bullet2/MultiBodyDemo/MultiBodyVehicle.cpp
../bullet2/ConstraintDemo/ConstraintPhysicsSetup.cpp
../bullet2/ConstraintDemo/ConstraintPhysicsSetup.h
../bullet2/CoordinateFrameDemo/CoordinateFrameDemoPhysicsSetup.cpp
../bullet2/CoordinateFrameDemo/CoordinateFrameDemoPhysicsSetup.h
../bullet2/FeatherstoneMultiBodyDemo/BulletMultiBodyDemos.cpp
../bullet2/FeatherstoneMultiBodyDemo/BulletMultiBodyDemos.h
../bullet2/FeatherstoneMultiBodyDemo/MultiDofDemo.cpp

View File

@@ -207,7 +207,10 @@ static BulletDemoInterface* sCurrentDemo = 0;
static b3AlignedObjectArray<const char*> allNames;
bool drawGUI=true;
extern bool useShadowMap;
static bool wireframe=false;
static bool visualWireframe=false;
static bool renderVisualGeometry=true;
static bool renderGrid = true;
static bool pauseSimulation=false;//true;
int midiBaseIndex = 176;
@@ -243,15 +246,18 @@ void MyKeyboardCallback(int key, int state)
if (key=='w' && state)
{
wireframe=!wireframe;
if (wireframe)
{
glPolygonMode( GL_FRONT_AND_BACK, GL_LINE );
} else
{
glPolygonMode( GL_FRONT_AND_BACK, GL_FILL );
}
visualWireframe=!visualWireframe;
}
if (key=='v' && state)
{
renderVisualGeometry = !renderVisualGeometry;
}
if (key=='g' && state)
{
renderGrid = !renderGrid;
}
if (key=='i' && state)
{
pauseSimulation = !pauseSimulation;
@@ -321,7 +327,7 @@ void openURDFDemo(const char* filename)
s_parameterInterface->removeAllParameters();
ImportUrdfDemo* physicsSetup = new ImportUrdfDemo();
ImportUrdfSetup* physicsSetup = new ImportUrdfSetup();
physicsSetup->setFileName(filename);
sCurrentDemo = new BasicDemo(app, physicsSetup);
@@ -595,7 +601,7 @@ int main(int argc, char* argv[])
MyProfileWindow* profWindow = setupProfileWindow(gui->getInternalData());
profileWindowSetVisible(profWindow,false);
gui->setFocus();
#if 0
{
MyGraphInput input(gui->getInternalData());
@@ -720,6 +726,8 @@ int main(int argc, char* argv[])
BT_PROFILE("Update Camera");
s_instancingRenderer->updateCamera(dg.upAxis);
}
if (renderGrid)
{
BT_PROFILE("Draw Grid");
app->drawGrid(dg);
@@ -748,11 +756,18 @@ int main(int argc, char* argv[])
sCurrentDemo->stepSimulation(deltaTimeInSeconds);//1./60.f);
prevTimeInMicroseconds = curTimeInMicroseconds;
}
if (renderVisualGeometry)
{
if (visualWireframe)
{
glPolygonMode( GL_FRONT_AND_BACK, GL_LINE );
}
BT_PROFILE("Render Scene");
sCurrentDemo->renderScene();
}
{
glPolygonMode( GL_FRONT_AND_BACK, GL_FILL );
sCurrentDemo->physicsDebugDraw();
}
}
@@ -785,7 +800,7 @@ int main(int argc, char* argv[])
app->swapBuffer();
}
gui->forceUpdateScrollBars();
} while (!s_window->requestedExit());
// selectDemo(0);

View File

@@ -46,6 +46,8 @@
"../bullet2/MultiBodyDemo/TestJointTorqueSetup.h",
"../bullet2/MultiBodyDemo/MultiBodyVehicle.cpp",
"../bullet2/MultiBodyDemo/MultiBodyVehicle.h",
"../bullet2/CoordinateFrameDemo/CoordinateFrameDemoPhysicsSetup.cpp",
"../bullet2/CoordinateFrameDemo/CoordinateFrameDemoPhysicsSetup.h",
-- "../DifferentialGearDemo/DifferentialGearSetup.cpp",
-- "../DifferentialGearDemo/DifferentialGearSetup.h",
"../FiniteElementMethod/FiniteElementDemo.cpp",

View File

@@ -0,0 +1,308 @@
#ifndef DISTRIBUTE_POINTS_H
#define DISTRIBUTE_POINTS_H
#include "Bullet3AppSupport/BulletDemoInterface.h"
#include "OpenGLWindow/CommonGraphicsApp.h"
#include "BulletCollision/CollisionShapes/btConvexHullShape.h"
#include "BulletCollision/CollisionShapes/btConvexPolyhedron.h"
#include "btBulletDynamicsCommon.h"
inline btScalar randRange(btScalar minRange, btScalar maxRange)
{
return (rand() / (btScalar(RAND_MAX) + btScalar(1.0))) * (maxRange - minRange) + minRange;
}
void myCallback(btBroadphasePair& collisionPair, btCollisionDispatcher& dispatcher, const btDispatcherInfo& dispatchInfo)
{
if (1)
{
btCollisionObject* colObj0 = (btCollisionObject*)collisionPair.m_pProxy0->m_clientObject;
btCollisionObject* colObj1 = (btCollisionObject*)collisionPair.m_pProxy1->m_clientObject;
btRigidBody* body0 = btRigidBody::upcast(colObj0);
btRigidBody* body1 = btRigidBody::upcast(colObj1);
if (body0 && body1)
{
btVector3 vec = body1->getWorldTransform().getOrigin()-body0->getWorldTransform().getOrigin();
vec.safeNormalize();
//add a small 'random' direction to avoid getting stuck in a plane
//vec += 0.00001*btVector3(randRange(0,1),randRange(0,1),randRange(0,1));
//magnitude: 1./vec.length1();
btScalar l = vec.length();
btScalar mag = 1.1/(l*l*l);
body0->applyImpulse(-mag*vec,btVector3(0,0,0));
body1->applyImpulse(mag*vec,btVector3(0,0,0));
}
} else
{
btCollisionDispatcher::defaultNearCallback(collisionPair,dispatcher,dispatchInfo);
}
}
class DistributePoints : public BulletDemoInterface
{
CommonGraphicsApp* m_app;
float m_x;
float m_y;
btDefaultCollisionConfiguration* m_collisionConfiguration;
btCollisionDispatcher* m_dispatcher;
btDiscreteDynamicsWorld* m_dynamicsWorld;
btDbvtBroadphase* m_broadphase;
btSequentialImpulseConstraintSolver* m_solver;
public:
DistributePoints(CommonGraphicsApp* app)
:m_app(app),
m_x(0),
m_y(0)
{
m_app->setUpAxis(1);
m_collisionConfiguration = new btDefaultCollisionConfiguration();
m_dispatcher = new btCollisionDispatcher(m_collisionConfiguration);
m_broadphase = new btDbvtBroadphase();
btSequentialImpulseConstraintSolver* sol = new btSequentialImpulseConstraintSolver;
m_solver = sol;
m_dynamicsWorld = new btDiscreteDynamicsWorld(m_dispatcher, m_broadphase, m_solver, m_collisionConfiguration);
m_dispatcher->setNearCallback(myCallback);
}
virtual ~DistributePoints()
{
delete m_dynamicsWorld;
delete m_solver;
delete m_broadphase;
delete m_dispatcher;
delete m_collisionConfiguration;
}
static BulletDemoInterface* CreateFunc(CommonGraphicsApp* app)
{
return new DistributePoints(app);
}
inline btScalar randRange(btScalar minRange, btScalar maxRange)
{
return (rand() / (btScalar(RAND_MAX) + btScalar(1.0))) * (maxRange - minRange) + minRange;
}
virtual void initPhysics()
{
//create spheres, attached with point to point constraint
//use a collision callback, apply forces
btScalar radius = 0.01;
btSphereShape* sphere = new btSphereShape(1);
int sphereId = m_app->registerGraphicsSphereShape(radius,false);
for (int i=0;i<256;i++)
{
btScalar mass =1.f;
btVector3 localInertia;
sphere->calculateLocalInertia(mass,localInertia);
btRigidBody::btRigidBodyConstructionInfo ci(mass,0,sphere,localInertia);
ci.m_startWorldTransform.setIdentity();
btVector3 center(randRange(-1,1),randRange(-1,1),randRange(-1,1));
center.normalize();
ci.m_startWorldTransform.setOrigin(center);
btRigidBody* body = new btRigidBody(ci);
const btVector3& pos = body->getWorldTransform().getOrigin();
btQuaternion orn = body->getWorldTransform().getRotation();
btVector4 color(1,0,0,1);
btVector3 scaling(radius,radius,radius);
int instanceId = m_app->m_renderer->registerGraphicsInstance(sphereId,pos,orn,color,scaling);
body->setUserIndex(instanceId);
m_dynamicsWorld->addRigidBody(body);
btVector3 pivotInA = -body->getWorldTransform().getOrigin();
btVector3 pivotInB(0,0,0);
// btPoint2PointConstraint* p2p = new btPoint2PointConstraint(*body, btTypedConstraint::getFixedBody(),pivotInA,pivotInB);
// m_dynamicsWorld->addConstraint(p2p);
body->setActivationState(DISABLE_DEACTIVATION);
}
m_dynamicsWorld->setGravity(btVector3(0,0,0));
m_app->m_renderer->writeTransforms();
}
virtual void exitPhysics()
{
}
virtual void stepSimulation(float deltaTime)
{
m_dynamicsWorld->stepSimulation(1./60.,0);
for (int i=0;i<m_dynamicsWorld->getNumCollisionObjects();i++)
{
btRigidBody* body = btRigidBody::upcast(m_dynamicsWorld->getCollisionObjectArray()[i]);
if (body && body->getUserIndex()>=0)
{
btTransform pos = body->getWorldTransform();
pos.setOrigin(pos.getOrigin().normalized());
body->setWorldTransform(pos);
body->setAngularVelocity(btVector3(0,0,0));
body->setLinearVelocity(btVector3(0,0,0));
}
}
}
virtual void renderScene()
{
//sync transforms
for (int i=0;i<m_dynamicsWorld->getNumCollisionObjects();i++)
{
btRigidBody* body = btRigidBody::upcast(m_dynamicsWorld->getCollisionObjectArray()[i]);
if (body && body->getUserIndex()>=0)
{
const btVector3& pos = body->getWorldTransform().getOrigin();
btQuaternion orn = body->getWorldTransform().getRotation();
m_app->m_renderer->writeSingleInstanceTransformToCPU(pos,orn,body->getUserIndex());
}
}
m_app->m_renderer->writeTransforms();
m_app->m_renderer->renderScene();
}
virtual void physicsDebugDraw()
{
int lineWidth = 1;
int pointSize = 2;
btAlignedObjectArray<btVector3> m_vertices;
for (int i=0;i<m_dynamicsWorld->getNumCollisionObjects();i++)
{
btRigidBody* body = btRigidBody::upcast(m_dynamicsWorld->getCollisionObjectArray()[i]);
if (body && body->getUserIndex()>=0)
{
btTransform pos = body->getWorldTransform();
m_vertices.push_back(pos.getOrigin());
}
}
btConvexHullShape* m_convexHull = new btConvexHullShape(&m_vertices[0].x(),m_vertices.size(),sizeof(btVector3));
m_convexHull->initializePolyhedralFeatures();
const btConvexPolyhedron* poly = m_convexHull->getConvexPolyhedron();
btScalar averageEdgeLength = 0.f;
btScalar numLengths=0;
for (int p=0;p<poly->m_faces.size();p++)
{
for (int f=2;f<poly->m_faces[p].m_indices.size();f++)
{
btVector4 color0(0,0,1,1);
btVector4 color1(0,0,1,1);
btVector4 color2(0,0,1,1);
int index0=poly->m_faces[p].m_indices[f-2];
int index1=poly->m_faces[p].m_indices[f-1];
int index2=poly->m_faces[p].m_indices[f];
btVector3 v0 = poly->m_vertices[index0];
btVector3 v1 = poly->m_vertices[index1];
btVector3 v2 = poly->m_vertices[index2];
btVector3 e0 = v1-v0;
btVector3 e1 = v2-v1;
btVector3 e2 = v0-v2;
btScalar e0Length = e0.length();
btScalar e1Length = e1.length();
btScalar e2Length = e2.length();
averageEdgeLength+=e0Length;
averageEdgeLength+=e1Length;
averageEdgeLength+=e2Length;
numLengths+=3;
}
}
averageEdgeLength/=numLengths;
btScalar maxLengthDiff = 0.f;
for (int p=0;p<poly->m_faces.size();p++)
{
for (int f=2;f<poly->m_faces[p].m_indices.size();f++)
{
btVector4 color0(0,0,1,1);
btVector4 color1(0,0,1,1);
btVector4 color2(0,0,1,1);
int index0=poly->m_faces[p].m_indices[f-2];
int index1=poly->m_faces[p].m_indices[f-1];
int index2=poly->m_faces[p].m_indices[f];
btVector3 v0 = poly->m_vertices[index0];
btVector3 v1 = poly->m_vertices[index1];
btVector3 v2 = poly->m_vertices[index2];
btVector3 e0 = v1-v0;
btVector3 e1 = v2-v1;
btVector3 e2 = v0-v2;
btScalar e0LengthDiff = btFabs(averageEdgeLength-e0.length());
btScalar e1LengthDiff = btFabs(averageEdgeLength-e1.length());
btScalar e2LengthDiff = btFabs(averageEdgeLength-e2.length());
btSetMax(maxLengthDiff,e0LengthDiff);
btSetMax(maxLengthDiff,e1LengthDiff);
btSetMax(maxLengthDiff,e2LengthDiff);
m_app->m_renderer->drawLine(&v0.x(),
&v1.x(),
color0,lineWidth);
m_app->m_renderer->drawLine(&v1.x(),
&v2.x(),
color1,lineWidth);
m_app->m_renderer->drawLine(&v2.x(),
&v0.x(),
color2,lineWidth);
}
//printf("maxEdgeLength=%f\n",maxEdgeLength);
}
for (int i=0;i<poly->m_vertices.size();i++)
{
btVector4 color(1,0,0,1);
m_app->m_renderer->drawPoint(poly->m_vertices[i],color,pointSize);
}
delete m_convexHull;
char msg[1024];
btScalar targetDist = 2.0f*sqrtf(4.0f/(btScalar)m_vertices.size());
sprintf(msg,"average Edge Length = %f, maxLengthDiff = %f",averageEdgeLength,maxLengthDiff);
b3Printf(msg);
}
virtual bool mouseMoveCallback(float x,float y)
{
return false;
}
virtual bool mouseButtonCallback(int button, int state, float x, float y)
{
return false;
}
virtual bool keyboardCallback(int key, int state)
{
return false;
}
};
#endif //DISTRIBUTE_POINTS_H

View File

@@ -0,0 +1,345 @@
#ifndef SPHERE_CREATION_H
#define SPHERE_CREATION_H
#include "Bullet3AppSupport/BulletDemoInterface.h"
#include "OpenGLWindow/CommonGraphicsApp.h"
#include "BulletCollision/CollisionShapes/btConvexHullShape.h"
#include "BulletCollision/CollisionShapes/btConvexPolyhedron.h"
class SphereCreation : public BulletDemoInterface
{
CommonGraphicsApp* m_app;
float m_x;
float m_y;
btAlignedObjectArray<btVector3> m_vertices;
btConvexHullShape* m_convexHull;
public:
SphereCreation(CommonGraphicsApp* app)
:m_app(app),
m_x(0),
m_y(0)
{
m_app->setUpAxis(1);
m_app->m_renderer->writeTransforms();
}
virtual ~SphereCreation()
{
}
static BulletDemoInterface* CreateFunc(CommonGraphicsApp* app)
{
return new SphereCreation(app);
}
inline btScalar randRange(btScalar minRange, btScalar maxRange)
{
return (rand() / (btScalar(RAND_MAX) + btScalar(1.0))) * (maxRange - minRange) + minRange;
}
virtual void initPhysics()
{
srand(0);
//create random vertices
int numVerts = 256;
for (int i=0;i<numVerts;i++)
{
btVector3 v(randRange(-1,1),randRange(-1,1),randRange(-1,1));
v.safeNormalize();
m_vertices.push_back(v);
}
for (int i=0;i<1;i++)
{
distributeVerticesOnSphere(5,0.2);
}
m_convexHull = new btConvexHullShape(&m_vertices[0].x(),m_vertices.size(),sizeof(btVector3));
m_convexHull->initializePolyhedralFeatures();
}
virtual void exitPhysics()
{
//dump vertices
printf("indices:\n");
const btConvexPolyhedron* poly = m_convexHull->getConvexPolyhedron();
for (int i=0;i<poly->m_vertices.size();i++)
{
printf("%f,%f,%f,%f,%f,%f,%f,%f,%f,\n",poly->m_vertices[i].x(),
poly->m_vertices[i].y(),
poly->m_vertices[i].z(),
1.f,
poly->m_vertices[i].x(),
poly->m_vertices[i].y(),
poly->m_vertices[i].z(),
0.5f,0.5f);
}
for (int p=0;p<poly->m_faces.size();p++)
{
for (int f=2;f<poly->m_faces[p].m_indices.size();f++)
{
int index0=poly->m_faces[p].m_indices[f-2];
int index1=poly->m_faces[p].m_indices[f-1];
int index2=poly->m_faces[p].m_indices[f];
printf("%d,%d,%d,\n",index0,index1,index2);
}
}
}
void distributeVerticesOnSphere(int iterations,btScalar relaxation)
{
btScalar previousAverage=0;
btScalar averageDist = 0;
btScalar previousAverageError = 0.0f;
btScalar maxError = -1e30f;
btScalar averageError = 0.f;
///bring closest the closest neighbor of each vertex closer to the 'average' neighbor distance
for (int i=0;i<iterations;i++)
{
maxError = -1e30f;
averageDist = 0.f;
averageError = 0.f;
int numActualVerts = 0;
for (int v=0;v<m_vertices.size();v++)
{
btScalar minDist = 1e30f;
int closestOther = -1;
//find closest vertex
for (int w=0;w<m_vertices.size();w++)
{
if (w!=v)
{
numActualVerts++;
btVector3 vec = m_vertices[w]-m_vertices[v];
btScalar d = vec.length();
if (d<minDist)
{
minDist = d;
closestOther = w;
}
}
}
btScalar errorDist = previousAverage-minDist;
if (maxError < errorDist)
{
maxError = errorDist;
}
averageDist+=minDist;
if (closestOther>=0)
{
btVector3 vec = m_vertices[closestOther]-m_vertices[v];
vec.safeNormalize();
if (previousAverage)
{
averageError+=btFabs(errorDist);
m_vertices[v] -= vec*previousAverageError*relaxation;
m_vertices[closestOther] += vec*previousAverageError*relaxation;
m_vertices[v].normalize();
m_vertices[closestOther].normalize();
}
}
}
averageDist /= btScalar(m_vertices.size());
averageError /= btScalar(m_vertices.size());
previousAverageError = averageError;
previousAverage = averageDist;
}
char msg[1024];
btScalar targetDist = 2.0f*sqrtf(4.0f/(btScalar)m_vertices.size());
sprintf(msg,"averageDist = %f, previousAverageError = %f, maxError = %f, target = %f\n",averageDist,previousAverageError,maxError,targetDist);
b3Printf(msg);
}
virtual void stepSimulation(float deltaTime)
{
m_x+=0.01f;
m_y+=0.02f;
//bringVerticesTogether();
}
virtual void renderScene()
{
m_app->m_renderer->renderScene();
}
virtual void physicsDebugDraw()
{
int lineWidth = 1;
int pointSize = 2;
distributeVerticesOnSphere(12,0.2f);
delete m_convexHull;
m_convexHull = new btConvexHullShape(&m_vertices[0].x(),m_vertices.size(),sizeof(btVector3));
m_convexHull->initializePolyhedralFeatures();
const btConvexPolyhedron* poly = m_convexHull->getConvexPolyhedron();
if (m_vertices.size() != poly->m_vertices.size())
{
printf("Warning: m_vertices.size()=%d and poly->m_vertices.size()=%d\n", m_vertices.size(),
poly->m_vertices.size());
return;
} else
{
for (int i=0;i<m_vertices.size();i++)
{
m_vertices[i] = poly->m_vertices[i];
}
}
btScalar maxEdgeLength = -1e30f;
btScalar averageEdgeLength=0.f;
btScalar numLengts = 0;
for (int p=0;p<poly->m_faces.size();p++)
{
for (int f=2;f<poly->m_faces[p].m_indices.size();f++)
{
btVector4 color0(0,0,1,1);
btVector4 color1(0,0,1,1);
btVector4 color2(0,0,1,1);
int index0=poly->m_faces[p].m_indices[f-2];
int index1=poly->m_faces[p].m_indices[f-1];
int index2=poly->m_faces[p].m_indices[f];
btVector3 v0 = poly->m_vertices[index0];
btVector3 v1 = poly->m_vertices[index1];
btVector3 v2 = poly->m_vertices[index2];
btVector3 e0 = v1-v0;
btVector3 e1 = v2-v1;
btVector3 e2 = v0-v2;
btScalar e0Length = e0.length();
btScalar e1Length = e1.length();
btScalar e2Length = e2.length();
averageEdgeLength+= e0Length;
averageEdgeLength+= e1Length;
averageEdgeLength+= e2Length;
numLengts+=3.f;
}
}
averageEdgeLength/=numLengts;
for (int p=0;p<poly->m_faces.size();p++)
{
for (int f=2;f<poly->m_faces[p].m_indices.size();f++)
{
btVector4 color0(0,0,1,1);
btVector4 color1(0,0,1,1);
btVector4 color2(0,0,1,1);
int index0=poly->m_faces[p].m_indices[f-2];
int index1=poly->m_faces[p].m_indices[f-1];
int index2=poly->m_faces[p].m_indices[f];
btVector3 v0 = m_vertices[index0];
btVector3 v1 = m_vertices[index1];
btVector3 v2 = m_vertices[index2];
btVector3 e0 = v1-v0;
btVector3 e1 = v2-v1;
btVector3 e2 = v0-v2;
btScalar e0Length = e0.length();
btScalar e1Length = e1.length();
btScalar e2Length = e2.length();
btScalar scaling = -0.01;//-0.01f;//0;//-0.02f;
if (e0Length>maxEdgeLength)
maxEdgeLength = e0Length;
{
btScalar errorLength = averageEdgeLength-e0Length;
m_vertices[index0] += e0.normalized()*errorLength*scaling;
m_vertices[index1] -= e0.normalized()*errorLength*scaling;
m_vertices[index0].normalize();
m_vertices[index1].normalize();
color0.setValue(1,0,0,1);
//shift vertices
}
if (e1Length>maxEdgeLength)
maxEdgeLength = e1Length;
{
btScalar errorLength = averageEdgeLength-e1Length;
m_vertices[index1] += e1.normalized()*errorLength*scaling;
m_vertices[index2] -= e1.normalized()*errorLength*scaling;
m_vertices[index1].normalize();
m_vertices[index2].normalize();
color1.setValue(1,0,0,1);
}
if (e2Length>maxEdgeLength)
maxEdgeLength = e2Length;
{
btScalar errorLength = averageEdgeLength-e2Length;
m_vertices[index2] += e2.normalized()*errorLength*scaling;
m_vertices[index0] -= e2.normalized()*errorLength*scaling;
color2.setValue(1,0,0,1);
m_vertices[index2].normalize();
m_vertices[index0].normalize();
}
}
}
for (int p=0;p<poly->m_faces.size();p++)
{
for (int f=2;f<poly->m_faces[p].m_indices.size();f++)
{
btVector4 color0(0,0,1,1);
btVector4 color1(0,0,1,1);
btVector4 color2(0,0,1,1);
int index0=poly->m_faces[p].m_indices[f-2];
int index1=poly->m_faces[p].m_indices[f-1];
int index2=poly->m_faces[p].m_indices[f];
btVector3 v0 = m_vertices[index0];
btVector3 v1 = m_vertices[index1];
btVector3 v2 = m_vertices[index2];
m_app->m_renderer->drawLine(&v0.x(),
&v1.x(),
color0,lineWidth);
m_app->m_renderer->drawLine(&v1.x(),
&v2.x(),
color1,lineWidth);
m_app->m_renderer->drawLine(&v2.x(),
&v0.x(),
color2,lineWidth);
}
//printf("maxEdgeLength=%f\n",maxEdgeLength);
}
for (int i=0;i<m_vertices.size();i++)
{
btVector4 color(1,0,0,1);
m_app->m_renderer->drawPoint(m_vertices[i],color,pointSize);
}
}
virtual bool mouseMoveCallback(float x,float y)
{
return false;
}
virtual bool mouseButtonCallback(int button, int state, float x, float y)
{
return false;
}
virtual bool keyboardCallback(int key, int state)
{
return false;
}
};
#endif //SPHERE_CREATION_H

View File

@@ -7,13 +7,13 @@
#include "OpenGLWindow/SimpleOpenGL3App.h"
#include "Wavefront2GLInstanceGraphicsShape.h"
ImportObjDemo::ImportObjDemo(CommonGraphicsApp* app)
ImportObjSetup::ImportObjSetup(CommonGraphicsApp* app)
:m_app(app)
{
}
ImportObjDemo::~ImportObjDemo()
ImportObjSetup::~ImportObjSetup()
{
}
@@ -24,7 +24,7 @@ ImportObjDemo::~ImportObjDemo()
void ImportObjDemo::initPhysics(GraphicsPhysicsBridge& gfxBridge)
void ImportObjSetup::initPhysics(GraphicsPhysicsBridge& gfxBridge)
{
gfxBridge.setUpAxis(2);
this->createEmptyDynamicsWorld();

View File

@@ -4,12 +4,12 @@
#include "Bullet3AppSupport/CommonRigidBodySetup.h"
class ImportObjDemo : public CommonRigidBodySetup
class ImportObjSetup : public CommonRigidBodySetup
{
struct CommonGraphicsApp* m_app;
public:
ImportObjDemo(CommonGraphicsApp* app);
virtual ~ImportObjDemo();
ImportObjSetup(CommonGraphicsApp* app);
virtual ~ImportObjSetup();
virtual void initPhysics(GraphicsPhysicsBridge& gfxBridge);
};

View File

@@ -6,20 +6,20 @@
#include "OpenGLWindow/SimpleOpenGL3App.h"
#include "LoadMeshFromSTL.h"
ImportSTLDemo::ImportSTLDemo(CommonGraphicsApp* app)
ImportSTLSetup::ImportSTLSetup(CommonGraphicsApp* app)
:m_app(app)
{
}
ImportSTLDemo::~ImportSTLDemo()
ImportSTLSetup::~ImportSTLSetup()
{
}
void ImportSTLDemo::initPhysics(GraphicsPhysicsBridge& gfxBridge)
void ImportSTLSetup::initPhysics(GraphicsPhysicsBridge& gfxBridge)
{
gfxBridge.setUpAxis(2);
this->createEmptyDynamicsWorld();

View File

@@ -4,12 +4,12 @@
#include "Bullet3AppSupport/CommonRigidBodySetup.h"
class ImportSTLDemo : public CommonRigidBodySetup
class ImportSTLSetup : public CommonRigidBodySetup
{
struct CommonGraphicsApp* m_app;
public:
ImportSTLDemo(CommonGraphicsApp* app);
virtual ~ImportSTLDemo();
ImportSTLSetup(CommonGraphicsApp* app);
virtual ~ImportSTLSetup();
virtual void initPhysics(GraphicsPhysicsBridge& gfxBridge);
};

View File

@@ -12,12 +12,12 @@ static int bodyCollisionFilterMask=btBroadphaseProxy::AllFilter&(~btBroadphasePr
static bool enableConstraints = true;//false;
ImportUrdfDemo::ImportUrdfDemo()
ImportUrdfSetup::ImportUrdfSetup()
{
sprintf(m_fileName,"r2d2.urdf");
sprintf(m_fileName,"r2d2.urdf");//sphere2.urdf");//
}
ImportUrdfDemo::~ImportUrdfDemo()
ImportUrdfSetup::~ImportUrdfSetup()
{
}
@@ -41,7 +41,7 @@ btVector3 selectColor()
return color;
}
void ImportUrdfDemo::setFileName(const char* urdfFileName)
void ImportUrdfSetup::setFileName(const char* urdfFileName)
{
memcpy(m_fileName,urdfFileName,strlen(urdfFileName)+1);
}
@@ -544,7 +544,260 @@ void URDFvisual2BulletCollisionShape(my_shared_ptr<const Link> link, GraphicsPhy
}
void ImportUrdfDemo::initPhysics(GraphicsPhysicsBridge& gfxBridge)
btMultiBody* URDF2BulletMultiBody(my_shared_ptr<const Link> link, GraphicsPhysicsBridge& gfxBridge, const btTransform& parentTransformInWorldSpace, btMultiBodyDynamicsWorld* world, URDF2BulletMappings& mappings, const char* pathPrefix, btMultiBody* mb, int totalNumJoints)
{
btScalar mass = 0.f;
btTransform localInertialTransform; localInertialTransform.setIdentity();
btVector3 localInertiaDiagonal(0,0,0);
{
if ((*link).inertial)
{
mass = (*link).inertial->mass;
btMatrix3x3 inertiaMat;
inertiaMat.setIdentity();
inertiaMat.setValue(
(*link).inertial->ixx,(*link).inertial->ixy,(*link).inertial->ixz,
(*link).inertial->ixy,(*link).inertial->iyy,(*link).inertial->iyz,
(*link).inertial->ixz,(*link).inertial->iyz,(*link).inertial->izz);
btScalar threshold = 0.00001f;
int maxSteps=20;
btMatrix3x3 inertia2PrincipalAxis;
inertiaMat.diagonalize(inertia2PrincipalAxis,threshold,maxSteps);
localInertiaDiagonal.setValue(inertiaMat[0][0],inertiaMat[1][1],inertiaMat[2][2]);
btVector3 inertiaLocalCOM((*link).inertial->origin.position.x,(*link).inertial->origin.position.y,(*link).inertial->origin.position.z);
localInertialTransform.setOrigin(inertiaLocalCOM);
btQuaternion inertiaOrn((*link).inertial->origin.rotation.x,(*link).inertial->origin.rotation.y,(*link).inertial->origin.rotation.z,(*link).inertial->origin.rotation.w);
btMatrix3x3 inertiaOrnMat(inertiaOrn);
if (mass > 0 && (localInertiaDiagonal[0]==0.f || localInertiaDiagonal[1] == 0.f
|| localInertiaDiagonal[2] == 0.f))
{
b3Warning("Error: inertia should not be zero if mass is positive\n");
localInertiaDiagonal.setMax(btVector3(0.1,0.1,0.1));
localInertialTransform.setIdentity();//.setBasis(inertiaOrnMat);
}
else
{
localInertialTransform.setBasis(inertiaOrnMat*inertia2PrincipalAxis);
}
}
}
btTransform linkTransformInWorldSpace;
int parentIndex = -1;
const Link* parentLink = (*link).getParent();
if (parentLink)
{
parentIndex = parentLink->m_link_index;
btAssert(parentIndex>=0);
}
int linkIndex = mappings.m_linkMasses.size();
btTransform parent2joint;
if ((*link).parent_joint)
{
const urdf::Vector3 pos = (*link).parent_joint->parent_to_joint_origin_transform.position;
const urdf::Rotation orn = (*link).parent_joint->parent_to_joint_origin_transform.rotation;
parent2joint.setOrigin(btVector3(pos.x,pos.y,pos.z));
parent2joint.setRotation(btQuaternion(orn.x,orn.y,orn.z,orn.w));
linkTransformInWorldSpace =parentTransformInWorldSpace*parent2joint;
} else
{
linkTransformInWorldSpace = parentTransformInWorldSpace;
btAssert(mb==0);
bool multiDof = true;
bool canSleep = false;
bool isFixedBase = (mass==0);//todo: figure out when base is fixed
mb = new btMultiBody(totalNumJoints,mass, localInertiaDiagonal, isFixedBase, canSleep, multiDof);
}
btAssert(mb);
(*link).m_link_index = linkIndex;
//compute this links center of mass transform, aligned with the principal axis of inertia
{
//btTransform rigidBodyFrameInWorldSpace =linkTransformInWorldSpace*inertialFrame;
mappings.m_linkMasses.push_back(mass);
mappings.m_linkLocalDiagonalInertiaTensors.push_back(localInertiaDiagonal);
mappings.m_linkLocalInertiaTransforms.push_back(localInertialTransform);
if ((*link).parent_joint)
{
btTransform offsetInA,offsetInB;
offsetInA.setIdentity();
//offsetInA = mappings.m_linkLocalInertiaTransforms[parentIndex].inverse()*parent2joint;
offsetInA = parent2joint;
offsetInB.setIdentity();
//offsetInB = localInertialTransform.inverse();
const Joint* pj = (*link).parent_joint.get();
//btVector3 jointAxis(0,0,1);//pj->axis.x,pj->axis.y,pj->axis.z);
btVector3 jointAxis(pj->axis.x,pj->axis.y,pj->axis.z);
mappings.m_jointAxisArray.push_back(jointAxis);
mappings.m_jointOffsetInParent.push_back(offsetInA);
mappings.m_jointOffsetInChild.push_back(offsetInB);
mappings.m_jointTypeArray.push_back(pj->type);
switch (pj->type)
{
case Joint::FIXED:
{
printf("Fixed joint\n");
mb->setupFixed(linkIndex-1,mass,localInertiaDiagonal,parentIndex-1,offsetInA.getRotation(),offsetInA.getOrigin(),offsetInB.getOrigin());
break;
}
case Joint::CONTINUOUS:
case Joint::REVOLUTE:
{
printf("Revolute joint\n");
mb->setupRevolute(linkIndex-1,mass,localInertiaDiagonal,parentIndex-1,offsetInA.getRotation(),jointAxis,offsetInA.getOrigin(),offsetInB.getOrigin(),true);
mb->finalizeMultiDof();
//mb->setJointVel(linkIndex-1,1);
break;
}
case Joint::PRISMATIC:
{
mb->setupPrismatic(linkIndex-1,mass,localInertiaDiagonal,parentIndex-1,offsetInA.getRotation(),jointAxis,offsetInB.getOrigin(),true);
printf("Prismatic joint\n");
break;
}
default:
{
printf("Unknown joint\n");
btAssert(0);
}
};
} else
{
mappings.m_jointAxisArray.push_back(btVector3(0,0,0));
btTransform ident;
ident.setIdentity();
mappings.m_jointOffsetInParent.push_back(ident);
mappings.m_jointOffsetInChild.push_back(ident);
mappings.m_jointTypeArray.push_back(-1);
}
}
//btCompoundShape* compoundShape = new btCompoundShape();
btCollisionShape* shape = 0;
for (int v=0;v<(int)link->collision_array.size();v++)
{
const Collision* visual = link->collision_array[v].get();
shape = convertVisualToCollisionShape(visual,pathPrefix);
if (shape)//childShape)
{
gfxBridge.createCollisionShapeGraphicsObject(shape);//childShape);
//btVector3 color = selectColor();
/*
if (visual->material.get())
{
color.setValue(visual->material->color.r,visual->material->color.g,visual->material->color.b);//,visual->material->color.a);
}
*/
btVector3 localInertia(0,0,0);
if (mass)
{
shape->calculateLocalInertia(mass,localInertia);
}
//btRigidBody::btRigidBodyConstructionInfo rbci(mass,0,shape,localInertia);
btVector3 visual_pos(visual->origin.position.x,visual->origin.position.y,visual->origin.position.z);
btQuaternion visual_orn(visual->origin.rotation.x,visual->origin.rotation.y,visual->origin.rotation.z,visual->origin.rotation.w);
btTransform visual_frame;
visual_frame.setOrigin(visual_pos);
visual_frame.setRotation(visual_orn);
btTransform childTransform;
childTransform.setIdentity();//TODO(erwincoumans): compute relative visual/inertial transform
// compoundShape->addChildShape(childTransform,childShape);
}
}
if (shape)//compoundShape->getNumChildShapes()>0)
{
btMultiBodyLinkCollider* col= new btMultiBodyLinkCollider(mb, linkIndex-1);
col->setCollisionShape(shape);
btTransform tr;
tr.setIdentity();
tr = linkTransformInWorldSpace;
//if we don't set the initial pose of the btCollisionObject, the simulator will do this
//when syncing the btMultiBody link transforms to the btMultiBodyLinkCollider
//tr.setOrigin(local_origin[0]);
//tr.setRotation(btQuaternion(quat[0],quat[1],quat[2],quat[3]));
col->setWorldTransform(tr);
bool isDynamic = true;
short collisionFilterGroup = isDynamic? short(btBroadphaseProxy::DefaultFilter) : short(btBroadphaseProxy::StaticFilter);
short collisionFilterMask = isDynamic? short(btBroadphaseProxy::AllFilter) : short(btBroadphaseProxy::AllFilter ^ btBroadphaseProxy::StaticFilter);
world->addCollisionObject(col,collisionFilterGroup,collisionFilterMask);
btVector3 color = selectColor();//(0.0,0.0,0.5);
gfxBridge.createCollisionObjectGraphicsObject(col,color);
btScalar friction = 0.5f;
col->setFriction(friction);
if (parentIndex>=0)
{
mb->getLink(linkIndex-1).m_collider=col;
} else
{
mb->setBaseCollider(col);
}
}
for (std::vector<my_shared_ptr<Link> >::const_iterator child = link->child_links.begin(); child != link->child_links.end(); child++)
{
if (*child)
{
URDF2BulletMultiBody(*child,gfxBridge, linkTransformInWorldSpace, world,mappings,pathPrefix,mb,totalNumJoints);
}
else
{
std::cout << "root link: " << link->name << " has a null child!" << *child << std::endl;
}
}
return mb;
}
void ImportUrdfSetup::initPhysics(GraphicsPhysicsBridge& gfxBridge)
{
int upAxis = 2;
@@ -620,15 +873,16 @@ void ImportUrdfDemo::initPhysics(GraphicsPhysicsBridge& gfxBridge)
int numJoints = (*robot).m_numJoints;
if (1)
static bool useFeatherstone = false;
if (!useFeatherstone)
{
URDF2BulletMappings mappings;
URDFvisual2BulletCollisionShape(root_link, gfxBridge, identityTrans,m_dynamicsWorld,mappings,pathPrefix);
}
//the btMultiBody support is work-in-progress :-)
#if 0
if (0)
#if 1
else
{
URDF2BulletMappings mappings;
@@ -641,7 +895,7 @@ void ImportUrdfDemo::initPhysics(GraphicsPhysicsBridge& gfxBridge)
}
#endif//
useFeatherstone = !useFeatherstone;
printf("numJoints/DOFS = %d\n", numJoints);
if (0)
@@ -681,7 +935,7 @@ void ImportUrdfDemo::initPhysics(GraphicsPhysicsBridge& gfxBridge)
}
void ImportUrdfDemo::stepSimulation(float deltaTime)
void ImportUrdfSetup::stepSimulation(float deltaTime)
{
if (m_dynamicsWorld)
{

View File

@@ -4,13 +4,13 @@
#include "Bullet3AppSupport/CommonMultiBodySetup.h"
class ImportUrdfDemo : public CommonMultiBodySetup
class ImportUrdfSetup : public CommonMultiBodySetup
{
char m_fileName[1024];
public:
ImportUrdfDemo();
virtual ~ImportUrdfDemo();
ImportUrdfSetup();
virtual ~ImportUrdfSetup();
virtual void initPhysics(GraphicsPhysicsBridge& gfxBridge);
virtual void stepSimulation(float deltaTime);

View File

@@ -0,0 +1,90 @@
#include "CoordinateFrameDemoPhysicsSetup.h"
#include "btBulletDynamicsCommon.h"
#define ARRAY_SIZE_Y 5
#define ARRAY_SIZE_X 5
#define ARRAY_SIZE_Z 5
bool showRigidBodyCenterOfMass = true;
void CoordinateFrameDemoPhysicsSetup::debugDraw()
{
/*
for (int i=0;i<m_dynamicsWorld->getCollisionObjectArray().size();i++)
{
const btCollisionObject* colObj = m_dynamicsWorld->getCollisionObjectArray()[i];
if (showRigidBodyCenterOfMass)
{
m_dynamicsWorld->getDebugDrawer()->drawTransform(colObj->getWorldTransform(),1);
}
}
*/
m_dynamicsWorld->debugDrawWorld();
}
void CoordinateFrameDemoPhysicsSetup::initPhysics(GraphicsPhysicsBridge& gfxBridge)
{
createEmptyDynamicsWorld();
m_dynamicsWorld->setGravity(btVector3(0,0,0));
gfxBridge.createPhysicsDebugDrawer(m_dynamicsWorld);
m_dynamicsWorld->getDebugDrawer()->setDebugMode(btIDebugDraw::DBG_DrawWireframe+btIDebugDraw::DBG_DrawContactPoints);
m_dynamicsWorld->getDebugDrawer()->setDebugMode(m_dynamicsWorld->getDebugDrawer()->getDebugMode() + btIDebugDraw::DBG_DrawFrames);
btScalar sqr2 = btSqrt(2);
btVector3 tetraVerts[] = {
btVector3(1.f, 0.f, -1/sqr2),
btVector3(-1.f, 0.f, -1/sqr2),
btVector3(0, 1.f, 1/sqr2),
btVector3(0, -1.f, 1/sqr2),
};
{
//create a few dynamic rigidbodies
// Re-using the same collision is better for memory usage and performance
btCompoundShape* hull = new btCompoundShape();
btConvexHullShape* childHull = new btConvexHullShape(&tetraVerts[0].getX(),sizeof(tetraVerts)/sizeof(btVector3),sizeof(btVector3));
childHull->initializePolyhedralFeatures();
btTransform childTrans;
childTrans.setIdentity();
childTrans.setOrigin(btVector3(2,0,0));
hull->addChildShape(childTrans,childHull);
gfxBridge.createCollisionShapeGraphicsObject(hull);
m_collisionShapes.push_back(hull);
/// 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)
hull->calculateLocalInertia(mass,localInertia);
startTransform.setOrigin(btVector3(0,0,0));
btRigidBody* body = createRigidBody(mass,startTransform,hull);
gfxBridge.createRigidBodyGraphicsObject(body, btVector3(1, 1, 0));
}
}

View File

@@ -0,0 +1,28 @@
#ifndef COORDINATE_FRAME_DEMO_PHYSICS_SETUP_H
#define COORDINATE_FRAME_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/btVector3.h"
#include "LinearMath/btAlignedObjectArray.h"
#include "Bullet3AppSupport/CommonRigidBodySetup.h"
struct CoordinateFrameDemoPhysicsSetup : public CommonRigidBodySetup
{
virtual void initPhysics(GraphicsPhysicsBridge& gfxBridge);
virtual void debugDraw();
};
#endif //COORDINATE_FRAME_DEMO_PHYSICS_SETUP_H

View File

@@ -33,97 +33,114 @@ struct MyGraphicsPhysicsBridge : public GraphicsPhysicsBridge
btCollisionShape* shape = body->getCollisionShape();
btTransform startTransform = body->getWorldTransform();
int graphicsShapeId = shape->getUserIndex();
btAssert(graphicsShapeId >= 0);
btVector3 localScaling = shape->getLocalScaling();
int graphicsInstanceId = m_glApp->m_renderer->registerGraphicsInstance(graphicsShapeId, startTransform.getOrigin(), startTransform.getRotation(), color, localScaling);
body->setUserIndex(graphicsInstanceId);
if (graphicsShapeId>=0)
{
// btAssert(graphicsShapeId >= 0);
btVector3 localScaling = shape->getLocalScaling();
int graphicsInstanceId = m_glApp->m_renderer->registerGraphicsInstance(graphicsShapeId, startTransform.getOrigin(), startTransform.getRotation(), color, localScaling);
body->setUserIndex(graphicsInstanceId);
}
}
virtual void createCollisionShapeGraphicsObject(btCollisionShape* collisionShape, const btTransform& parentTransform, btAlignedObjectArray<GraphicsVertex>& verticesOut, btAlignedObjectArray<int>& indicesOut)
{
//todo: support all collision shape types
switch (collisionShape->getShapeType())
{
case TRIANGLE_MESH_SHAPE_PROXYTYPE:
{
break;
}
default:
{
if (collisionShape->isConvex())
{
btConvexShape* convex = (btConvexShape*)collisionShape;
{
btShapeHull* hull = new btShapeHull(convex);
hull->buildHull(0.0);
{
//int strideInBytes = 9*sizeof(float);
//int numVertices = hull->numVertices();
//int numIndices =hull->numIndices();
for (int t=0;t<hull->numTriangles();t++)
{
btVector3 triNormal;
int index0 = hull->getIndexPointer()[t*3+0];
int index1 = hull->getIndexPointer()[t*3+1];
int index2 = hull->getIndexPointer()[t*3+2];
btVector3 pos0 =parentTransform*hull->getVertexPointer()[index0];
btVector3 pos1 =parentTransform*hull->getVertexPointer()[index1];
btVector3 pos2 =parentTransform*hull->getVertexPointer()[index2];
triNormal = (pos1-pos0).cross(pos2-pos0);
triNormal.normalize();
for (int v=0;v<3;v++)
{
int index = hull->getIndexPointer()[t*3+v];
GraphicsVertex vtx;
btVector3 pos =parentTransform*hull->getVertexPointer()[index];
vtx.pos[0] = pos.x();
vtx.pos[1] = pos.y();
vtx.pos[2] = pos.z();
vtx.pos[3] = 0.f;
vtx.normal[0] =triNormal.x();
vtx.normal[1] =triNormal.y();
vtx.normal[2] =triNormal.z();
vtx.texcoord[0] = 0.5f;
vtx.texcoord[1] = 0.5f;
indicesOut.push_back(verticesOut.size());
verticesOut.push_back(vtx);
}
}
}
}
} else
{
if (collisionShape->isCompound())
{
btCompoundShape* compound = (btCompoundShape*) collisionShape;
for (int i=0;i<compound->getNumChildShapes();i++)
{
btTransform childWorldTrans = parentTransform * compound->getChildTransform(i);
createCollisionShapeGraphicsObject(compound->getChildShape(i),childWorldTrans,verticesOut,indicesOut);
}
} else
{
btAssert(0);
}
}
}
};
}
virtual void createCollisionShapeGraphicsObject(btCollisionShape* collisionShape)
{
//already has a graphics object?
if (collisionShape->getUserIndex()>=0)
return;
//todo: support all collision shape types
switch (collisionShape->getShapeType())
btAlignedObjectArray<GraphicsVertex> vertices;
btAlignedObjectArray<int> indices;
btTransform startTrans;startTrans.setIdentity();
createCollisionShapeGraphicsObject(collisionShape,startTrans,vertices,indices);
if (vertices.size() && indices.size())
{
case BOX_SHAPE_PROXYTYPE:
{
btBoxShape* box = (btBoxShape*)collisionShape;
btVector3 halfExtents = box->getHalfExtentsWithMargin();
int cubeShapeId = m_glApp->registerCubeShape(halfExtents.x(), halfExtents.y(), halfExtents.z());
box->setUserIndex(cubeShapeId);
break;
int shapeId = m_glApp->m_renderer->registerShape(&vertices[0].pos[0],vertices.size(),&indices[0],indices.size());
collisionShape->setUserIndex(shapeId);
}
case TRIANGLE_MESH_SHAPE_PROXYTYPE:
{
break;
}
default:
{
if (collisionShape->isConvex())
{
btConvexShape* convex = (btConvexShape*)collisionShape;
{
btShapeHull* hull = new btShapeHull(convex);
hull->buildHull(0.0);
{
//int strideInBytes = 9*sizeof(float);
//int numVertices = hull->numVertices();
//int numIndices =hull->numIndices();
btAlignedObjectArray<GraphicsVertex> gvertices;
btAlignedObjectArray<int> indices;
for (int t=0;t<hull->numTriangles();t++)
{
btVector3 triNormal;
int index0 = hull->getIndexPointer()[t*3+0];
int index1 = hull->getIndexPointer()[t*3+1];
int index2 = hull->getIndexPointer()[t*3+2];
btVector3 pos0 =hull->getVertexPointer()[index0];
btVector3 pos1 =hull->getVertexPointer()[index1];
btVector3 pos2 =hull->getVertexPointer()[index2];
triNormal = (pos1-pos0).cross(pos2-pos0);
triNormal.normalize();
for (int v=0;v<3;v++)
{
int index = hull->getIndexPointer()[t*3+v];
GraphicsVertex vtx;
btVector3 pos =hull->getVertexPointer()[index];
vtx.pos[0] = pos.x();
vtx.pos[1] = pos.y();
vtx.pos[2] = pos.z();
vtx.pos[3] = 0.f;
vtx.normal[0] =triNormal.x();
vtx.normal[1] =triNormal.y();
vtx.normal[2] =triNormal.z();
vtx.texcoord[0] = 0.5f;
vtx.texcoord[1] = 0.5f;
indices.push_back(gvertices.size());
gvertices.push_back(vtx);
}
}
int shapeId = m_glApp->m_renderer->registerShape(&gvertices[0].pos[0],gvertices.size(),&indices[0],indices.size());
convex->setUserIndex(shapeId);
}
}
} else
{
btAssert(0);
}
}
};
}
virtual void syncPhysicsToGraphics(const btDiscreteDynamicsWorld* rbWorld)
{

View File

@@ -282,6 +282,26 @@ void GwenUserInterface::init(int width, int height,Gwen::Renderer::Base* rendere
}
void GwenUserInterface::forceUpdateScrollBars()
{
b3Assert(m_data);
b3Assert(m_data->m_explorerTreeCtrl);
if (m_data && m_data->m_explorerTreeCtrl)
{
m_data->m_explorerTreeCtrl->ForceUpdateScrollBars();
}
}
void GwenUserInterface::setFocus()
{
b3Assert(m_data);
b3Assert(m_data->m_explorerTreeCtrl);
if (m_data && m_data->m_explorerTreeCtrl)
{
m_data->m_explorerTreeCtrl->Focus();
}
}
b3ToggleButtonCallback GwenUserInterface::getToggleButtonCallback()
{
return m_data->m_toggleButtonCallback;

View File

@@ -25,6 +25,8 @@ class GwenUserInterface
virtual ~GwenUserInterface();
void init(int width, int height,Gwen::Renderer::Base* gwenRenderer,float retinaScale);
void setFocus();
void forceUpdateScrollBars();
void draw(int width, int height);

View File

@@ -15,7 +15,7 @@ using namespace Gwen::Controls;
GWEN_CONTROL_CONSTRUCTOR( TreeControl )
{
m_TreeControl = this;
m_bUpdateScrollBar = 2;
m_ToggleButton->DelayedDelete();
m_ToggleButton = NULL;
m_Title->DelayedDelete();
@@ -49,7 +49,7 @@ void TreeControl::ForceUpdateScrollBars()
void TreeControl::OnChildBoundsChanged( Gwen::Rect /*oldChildBounds*/, Base* /*pChild*/ )
{
//m_ScrollControl->UpdateScrollBars();
}
void TreeControl::Clear()
@@ -100,7 +100,7 @@ bool TreeControl::OnKeyUp( bool bDown )
{
if (bDown)
{
ForceUpdateScrollBars();
// int maxIndex = 0;
int newIndex = 0;
int maxItem=0;
@@ -151,6 +151,7 @@ bool TreeControl::OnKeyUp( bool bDown )
}
}
}
ForceUpdateScrollBars();
return true;
}
@@ -159,7 +160,7 @@ bool TreeControl::OnKeyDown( bool bDown )
{
if (bDown)
{
ForceUpdateScrollBars();
// int maxIndex = 0;
int newIndex = 0;
int maxItem=0;
@@ -210,6 +211,7 @@ bool TreeControl::OnKeyDown( bool bDown )
}
}
}
ForceUpdateScrollBars();
return true;
}
extern int avoidUpdate;
@@ -220,7 +222,7 @@ bool TreeControl::OnKeyRight( bool bDown )
{
avoidUpdate = -3;
ForceUpdateScrollBars();
iterate(ITERATE_ACTION_OPEN,0,0);
int maxItem=0;
int curItem=0;
@@ -255,6 +257,7 @@ bool TreeControl::OnKeyRight( bool bDown )
}
Invalidate();
}
ForceUpdateScrollBars();
return true;
}
bool TreeControl::OnKeyLeft( bool bDown )
@@ -264,7 +267,7 @@ bool TreeControl::OnKeyLeft( bool bDown )
avoidUpdate = -3;
ForceUpdateScrollBars();
iterate(ITERATE_ACTION_CLOSE,0,0);
@@ -304,11 +307,12 @@ bool TreeControl::OnKeyLeft( bool bDown )
}
//viewSize/contSize
printf("!\n");
//printf("!\n");
//this->Layout(0);
}
ForceUpdateScrollBars();
return true;
}

View File

@@ -144,13 +144,16 @@ void TreeNode::Open()
m_InnerPanel->Show();
if ( m_ToggleButton ) m_ToggleButton->SetToggleState( true );
Invalidate();
m_TreeControl->ForceUpdateScrollBars();
}
void TreeNode::Close()
{
m_InnerPanel->Hide();
if ( m_ToggleButton ) m_ToggleButton->SetToggleState( false );
Invalidate();
m_TreeControl->ForceUpdateScrollBars();
}
void TreeNode::ExpandAll()
@@ -273,6 +276,7 @@ void TreeNode::iterate(int action, int* curIndex, int* targetIndex)
{
Open();
break;
}
case ITERATE_ACTION_CLOSE:

View File

@@ -94,6 +94,8 @@ namespace Gwen
bool m_bRoot;
bool m_bSelected;
bool m_bSelectable;
int m_bUpdateScrollBar;
};
}

View File

@@ -42,6 +42,8 @@ struct CommonRenderInterface
virtual void drawLines(const float* positions, const float color[4], int numPoints, int pointStrideInBytes, const unsigned int* indices, int numIndices, float pointDrawSize)=0;
virtual void drawLine(const float from[4], const float to[4], const float color[4], float lineWidth) = 0;
virtual void drawLine(const double from[4], const double to[4], const double color[4], double lineWidth) = 0;
virtual void drawPoint(const float* position, const float color[4], float pointDrawSize)=0;
virtual void drawPoint(const double* position, const double color[4], double pointDrawSize)=0;
virtual int registerShape(const float* vertices, int numvertices, const int* indices, int numIndices,int primitiveType=B3_GL_TRIANGLES, int textureIndex=-1)=0;
virtual void updateShape(int shapeIndex, const float* vertices)=0;

View File

@@ -1339,10 +1339,19 @@ void GLInstancingRenderer::renderScene()
}
void GLInstancingRenderer::drawPoint(const double* position, const double color[4], double pointDrawSize)
{
float pos[4]={position[0],position[1],position[2],0};
float clr[4] = {color[0],color[1],color[2],color[3]};
drawPoints(pos,clr,1,3*sizeof(float),float(pointDrawSize));
}
void GLInstancingRenderer::drawPoint(const float* positions, const float color[4], float pointDrawSize)
{
drawPoints(positions,color,1,3*sizeof(float),pointDrawSize);
}
void GLInstancingRenderer::drawPoints(const float* positions, const float color[4], int numPoints, int pointStrideInBytes, float pointDrawSize)
{

View File

@@ -104,6 +104,7 @@ public:
virtual void drawLines(const float* positions, const float color[4], int numPoints, int pointStrideInBytes, const unsigned int* indices, int numIndices, float pointDrawSize);
virtual void drawPoints(const float* positions, const float color[4], int numPoints, int pointStrideInBytes, float pointDrawSize);
virtual void drawPoint(const float* position, const float color[4], float pointSize=1);
virtual void drawPoint(const double* position, const double color[4], double pointDrawSize=1);
virtual void updateCamera(int upAxis=1);
virtual void getCameraPosition(float cameraPos[4]);

View File

@@ -38,6 +38,7 @@
</collision>
<inertial>
<mass value="10"/>
<origin rpy="0 1.57075 0" xyz="0 0 -0.3"/>
<inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/>
</inertial>
</link>
@@ -145,6 +146,7 @@
<inertial>
<mass value="10"/>
<inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/>
<origin rpy="0 1.57075 0" xyz="0 0 -0.3"/>
</inertial>
</link>