Having problems with btBvhTriangleMeshShape

monk
Posts: 7
Joined: Tue Dec 08, 2009 1:38 pm

Having problems with btBvhTriangleMeshShape

Post by monk »

Hi all.

I'm playing around with bullet a bit but i'm having some probs.
I have this small directx app that loads 2 .x files, one mesh is a simple flat terrain and the other just a sphere. Both exported from 3ds max using panda exporter.
I started by creating a collison box shape for the terrain and a sphere collision shape for the sphere object. All was working fine.

My goal is to use more complex models, like racing tracks, and after doing some reasearch in the forums, it seems that the btBvhTriangleMeshShape is the way the go if you want to handle collisions with such geometry.
I decided to create a btBvhTriangleMeshShape for my simple terrain but the collisions appear all messed up. As you can see in the image below, the sphere just stops in mid air!

Image

Here's the code i use to set up objects:

Bullet initialization:

Code: Select all

void cPhysics::InitPhysics()
{
	//Collision configuration contains default setup for memory, collision setup
	physCollisionConfiguration = new btDefaultCollisionConfiguration();

	//Use the default collision dispatcher. For parallel processing you can use a diffent dispatcher (see Extras/BulletMultiThreaded)
	physDispatcher = new btCollisionDispatcher(physCollisionConfiguration);


	physBroadphase = new btDbvtBroadphase();

	//The default constraint solver. For parallel processing you can use a different solver (see Extras/BulletMultiThreaded)
	physSolver = new btSequentialImpulseConstraintSolver;
	//physSolver = solver;

	//Create the main physics object
	physDynamicsWorld = new btDiscreteDynamicsWorld(physDispatcher,physBroadphase,physSolver,physCollisionConfiguration);
	physDynamicsWorld->setGravity(btVector3(0,-9.8f,0));
}

The objects setup:

Code: Select all


struct TriMeshData
{
	btScalar   *vertices;
	int         *indices;   
	btTriangleIndexVertexArray   *indexVertexArrays;
	TriMeshData()
	{
		vertices = NULL;
		indices = NULL;
		indexVertexArrays = NULL;
	}
	~TriMeshData()
	{
		if( vertices ) delete [] vertices;
		if( indices ) delete [] indices;
		if( indexVertexArrays ) delete indexVertexArrays;
	}
};

....

btCollisionShape* physSphereShape;
btRigidBody* physBoxBody;
btBvhTriangleMeshShape* physGroundShape;
btRigidBody* physGroundBody;

....

mPhysics = new cPhysics();
	mPhysics->InitPhysics();

	//Create the ground object
	{
		// Create the ground shape
		//physGroundShape = new btBoxShape(btVector3(btScalar(50.0f),btScalar(0.0f),btScalar(50.0f)));


		DWORD numVertices      = mMesh->GetNumVertices();
		DWORD numFaces         = mMesh->GetNumFaces();

		VertexPos *v = 0;
		mMesh->LockVertexBuffer(0, (void**)&v);

		// Extract vertices
		pData = new TriMeshData();
		pData->vertices = new btScalar[numVertices * 3];   

		for(UINT i = 0; i < numVertices; i++)
		{
			pData->vertices[i*3+0] = v[i].pos.x;
			pData->vertices[i*3+1] = v[i].pos.y;
			pData->vertices[i*3+2] = v[i].pos.z;      
		}   

		mMesh->UnlockVertexBuffer();

		// Extract indices
		pData->indices = new int[numFaces * 3];   
		WORD* ind = 0;
		mMesh->LockIndexBuffer(0,(void**)&ind);      

		//memcpy( &indices, &ind, sizeof(ind));   
		for (int i=0;i < numFaces; i++)
		{   
			pData->indices[i*3+0] = ind[i*3+0];
			pData->indices[i*3+1] = ind[i*3+1];
			pData->indices[i*3+2] = ind[i*3+2];      
		}

		mMesh->UnlockIndexBuffer();      

		int indexStride = 3 * sizeof(int);
		int vertStride = sizeof(btVector3);

		pData->indexVertexArrays = new btTriangleIndexVertexArray(numFaces, pData->indices, indexStride,
			numVertices, (btScalar*) &pData->vertices[0], sizeof(btScalar) * 3);

		btTriangleMesh* trimesh = new btTriangleMesh();
		for( DWORD i = 0; i < numFaces; i++ )
		{
			int index0 = pData->indices[i*3];
			int index1 = pData->indices[i*3+1];
			int index2 = pData->indices[i*3+2];

			btVector3 vertex0(pData->vertices[index0*3], pData->vertices[index0*3+1],pData->vertices[index0*3+2]);
			btVector3 vertex1(pData->vertices[index1*3], pData->vertices[index1*3+1],pData->vertices[index1*3+2]);
			btVector3 vertex2(pData->vertices[index2*3], pData->vertices[index2*3+1],pData->vertices[index2*3+2]);

			trimesh->addTriangle(vertex0,vertex1,vertex2);
		}


		bool useQuantizedAabbCompression = true;
		//btVector3 aabbMin(-1000,-1000,-1000),aabbMax(1000,1000,1000);
		physGroundShape = new btBvhTriangleMeshShape(trimesh, useQuantizedAabbCompression);  
		//physGroundShape = new btBvhTriangleMeshShape(pData->indexVertexArrays, useQuantizedAabbCompression);  

		// Set the position for the ground shape
		//physGroundShape->calculateLocalInertia(0,btVector3(0, 0, 0));
		btTransform groundTransform;
		groundTransform.setIdentity();
		groundTransform.setOrigin(btVector3(0, 0.0f, 0));
		//physGroundShape->calculateLocalInertia(0,btVector3(0, 0, 0));

		// Create MotionState and RigidBody object for the ground shape
		btDefaultMotionState* myMotionState = new btDefaultMotionState(groundTransform);
		btRigidBody::btRigidBodyConstructionInfo rbInfo(0, myMotionState, physGroundShape, btVector3(0, 0, 0));
		physGroundBody = new btRigidBody(rbInfo);

		// Add ground body to physics object
		if (mPhysics && physGroundBody)
		{
			mPhysics->GetPhysicsWorld()->addRigidBody(physGroundBody);
		}
		physGroundBody->activate();
		
	}

	//Create the sphere object
	{
		//Create the box shape
		float radius = 1.0f;
		physSphereShape = new btSphereShape(radius);

		//float const volume = (4.f / 3.f) * D3DX_PI * radius * radius * radius;
		//btScalar const mass = volume * 5.0;

		//Set mass, initial inertia and position for the box
		float mass = 1.0f;
		btVector3 inertia(0, 0, 0);

		physSphereShape->calculateLocalInertia( mass, inertia );

		btTransform startTransform;
		startTransform.setIdentity();
		startTransform.setOrigin(btVector3(0, 50, 0));

		//Calculate the inertia
		//physSphereShape->calculateLocalInertia(1.0, inertia);

		// Create MotionState and RigidBody object for the box shape
		btDefaultMotionState* myMotionState = new btDefaultMotionState(startTransform);
		btRigidBody::btRigidBodyConstructionInfo rbInfo(mass, myMotionState, physSphereShape, inertia);
		physBoxBody = new btRigidBody(rbInfo);

		// Add box sphere to physics object & activate it
		if (mPhysics)
		{
			mPhysics->GetPhysicsWorld()->addRigidBody(physBoxBody);
		}		
		physBoxBody->activate();
		//physBoxBody->setActivationState(2);
	}

Any ideas what could be worng?

Thanks in advance :)
Grimreaper85
Posts: 4
Joined: Mon Feb 15, 2010 1:29 am

Re: Having problems with btBvhTriangleMeshShape

Post by Grimreaper85 »

If the sphere drops then appears to make contact in mid air, your physics body is not positioned the same as your rendered triangles. Your ground body is positioned at (0,0,0) in bullet and id guess your translating the ground down on the Y axis when you render.
User avatar
Erwin Coumans
Site Admin
Posts: 4221
Joined: Sun Jun 26, 2005 6:43 pm
Location: California, USA

Re: Having problems with btBvhTriangleMeshShape

Post by Erwin Coumans »

Try using the debug drawing tools to figure out what is going wrong: derive our own version of btIDebugDraw, assign it to the world and set the wireframe debug mode.

See the Bullet demos for implementation details,
Thanks,
Erwin
monk
Posts: 7
Joined: Tue Dec 08, 2009 1:38 pm

Re: Having problems with btBvhTriangleMeshShape

Post by monk »

Hi there

Sorry for the late reply.
Below is the output i get from debug drawing the ground geometry:

Image

Any ideas why this is hapenning? :(

Thanks
User avatar
Erwin Coumans
Site Admin
Posts: 4221
Joined: Sun Jun 26, 2005 6:43 pm
Location: California, USA

Re: Having problems with btBvhTriangleMeshShape

Post by Erwin Coumans »

It seems you need to do some debugging.

Some tip: get rid of btTriangleIndexVertexArray, and only use btTriangleMesh until things work fine.

What is the up-axis? It seems the up axis needs to be the same for all vertices, just put some assert/breakpoint when you add the vertices and track down from there.
Thanks,
Erwin