I had the same problem when I started using Bullet, although I was doing something differently wrong from you.
Attached is my working code. Hopefully you can find it of some use to see what you're missing.
Code: Select all
#include "p_collision.h"
#include "p_object.h"
#include "p_world.h"
#include "u_list.h"
#include "r_timer.h"
#include "z_mem.h"
#include "m_print.h"
namespace Collision
{
btDefaultCollisionConfiguration* collisionConfiguration = NULL;
btCollisionDispatcher* dispatcher = NULL;
btDiscreteDynamicsWorld* dynamicsWorld = NULL;
btAxisSweep3* overlappingPairCache = NULL;
btSequentialImpulseConstraintSolver* solver = NULL;
colshape_t *colHead = NULL;
//keep track of the shapes, we release memory at exit.
//make sure to re-use collision shapes among rigid bodies whenever possible!
btAlignedObjectArray<btCollisionShape*> collisionShapes;
// The btObjectMotionState provides an implementation to synchronize world transforms with offsets
// to the objects.
struct btObjectMotionState : public btMotionState
{
btTransform m_graphicsWorldTrans;
btTransform m_centerOfMassOffset;
btTransform m_startWorldTrans;
Object::object_t *object;
btRigidBody *rigidBody;
btObjectMotionState(const btTransform& startTrans = btTransform::getIdentity(),const btTransform& centerOfMassOffset = btTransform::getIdentity())
: m_graphicsWorldTrans(startTrans),
m_centerOfMassOffset(centerOfMassOffset),
m_startWorldTrans(startTrans),
object(0)
{
}
void setObject(Object::object_t *pObj)
{
object = pObj;
}
void setRigidBody(btRigidBody *body)
{
rigidBody = body;
}
///synchronizes world transform from user to physics
virtual void getWorldTransform(btTransform& centerOfMassWorldTrans ) const
{
centerOfMassWorldTrans = m_centerOfMassOffset.inverse() * m_graphicsWorldTrans ;
}
///synchronizes world transform from physics to user
///Bullet only calls the update of worldtransform for active objects
virtual void setWorldTransform(const btTransform& centerOfMassWorldTrans)
{
m_graphicsWorldTrans = centerOfMassWorldTrans * m_centerOfMassOffset ;
getPosition(rigidBody, (Vector::vector_t*)&object->x);
getMomentum(rigidBody, (Vector::vector_t*)&object->momx);
}
};
// Callback for object hitting...something
void ObjectNarrowCallback (btBroadphasePair &collisionPair, btCollisionDispatcher &dispatcher, btDispatcherInfo &dispatchInfo)
{
// Do your collision logic here
// Only dispatch the Bullet collision information if you want the physics to continue
btCollisionObject* colObj0 = (btCollisionObject*)collisionPair.m_pProxy0->m_clientObject;
btCollisionObject* colObj1 = (btCollisionObject*)collisionPair.m_pProxy1->m_clientObject;
if (dispatcher.needsCollision(colObj0,colObj1))
{
//dispatcher will keep algorithms persistent in the collision pair
if (!collisionPair.m_algorithm)
{
collisionPair.m_algorithm = dispatcher.findAlgorithm(colObj0,colObj1);
}
if (collisionPair.m_algorithm)
{
btManifoldResult contactPointResult(colObj0,colObj1);
if (dispatchInfo.m_dispatchFunc == btDispatcherInfo::DISPATCH_DISCRETE)
{
//discrete collision detection query
collisionPair.m_algorithm->processCollision(colObj0,colObj1,dispatchInfo,&contactPointResult);
} else
{
//continuous collision detection query, time of impact (toi)
btScalar toi = collisionPair.m_algorithm->calculateTimeOfImpact(colObj0,colObj1,dispatchInfo,&contactPointResult);
if (dispatchInfo.m_timeOfImpact > toi)
dispatchInfo.m_timeOfImpact = toi;
}
btPersistentManifold *contactManifold = contactPointResult.getPersistentManifold();
if ((colObj0->getUserPointer() && !colObj1->getUserPointer())
|| (!colObj0->getUserPointer() && colObj1->getUserPointer())) // One of the objects is a triangle mesh
{
Object::object_t *object;
int numContacts = contactManifold->getNumContacts();
if (colObj0->getUserPointer())
object = (Object::object_t*)colObj0->getUserPointer();
else if (colObj1->getUserPointer())
object = (Object::object_t*)colObj1->getUserPointer();
int i;
for (i = 0; i < numContacts; i++)
{
btManifoldPoint &pt = contactManifold->getContactPoint(i);
btVector3 pointVec = pt.getPositionWorldOnB();
// Get pt - object vector
// Normalize
// Do dot product with object up vector
// Is it positive? Then we have a floor (I guess...)
Vector::vector_t ptVec;
Vector::Load(&ptVec, pointVec.getX() - object->x, pointVec.getY() - object->y, pointVec.getZ() - object->z);
Vector::Normalize(&ptVec);
if (Vector::Dot((Vector::vector_t*)&object->upx, &ptVec) > 0)
{
// Floor?
object->upx = ptVec.x;
object->upy = ptVec.y;
object->upz = ptVec.z;
}
}
}
}
}
}
void Init(void)
{
///collision configuration contains default setup for memory, collision setup. Advanced users can create their own configuration.
collisionConfiguration = new btDefaultCollisionConfiguration();
///use the default collision dispatcher. For parallel processing you can use a diffent dispatcher (see Extras/BulletMultiThreaded)
dispatcher = new btCollisionDispatcher(collisionConfiguration);
dispatcher->setNearCallback((btNearCallback)ObjectNarrowCallback);
///the default constraint solver. For parallel processing you can use a different solver (see Extras/BulletMultiThreaded)
solver = new btSequentialImpulseConstraintSolver;
colHead = NULL;
Err_Printf("Collision::Init()\n");
}
void SetupWorld(Vector::vector_t *min, Vector::vector_t *max, Vector::vector_t *gravity)
{
///the maximum size of the collision world. Make sure objects stay within these boundaries
///Don't make the world AABB size too large, it will harm simulation quality and performance
btVector3 worldAabbMin(min->x,min->y,min->z);
btVector3 worldAabbMax(max->x, max->y, max->z);
int maxProxies = 1024;
if (overlappingPairCache)
delete overlappingPairCache;
overlappingPairCache = new btAxisSweep3(worldAabbMin,worldAabbMax,maxProxies);
dynamicsWorld = new btDiscreteDynamicsWorld(dispatcher,overlappingPairCache,solver,collisionConfiguration);
dynamicsWorld->setGravity(btVector3(gravity->x, gravity->y, gravity->z));
Err_Printf("Collision::SetupWorld()\n");
}
void Update(void)
{
dynamicsWorld->stepSimulation(1,10);
Err_Printf("Collision::Update(%d)\n", Timer::gamecount);
}
colshape_t *AddSphere(void *userPtr, float pX, float pY, float pZ, float pRadius, float pMass)
{
//create a dynamic rigidbody
colshape_t *newColshape = (colshape_t*)Z_Malloc(sizeof(colshape_t), ZT_COLLISIONOBJ);
newColshape->colShape = new btSphereShape(btScalar(pRadius));
collisionShapes.push_back(newColshape->colShape);
// Create Dynamic Object
btTransform startTransform;
startTransform.setIdentity();
btScalar mass(pMass);
//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)
newColshape->colShape->calculateLocalInertia(mass,localInertia);
startTransform.setOrigin(btVector3(pX,pY,pZ));
newColshape->colShape->setUserPointer(userPtr);
//using motionstate is recommended, it provides interpolation capabilities, and only synchronizes 'active' objects
btObjectMotionState* myMotionState = new btObjectMotionState(startTransform);
myMotionState->setObject((Object::object_t*)userPtr);
btRigidBody::btRigidBodyConstructionInfo rbInfo(mass,myMotionState,newColshape->colShape,localInertia);
btRigidBody* body = new btRigidBody(rbInfo);
myMotionState->setRigidBody(body);
newColshape->rigidBody = body;
dynamicsWorld->addRigidBody(body);
// testing stuff
/* body->setRestitution(0.8f);
body->setFriction(0.5f);*/
List::Add((List::item_t*)newColshape, (List::item_t**)&colHead);
Err_Printf("Collision::AddSphere()\n");
return newColshape;
}
void setMomentum(colshape_t *colShape, Vector::vector_t *mom, boolean relative)
{
btRigidBody *body = colShape->rigidBody;
if (body && body->getMotionState())
{
btVector3 velocity;
if (relative)
{
velocity = body->getLinearVelocity();
velocity.setX(velocity.getX() + mom->x);
velocity.setY(velocity.getY() + mom->y);
velocity.setZ(velocity.getZ() + mom->z);
}
else
{
velocity.setX(mom->x);
velocity.setY(mom->y);
velocity.setZ(mom->z);
}
body->setLinearVelocity(velocity);
}
}
void getMomentum(btRigidBody *body, Vector::vector_t *mom)
{
btVector3 velocity = body->getLinearVelocity();
mom->x = velocity.getX();
mom->y = velocity.getY();
mom->z = velocity.getZ();
}
void getMomentum(colshape_t *colShape, Vector::vector_t *mom)
{
btRigidBody *body = colShape->rigidBody;
if (body && body->getMotionState())
{
getMomentum(body, mom);
}
}
void setPosition(colshape_t *colShape, Vector::vector_t *pos)
{
btTransform trans;
trans.setIdentity();
btVector3 origin;
origin.setX(pos->x);
origin.setY(pos->y);
origin.setZ(pos->z);
trans.setOrigin(origin);
btRigidBody *body = colShape->rigidBody;
if (body && body->getMotionState())
body->setWorldTransform(trans);
}
void getPosition(btRigidBody *body, Vector::vector_t *pos)
{
btTransform trans;
body->getMotionState()->getWorldTransform(trans);
pos->x = float(trans.getOrigin().getX());
pos->y = float(trans.getOrigin().getY());
pos->z = float(trans.getOrigin().getZ());
}
void getPosition(colshape_t *colShape, Vector::vector_t *pos)
{
btRigidBody *body = colShape->rigidBody;
if (body && body->getMotionState())
{
getPosition(body, pos);
}
}
colshape_t *AddBox(void *userPtr, float pX, float pY, float pZ, float pWidth, float pHeight, float pDepth, float pMass)
{
//create a dynamic rigidbody
colshape_t *newColshape = (colshape_t*)Z_Malloc(sizeof(colshape_t), ZT_COLLISIONOBJ);
newColshape->colShape = new btBoxShape(btVector3(pWidth,pHeight,pDepth));
collisionShapes.push_back(newColshape->colShape);
// Create Dynamic Object
btTransform startTransform;
startTransform.setIdentity();
btScalar mass(pMass);
//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)
newColshape->colShape->calculateLocalInertia(mass,localInertia);
startTransform.setOrigin(btVector3(pX,pY,pZ));
newColshape->colShape->setUserPointer(userPtr);
//using motionstate is recommended, it provides interpolation capabilities, and only synchronizes 'active' objects
btObjectMotionState* myMotionState = new btObjectMotionState(startTransform);
myMotionState->setObject((Object::object_t*)userPtr);
btRigidBody::btRigidBodyConstructionInfo rbInfo(mass,myMotionState,newColshape->colShape,localInertia);
btRigidBody* body = new btRigidBody(rbInfo);
myMotionState->setRigidBody(body);
newColshape->rigidBody = body;
dynamicsWorld->addRigidBody(body);
List::Add((List::item_t*)newColshape, (List::item_t**)&colHead);
Err_Printf("Collision::AddBox()\n");
return newColshape;
}
//
// AddWorldMesh
//
// Adds the static world mesh to the collision list
//
void AddWorldMesh(World::polygon_t *polyArray, int numPolys)
{
btTriangleMesh *trimesh = new btTriangleMesh();
btTransform startTransform;
startTransform.setIdentity();
btScalar mass(0.f);
World::polygon_t *element = polyArray;
int i;
for (i = 0; i < numPolys; i++)
{
btVector3 vertex0(element->triangle.vertices[0], element->triangle.vertices[1], element->triangle.vertices[2]);
btVector3 vertex1(element->triangle.vertices[3], element->triangle.vertices[4], element->triangle.vertices[5]);
btVector3 vertex2(element->triangle.vertices[6], element->triangle.vertices[7], element->triangle.vertices[8]);
trimesh->addTriangle(vertex0, vertex1, vertex2);
element++;
}
btBvhTriangleMeshShape *bvtTrimesh = new btBvhTriangleMeshShape(trimesh, true);
btDefaultMotionState* myMotionState = new btDefaultMotionState(startTransform);
btVector3 localInertia(0,0,0);
btRigidBody::btRigidBodyConstructionInfo rbInfo(mass,myMotionState,bvtTrimesh,localInertia);
btRigidBody* body = new btRigidBody(rbInfo);
collisionShapes.push_back(bvtTrimesh);
dynamicsWorld->addRigidBody(body);
//testing stuff
body->setRestitution(0.8f);
body->setFriction(0.5f);
Err_Printf("Collision::AddWorldMesh (%d triangles)\n", numPolys);
}
void Shutdown(void)
{
int i;
if (dynamicsWorld)
{
//remove the rigidbodies from the dynamics world and delete them
for (i=dynamicsWorld->getNumCollisionObjects()-1; i>=0 ;i--)
{
btCollisionObject* obj = dynamicsWorld->getCollisionObjectArray()[i];
btRigidBody* body = btRigidBody::upcast(obj);
if (body && body->getMotionState())
{
delete body->getMotionState();
}
dynamicsWorld->removeCollisionObject( obj );
delete obj;
}
}
//delete collision shapes
for (int j=0;j<collisionShapes.size();j++)
{
btCollisionShape* shape = collisionShapes[j];
collisionShapes[j] = 0;
delete shape;
}
Z_FreeTags(ZT_COLLISIONOBJ, ZT_COLLISIONOBJ);
colHead = NULL;
//delete dynamics world
if (dynamicsWorld)
delete dynamicsWorld;
dynamicsWorld = NULL;
//delete solver
if (solver)
delete solver;
solver = NULL;
//delete broadphase
if (overlappingPairCache)
delete overlappingPairCache;
overlappingPairCache = NULL;
//delete dispatcher
if (dispatcher)
delete dispatcher;
dispatcher = NULL;
if (collisionConfiguration)
delete collisionConfiguration;
collisionConfiguration = NULL;
//next line is optional: it will be cleared by the destructor when the array goes out of scope
collisionShapes.clear();
Err_Printf("Collision::Shutdown()\n");
}
}