Super simple demo has objects passing through others

Spaddlewit
Posts: 28
Joined: Fri Sep 04, 2009 8:23 pm

Super simple demo has objects passing through others

Post by Spaddlewit »

Hi,

I've created a small Bullet demo to try and get some simple things working, and hoping it might be of use to some others just getting started. However, when I start the simulation, the box or sphere objects fall right through the triangle mesh. Any idea what I could be doing wrong?

I call the functions in this order:
Init();
SetupWorld();
AddWorldMesh();
AddBox();

Update() is called 60 times per second.

Code: Select all

#include "p_collision.h"
#include "p_world.h"
#include "u_list.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;

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);

	///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.f/60.f,10);
	Err_Printf("Collision::Update()\n");
}

colshape_t *AddSphere(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));
		
	//using motionstate is recommended, it provides interpolation capabilities, and only synchronizes 'active' objects
	btDefaultMotionState* myMotionState = new btDefaultMotionState(startTransform);
	btRigidBody::btRigidBodyConstructionInfo rbInfo(mass,myMotionState,newColshape->colShape,localInertia);
	btRigidBody* body = new btRigidBody(rbInfo);

	newColshape->rigidBody = body;

	dynamicsWorld->addRigidBody(body);

	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->getAngularVelocity();
			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->setAngularVelocity(velocity);
	}
}

void getMomentum(colshape_t *colShape, Vector::vector_t *mom)
{
	btRigidBody *body = colShape->rigidBody;
	if (body && body->getMotionState())
	{
		btVector3 velocity = body->getAngularVelocity();
		mom->x = velocity.getX();
		mom->y = velocity.getY();
		mom->z = velocity.getZ();
	}
}

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(colshape_t *colShape, Vector::vector_t *pos)
{
	btTransform trans;

	btRigidBody *body = colShape->rigidBody;
	if (body && body->getMotionState())
	{
		body->getMotionState()->getWorldTransform(trans);
		pos->x = float(trans.getOrigin().getX());
		pos->y = float(trans.getOrigin().getY());
		pos->z = float(trans.getOrigin().getZ());
	}
}

colshape_t *AddBox(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(10,-2,0);
	if (isDynamic)
		newColshape->colShape->calculateLocalInertia(mass,localInertia);

	startTransform.setOrigin(btVector3(pX,pY,pZ));
		
	//using motionstate is recommended, it provides interpolation capabilities, and only synchronizes 'active' objects
	btDefaultMotionState* myMotionState = new btDefaultMotionState(startTransform);
	btRigidBody::btRigidBodyConstructionInfo rbInfo(mass,myMotionState,newColshape->colShape,localInertia);
	btRigidBody* body = new btRigidBody(rbInfo);

	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);

	collisionShapes.push_back(bvtTrimesh);
	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");
}

}
step_jac
Posts: 1
Joined: Thu Sep 17, 2009 7:34 pm

Re: Super simple demo has objects passing through others

Post by step_jac »

Hi,

I'm a new user of Bullet so please correct me if I'm wrong. We've had simular experiences with collisions not taking place on faster moving objects. I don't believe continuous collision detection is fully integrated to Bullet currently as per the comment in "btContinousDynamicsWorld.h". Discrete collision detection is probably taking place resulting in objects potentially going through each other if moving fast enough. You could potentially run the step simulation with a smaller base time step to ensure these collisions are caught ( stepSimulation(1.0f/60.f, 10, 1.0f/240.f ) but I'm not sure what artifacts that may cause as the Bullet manual suggest running at a base timestep of one 60th of a second.

Best,

Stephane