X11OpenGLWindow: create stencil buffer for shadows in OpenGL2 mode (OpenGL3 uses shadow maps)
Add 'createCollisionObjectGraphicsObject' API for CommonPhysicsSetup Add 'pthread' dependency as workaround for NVIDIA graphics driver issue (see //See https://bugs.launchpad.net/ubuntu/+source/nvidia-graphics-drivers-319/+bug/1248642 )
This commit is contained in:
@@ -18,6 +18,14 @@
|
||||
#include "../ImportURDFDemo/ImportURDFSetup.h"
|
||||
#include "../ImportObjDemo/ImportObjSetup.h"
|
||||
#include "../ImportSTLDemo/ImportSTLSetup.h"
|
||||
#include "../../Demos/SerializeDemo/SerializeSetup.h"
|
||||
#include "../bullet2/MultiBodyDemo/TestJointTorqueSetup.h"
|
||||
|
||||
static BulletDemoInterface* TestJointTorqueCreateFunc(SimpleOpenGL3App* app)
|
||||
{
|
||||
CommonPhysicsSetup* physicsSetup = new TestJointTorqueSetup();
|
||||
return new BasicDemo(app, physicsSetup);
|
||||
}
|
||||
|
||||
static BulletDemoInterface* LuaDemoCreateFunc(SimpleOpenGL3App* app)
|
||||
{
|
||||
@@ -36,7 +44,11 @@ static BulletDemoInterface* MyKinematicObjectCreateFunc(SimpleOpenGL3App* app)
|
||||
CommonPhysicsSetup* physicsSetup = new KinematicObjectSetup();
|
||||
return new BasicDemo(app, physicsSetup);
|
||||
}
|
||||
|
||||
static BulletDemoInterface* MySerializeCreateFunc(SimpleOpenGL3App* app)
|
||||
{
|
||||
CommonPhysicsSetup* physicsSetup = new SerializeSetup();
|
||||
return new BasicDemo(app, physicsSetup);
|
||||
}
|
||||
static BulletDemoInterface* MyConstraintCreateFunc(SimpleOpenGL3App* app)
|
||||
{
|
||||
CommonPhysicsSetup* physicsSetup = new ConstraintPhysicsSetup();
|
||||
@@ -70,7 +82,7 @@ struct BulletDemoEntry
|
||||
|
||||
static BulletDemoEntry allDemos[]=
|
||||
{
|
||||
|
||||
|
||||
//{"emptydemo",EmptyBulletDemo::MyCreateFunc},
|
||||
{0,"API Demos", 0},
|
||||
|
||||
@@ -82,10 +94,11 @@ static BulletDemoEntry allDemos[]=
|
||||
|
||||
{0,"File Formats", 0},
|
||||
//@todo(erwincoumans) { 1, "bullet", MyImportSTLCreateFunc},
|
||||
{ 1, ".bullet",MySerializeCreateFunc},
|
||||
{ 1, "Wavefront Obj", MyImportObjCreateFunc},
|
||||
{ 1, "URDF", MyImportUrdfCreateFunc },
|
||||
{ 1, "STL", MyImportSTLCreateFunc},
|
||||
|
||||
|
||||
/* {1,"ChainDemo",ChainDemo::MyCreateFunc},
|
||||
// {0, "Stress tests", 0 },
|
||||
|
||||
@@ -95,13 +108,15 @@ static BulletDemoEntry allDemos[]=
|
||||
{1,"LemkeHingeDemo",HingeDemo::LemkeCreateFunc},
|
||||
{1,"InertiaHingeDemo",HingeDemo::InertiaCreateFunc},
|
||||
{1,"ABMHingeDemo",HingeDemo::FeatherstoneCreateFunc},
|
||||
|
||||
|
||||
{1,"Ragdoll",RagDollDemo::MyCreateFunc},
|
||||
*/
|
||||
{ 0, "Multibody" ,0},
|
||||
{1,"MultiBody1",FeatherstoneDemo1::MyCreateFunc},
|
||||
// {"MultiBody2",FeatherstoneDemo2::MyCreateFunc},
|
||||
{1,"MultiDofDemo",MultiDofDemo::MyCreateFunc},
|
||||
{1,"TestJointTorque",TestJointTorqueCreateFunc},
|
||||
|
||||
|
||||
};
|
||||
|
||||
|
||||
@@ -44,12 +44,21 @@
|
||||
"../bullet2/BasicDemo/Bullet2RigidBodyDemo.h",
|
||||
"../bullet2/LuaDemo/LuaPhysicsSetup.cpp",
|
||||
"../bullet2/LuaDemo/LuaPhysicsSetup.h",
|
||||
"../bullet2/MultiBodyDemo/TestJointTorqueSetup.cpp",
|
||||
"../bullet2/MultiBodyDemo/TestJointTorqueSetup.h",
|
||||
-- "../DifferentialGearDemo/DifferentialGearSetup.cpp",
|
||||
-- "../DifferentialGearDemo/DifferentialGearSetup.h",
|
||||
"../../Demos/BasicDemo/BasicDemoPhysicsSetup.cpp",
|
||||
"../../Demos/BasicDemo/BasicDemoPhysicsSetup.h",
|
||||
"../../Demos/CcdPhysicsDemo/CcdPhysicsSetup.cpp",
|
||||
"../../Demos/CcdPhysicsDemo/CcdPhysicsSetup.h",
|
||||
"../../Demos/SerializeDemo/SerializeSetup.cpp",
|
||||
"../../Extras/Serialize/BulletFileLoader/bChunk.cpp",
|
||||
"../../Extras/Serialize/BulletFileLoader/bDNA.cpp",
|
||||
"../../Extras/Serialize/BulletFileLoader/bFile.cpp",
|
||||
"../../Extras/Serialize/BulletFileLoader/btBulletFile.cpp",
|
||||
"../../Extras/Serialize/BulletWorldImporter/btBulletWorldImporter.cpp",
|
||||
"../../Extras/Serialize/BulletWorldImporter/btWorldImporter.cpp",
|
||||
"../bullet2/ConstraintDemo/ConstraintPhysicsSetup.cpp",
|
||||
"../bullet2/ConstraintDemo/ConstraintPhysicsSetup.h",
|
||||
"../ImportURDFDemo/ImportURDFSetup.cpp",
|
||||
|
||||
@@ -144,7 +144,7 @@ int main(int argc, char* argv[])
|
||||
}
|
||||
if (majorGlVersion>=3 && wci.m_openglVersion>=3)
|
||||
{
|
||||
float retinaScale = 1.f;
|
||||
// float retinaScale = 1.f;
|
||||
|
||||
#ifndef __APPLE__
|
||||
#ifndef _WIN32
|
||||
@@ -154,14 +154,15 @@ int main(int argc, char* argv[])
|
||||
glewInit();
|
||||
#endif
|
||||
|
||||
//we ned to call glGetError twice, because of some Ubuntu/Intel/OpenGL issue
|
||||
//we need to call glGetError twice, because of some Ubuntu/Intel/OpenGL issue
|
||||
|
||||
GLuint err = glGetError();
|
||||
err = glGetError();
|
||||
btAssert(err==GL_NO_ERROR);
|
||||
glGetError();
|
||||
glGetError();
|
||||
|
||||
btAssert(glGetError()==GL_NO_ERROR);
|
||||
|
||||
|
||||
retinaScale = window->getRetinaScale();
|
||||
//retinaScale = window->getRetinaScale();
|
||||
|
||||
//primRenderer = new GLPrimitiveRenderer(sWidth,sHeight);
|
||||
//sth_stash* font = initFont(primRenderer );
|
||||
|
||||
@@ -364,21 +364,40 @@ void ImportUrdfDemo::initPhysics(GraphicsPhysicsBridge& gfxBridge)
|
||||
gravity[upAxis]=-9.8;
|
||||
|
||||
m_dynamicsWorld->setGravity(gravity);
|
||||
int argc=0;
|
||||
const char* filename="somefile.urdf";
|
||||
//int argc=0;
|
||||
const char* someFileName="r2d2.urdf";
|
||||
|
||||
std::string xml_string;
|
||||
|
||||
const char* prefix[]={"./","./data/","../data/","../../data/","../../../data/","../../../../data/"};
|
||||
int numPrefixes = sizeof(prefix)/sizeof(const char*);
|
||||
char relativeFileName[1024];
|
||||
FILE* f=0;
|
||||
bool fileFound = false;
|
||||
int result = 0;
|
||||
|
||||
for (int i=0;!f && i<numPrefixes;i++)
|
||||
{
|
||||
sprintf(relativeFileName,"%s%s",prefix[i],someFileName);
|
||||
f = fopen(relativeFileName,"rb");
|
||||
if (f)
|
||||
{
|
||||
fileFound = true;
|
||||
break;
|
||||
}
|
||||
}
|
||||
if (f)
|
||||
{
|
||||
fclose(f);
|
||||
}
|
||||
|
||||
if (argc < 2){
|
||||
std::cerr << "No URDF file name provided, using a dummy test URDF" << std::endl;
|
||||
|
||||
if (!fileFound){
|
||||
std::cerr << "URDF file not found, using a dummy test URDF" << std::endl;
|
||||
xml_string = std::string(urdf_char);
|
||||
|
||||
} else
|
||||
{
|
||||
|
||||
|
||||
std::fstream xml_file(filename, std::fstream::in);
|
||||
std::fstream xml_file(relativeFileName, std::fstream::in);
|
||||
while ( xml_file.good() )
|
||||
{
|
||||
std::string line;
|
||||
@@ -407,7 +426,8 @@ void ImportUrdfDemo::initPhysics(GraphicsPhysicsBridge& gfxBridge)
|
||||
printTree(root_link);
|
||||
btTransform worldTrans;
|
||||
worldTrans.setIdentity();
|
||||
|
||||
|
||||
if (1)
|
||||
{
|
||||
URDF2BulletMappings mappings;
|
||||
URDFvisual2BulletCollisionShape(root_link, gfxBridge, worldTrans,m_dynamicsWorld,mappings);
|
||||
|
||||
@@ -2,14 +2,14 @@
|
||||
#define IMPORT_URDF_SETUP_H
|
||||
|
||||
|
||||
#include "../../Demos/CommonRigidBodySetup.h"
|
||||
#include "../../Demos/CommonMultiBodySetup.h"
|
||||
|
||||
class ImportUrdfDemo : public CommonRigidBodySetup
|
||||
class ImportUrdfDemo : public CommonMultiBodySetup
|
||||
{
|
||||
public:
|
||||
ImportUrdfDemo();
|
||||
virtual ~ImportUrdfDemo();
|
||||
|
||||
|
||||
virtual void initPhysics(GraphicsPhysicsBridge& gfxBridge);
|
||||
};
|
||||
|
||||
|
||||
@@ -11,15 +11,13 @@ int main(int argc, char* argv[])
|
||||
{
|
||||
b3CommandLineArgs myArgs(argc,argv);
|
||||
|
||||
float dt = 1./120.f;
|
||||
|
||||
SimpleOpenGL3App* app = new SimpleOpenGL3App("SimpleOpenGL3App",1024,768);
|
||||
app->m_instancingRenderer->setCameraDistance(13);
|
||||
app->m_instancingRenderer->setCameraPitch(0);
|
||||
app->m_instancingRenderer->setCameraTargetPosition(b3MakeVector3(0,0,0));
|
||||
|
||||
GLint err = glGetError();
|
||||
assert(err==GL_NO_ERROR);
|
||||
assert(glGetError()==GL_NO_ERROR);
|
||||
|
||||
myArgs.GetCmdLineArgument("mp4_file",gVideoFileName);
|
||||
if (gVideoFileName)
|
||||
@@ -40,8 +38,7 @@ int main(int argc, char* argv[])
|
||||
app->dumpNextFrameToPng(fileName);
|
||||
}
|
||||
|
||||
GLint err = glGetError();
|
||||
assert(err==GL_NO_ERROR);
|
||||
assert(glGetError()==GL_NO_ERROR);
|
||||
app->m_instancingRenderer->init();
|
||||
app->m_instancingRenderer->updateCamera();
|
||||
|
||||
|
||||
@@ -21,6 +21,10 @@ struct MyGraphicsPhysicsBridge : public GraphicsPhysicsBridge
|
||||
{
|
||||
}
|
||||
virtual void createRigidBodyGraphicsObject(btRigidBody* body, const btVector3& color)
|
||||
{
|
||||
createCollisionObjectGraphicsObject(body,color);
|
||||
}
|
||||
virtual void createCollisionObjectGraphicsObject(btCollisionObject* body, const btVector3& color)
|
||||
{
|
||||
btCollisionShape* shape = body->getCollisionShape();
|
||||
btTransform startTransform = body->getWorldTransform();
|
||||
@@ -45,7 +49,7 @@ struct MyGraphicsPhysicsBridge : public GraphicsPhysicsBridge
|
||||
}
|
||||
case TRIANGLE_MESH_SHAPE_PROXYTYPE:
|
||||
{
|
||||
|
||||
|
||||
break;
|
||||
}
|
||||
default:
|
||||
@@ -149,7 +153,7 @@ struct MyGraphicsPhysicsBridge : public GraphicsPhysicsBridge
|
||||
{
|
||||
return m_glApp->m_parameterInterface;
|
||||
}
|
||||
|
||||
|
||||
virtual void setUpAxis(int axis)
|
||||
{
|
||||
m_glApp->setUpAxis(axis);
|
||||
@@ -233,7 +237,7 @@ btVector3 Bullet2RigidBodyDemo::getRayTo(int x,int y)
|
||||
btVector3 rightOffset;
|
||||
btVector3 cameraUp=btVector3(0,0,0);
|
||||
cameraUp[m_glApp->getUpAxis()]=1;
|
||||
|
||||
|
||||
btVector3 vertical = cameraUp;
|
||||
|
||||
btVector3 hor;
|
||||
@@ -291,7 +295,7 @@ bool Bullet2RigidBodyDemo::mouseButtonCallback(int button, int state, float x, f
|
||||
|
||||
btVector3 rayFrom = camPos;
|
||||
btVector3 rayTo = getRayTo(x,y);
|
||||
|
||||
|
||||
m_physicsSetup->pickBody(rayFrom, rayTo);
|
||||
|
||||
|
||||
|
||||
248
Demos3/bullet2/MultiBodyDemo/TestJointTorqueSetup.cpp
Normal file
248
Demos3/bullet2/MultiBodyDemo/TestJointTorqueSetup.cpp
Normal file
@@ -0,0 +1,248 @@
|
||||
//test addJointTorque
|
||||
#include "TestJointTorqueSetup.h"
|
||||
|
||||
#include "BulletDynamics/Featherstone/btMultiBodyLinkCollider.h"
|
||||
TestJointTorqueSetup::TestJointTorqueSetup()
|
||||
{
|
||||
}
|
||||
|
||||
TestJointTorqueSetup::~TestJointTorqueSetup()
|
||||
{
|
||||
|
||||
}
|
||||
|
||||
void TestJointTorqueSetup::initPhysics(GraphicsPhysicsBridge& gfxBridge)
|
||||
{
|
||||
int upAxis = 2;
|
||||
|
||||
btVector4 colors[4] =
|
||||
{
|
||||
btVector4(1,0,0,1),
|
||||
btVector4(0,1,0,1),
|
||||
btVector4(0,1,1,1),
|
||||
btVector4(1,1,0,1),
|
||||
};
|
||||
int curColor = 0;
|
||||
|
||||
|
||||
|
||||
gfxBridge.setUpAxis(upAxis);
|
||||
|
||||
this->createEmptyDynamicsWorld();
|
||||
gfxBridge.createPhysicsDebugDrawer(m_dynamicsWorld);
|
||||
m_dynamicsWorld->getDebugDrawer()->setDebugMode(
|
||||
//btIDebugDraw::DBG_DrawConstraints
|
||||
+btIDebugDraw::DBG_DrawWireframe
|
||||
+btIDebugDraw::DBG_DrawContactPoints
|
||||
+btIDebugDraw::DBG_DrawAabb
|
||||
);//+btIDebugDraw::DBG_DrawConstraintLimits);
|
||||
|
||||
//create a static ground object
|
||||
if (0)
|
||||
{
|
||||
btVector3 groundHalfExtents(20,20,20);
|
||||
groundHalfExtents[upAxis]=1.f;
|
||||
btBoxShape* box = new btBoxShape(groundHalfExtents);
|
||||
box->initializePolyhedralFeatures();
|
||||
|
||||
gfxBridge.createCollisionShapeGraphicsObject(box);
|
||||
btTransform start; start.setIdentity();
|
||||
btVector3 groundOrigin(0,0,0);
|
||||
groundOrigin[upAxis]=-1.5;
|
||||
start.setOrigin(groundOrigin);
|
||||
btRigidBody* body = createRigidBody(0,start,box);
|
||||
btVector4 color = colors[curColor];
|
||||
curColor++;
|
||||
curColor&=3;
|
||||
gfxBridge.createRigidBodyGraphicsObject(body,color);
|
||||
}
|
||||
|
||||
{
|
||||
bool floating = false;
|
||||
bool damping = true;
|
||||
bool gyro = true;
|
||||
int numLinks = 5;
|
||||
bool spherical = false; //set it ot false -to use 1DoF hinges instead of 3DoF sphericals
|
||||
bool canSleep = false;
|
||||
bool selfCollide = false;
|
||||
btVector3 linkHalfExtents(0.05, 0.37, 0.1);
|
||||
btVector3 baseHalfExtents(0.05, 0.37, 0.1);
|
||||
|
||||
btVector3 basePosition = btVector3(-0.4f, 3.f, 0.f);
|
||||
//mbC->forceMultiDof(); //if !spherical, you can comment this line to check the 1DoF algorithm
|
||||
//init the base
|
||||
btVector3 baseInertiaDiag(0.f, 0.f, 0.f);
|
||||
float baseMass = 1.f;
|
||||
|
||||
if(baseMass)
|
||||
{
|
||||
btCollisionShape *pTempBox = new btBoxShape(btVector3(baseHalfExtents[0], baseHalfExtents[1], baseHalfExtents[2]));
|
||||
pTempBox->calculateLocalInertia(baseMass, baseInertiaDiag);
|
||||
delete pTempBox;
|
||||
}
|
||||
|
||||
bool isMultiDof = false;
|
||||
btMultiBody *pMultiBody = new btMultiBody(numLinks, baseMass, baseInertiaDiag, !floating, canSleep, isMultiDof);
|
||||
m_multiBody = pMultiBody;
|
||||
btQuaternion baseOriQuat(0.f, 0.f, 0.f, 1.f);
|
||||
pMultiBody->setBasePos(basePosition);
|
||||
pMultiBody->setWorldToBaseRot(baseOriQuat);
|
||||
btVector3 vel(0, 0, 0);
|
||||
// pMultiBody->setBaseVel(vel);
|
||||
|
||||
//init the links
|
||||
btVector3 hingeJointAxis(1, 0, 0);
|
||||
float linkMass = 1.f;
|
||||
btVector3 linkInertiaDiag(0.f, 0.f, 0.f);
|
||||
|
||||
btCollisionShape *pTempBox = new btBoxShape(btVector3(linkHalfExtents[0], linkHalfExtents[1], linkHalfExtents[2]));
|
||||
pTempBox->calculateLocalInertia(linkMass, linkInertiaDiag);
|
||||
delete pTempBox;
|
||||
|
||||
//y-axis assumed up
|
||||
btVector3 parentComToCurrentCom(0, -linkHalfExtents[1] * 2.f, 0); //par body's COM to cur body's COM offset
|
||||
btVector3 currentPivotToCurrentCom(0, -linkHalfExtents[1], 0); //cur body's COM to cur body's PIV offset
|
||||
btVector3 parentComToCurrentPivot = parentComToCurrentCom - currentPivotToCurrentCom; //par body's COM to cur body's PIV offset
|
||||
|
||||
//////
|
||||
btScalar q0 = 0.f * SIMD_PI/ 180.f;
|
||||
btQuaternion quat0(btVector3(0, 1, 0).normalized(), q0);
|
||||
quat0.normalize();
|
||||
/////
|
||||
|
||||
for(int i = 0; i < numLinks; ++i)
|
||||
{
|
||||
if(!spherical)
|
||||
pMultiBody->setupRevolute(i, linkMass, linkInertiaDiag, i - 1, btQuaternion(0.f, 0.f, 0.f, 1.f), hingeJointAxis, parentComToCurrentPivot, currentPivotToCurrentCom, false);
|
||||
else
|
||||
//pMultiBody->setupPlanar(i, linkMass, linkInertiaDiag, i - 1, btQuaternion(0.f, 0.f, 0.f, 1.f)/*quat0*/, btVector3(1, 0, 0), parentComToCurrentPivot*2, false);
|
||||
pMultiBody->setupSpherical(i, linkMass, linkInertiaDiag, i - 1, btQuaternion(0.f, 0.f, 0.f, 1.f), parentComToCurrentPivot, currentPivotToCurrentCom, false);
|
||||
}
|
||||
|
||||
//pMultiBody->finalizeMultiDof();
|
||||
|
||||
btMultiBodyDynamicsWorld* world = m_dynamicsWorld;
|
||||
|
||||
///
|
||||
world->addMultiBody(pMultiBody);
|
||||
btMultiBody* mbC = pMultiBody;
|
||||
mbC->setCanSleep(canSleep);
|
||||
mbC->setHasSelfCollision(selfCollide);
|
||||
mbC->setUseGyroTerm(gyro);
|
||||
//
|
||||
if(!damping)
|
||||
{
|
||||
mbC->setLinearDamping(0.f);
|
||||
mbC->setAngularDamping(0.f);
|
||||
}else
|
||||
{ mbC->setLinearDamping(0.1f);
|
||||
mbC->setAngularDamping(0.9f);
|
||||
}
|
||||
//
|
||||
btVector3 gravity(0,0,0);
|
||||
//gravity[upAxis] = -9.81;
|
||||
m_dynamicsWorld->setGravity(gravity);
|
||||
//////////////////////////////////////////////
|
||||
if(numLinks > 0)
|
||||
{
|
||||
btScalar q0 = 45.f * SIMD_PI/ 180.f;
|
||||
if(!spherical)
|
||||
if(mbC->isMultiDof())
|
||||
mbC->setJointPosMultiDof(0, &q0);
|
||||
else
|
||||
mbC->setJointPos(0, q0);
|
||||
else
|
||||
{
|
||||
btQuaternion quat0(btVector3(1, 1, 0).normalized(), q0);
|
||||
quat0.normalize();
|
||||
mbC->setJointPosMultiDof(0, quat0);
|
||||
}
|
||||
}
|
||||
///
|
||||
|
||||
btAlignedObjectArray<btQuaternion> world_to_local;
|
||||
world_to_local.resize(pMultiBody->getNumLinks() + 1);
|
||||
|
||||
btAlignedObjectArray<btVector3> local_origin;
|
||||
local_origin.resize(pMultiBody->getNumLinks() + 1);
|
||||
world_to_local[0] = pMultiBody->getWorldToBaseRot();
|
||||
local_origin[0] = pMultiBody->getBasePos();
|
||||
double friction = 1;
|
||||
{
|
||||
|
||||
// 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 (1)
|
||||
{
|
||||
btCollisionShape* box = new btBoxShape(baseHalfExtents);
|
||||
gfxBridge.createCollisionShapeGraphicsObject(box);
|
||||
|
||||
btMultiBodyLinkCollider* col= new btMultiBodyLinkCollider(pMultiBody, -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);
|
||||
|
||||
world->addCollisionObject(col, 2,1+2);
|
||||
|
||||
btVector3 color(0.0,0.0,0.5);
|
||||
gfxBridge.createCollisionObjectGraphicsObject(col,color);
|
||||
|
||||
col->setFriction(friction);
|
||||
pMultiBody->setBaseCollider(col);
|
||||
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
for (int i=0; i < pMultiBody->getNumLinks(); ++i)
|
||||
{
|
||||
const int parent = pMultiBody->getParent(i);
|
||||
world_to_local[i+1] = pMultiBody->getParentToLocalRot(i) * world_to_local[parent+1];
|
||||
local_origin[i+1] = local_origin[parent+1] + (quatRotate(world_to_local[i+1].inverse() , pMultiBody->getRVector(i)));
|
||||
}
|
||||
|
||||
|
||||
for (int i=0; i < pMultiBody->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(linkHalfExtents);
|
||||
gfxBridge.createCollisionShapeGraphicsObject(box);
|
||||
btMultiBodyLinkCollider* col = new btMultiBodyLinkCollider(pMultiBody, 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);
|
||||
world->addCollisionObject(col,2,1+2);
|
||||
btVector4 color = colors[curColor];
|
||||
curColor++;
|
||||
curColor&=3;
|
||||
gfxBridge.createCollisionObjectGraphicsObject(col,color);
|
||||
|
||||
|
||||
pMultiBody->getLink(i).m_collider=col;
|
||||
}
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
void TestJointTorqueSetup::stepSimulation(float deltaTime)
|
||||
{
|
||||
m_multiBody->addJointTorque(0, 10.0);
|
||||
m_dynamicsWorld->stepSimulation(deltaTime);
|
||||
}
|
||||
|
||||
21
Demos3/bullet2/MultiBodyDemo/TestJointTorqueSetup.h
Normal file
21
Demos3/bullet2/MultiBodyDemo/TestJointTorqueSetup.h
Normal file
@@ -0,0 +1,21 @@
|
||||
#ifndef TEST_JOINT_TORQUE_SETUP_H
|
||||
#define TEST_JOINT_TORQUE_SETUP_H
|
||||
|
||||
#include "../../../Demos/CommonMultiBodySetup.h"
|
||||
|
||||
struct TestJointTorqueSetup : public CommonMultiBodySetup
|
||||
{
|
||||
btMultiBody* m_multiBody;
|
||||
|
||||
public:
|
||||
|
||||
TestJointTorqueSetup();
|
||||
virtual ~TestJointTorqueSetup();
|
||||
|
||||
virtual void initPhysics(GraphicsPhysicsBridge& gfxBridge);
|
||||
|
||||
virtual void stepSimulation(float deltaTime);
|
||||
|
||||
};
|
||||
#endif //TEST_JOINT_TORQUE_SETUP_H
|
||||
|
||||
Reference in New Issue
Block a user