balls falling through deforming trimesh

alexmac
Posts: 4
Joined: Tue Mar 20, 2007 4:56 pm

balls falling through deforming trimesh

Post by alexmac »

I'm having some problems with my test application. Basically I've got a terrain mesh that can be modified (left click raises the terrain, right click lowers) and balls can be dropped onto the terrain from above (with the space bar):

The balls work ok when the terrain is flat and sometimes work on the terrain when it has had minor modifications, but with much deeper dips and higher mountains the balls simply fall through it.

The full code can be downloaded from here:

http://alexmac.cc/small-terrain-test.cpp

but here is the physics bit:

Code: Select all

// -----------------------------------------------------------------------------
// Bullet Physics
// -----------------------------------------------------------------------------

const int maxProxies = 32766;

btDynamicsWorld* world;
btCollisionDispatcher* dispatcher;
btOverlappingPairCache* broadphase;
btSequentialImpulseConstraintSolver* solver;

btRigidBody* mesh_body;
btTriangleMeshShape* mesh;
btTriangleIndexVertexArray *mesh_interface;

std::vector<btCollisionShape*> collision_meshes = std::vector<btCollisionShape*>();
std::vector<btRigidBody*> bodies = std::vector<btRigidBody*>();

void init_physics()
{
	btVector3 worldAabbMin(-100,-100,-100);
	btVector3 worldAabbMax(100,100,100);
	
	dispatcher = new btCollisionDispatcher();
	broadphase = new btAxisSweep3(worldAabbMin,worldAabbMax,maxProxies);
	solver = new btSequentialImpulseConstraintSolver();

	world = new btDiscreteDynamicsWorld(dispatcher,broadphase,solver);
	world->setGravity(btVector3(0,-10,0));

	// Trimesh
	mesh_interface = new btTriangleIndexVertexArray(terrain_triangle_count,
													&(terrain_triangles[0].v1),
													sizeof(Triangle),
													terrain_vertex_count,
													&(terrain_vertices[0].x),
													sizeof(Vertex));
	
	mesh = new btTriangleMeshShape(mesh_interface);
	
	btTransform mesh_pos;
	mesh_pos.setIdentity();
	mesh_pos.setOrigin(btVector3(0,0,0));

	btDefaultMotionState* motionstate = new btDefaultMotionState(mesh_pos);
	mesh_body = new btRigidBody(1000.0f,motionstate,mesh);
	mesh_body->setCollisionFlags(btCollisionObject::CF_STATIC_OBJECT);
	mesh_body->setActivationState(DISABLE_DEACTIVATION);
	
	world->addRigidBody(mesh_body);
}

void add_ball(float xp, float yp, float zp)
{
	float mass = 1.0f;
	btVector3 inertia(0,0,0);
	
	btTransform trans;
	trans.setIdentity();
	trans.setOrigin(btVector3(xp,yp,zp));
	
	btCollisionShape *geom = new btSphereShape (ball_radius);

	geom->calculateLocalInertia(mass,inertia);
	
	btDefaultMotionState* motionstate = new btDefaultMotionState(trans);

	btRigidBody* body = new btRigidBody(mass,motionstate,geom,inertia);
	
	body->setCcdSquareMotionThreshold( ball_radius );
	body->setCcdSweptSphereRadius( 0.2*ball_radius );
	body->setActivationState(DISABLE_DEACTIVATION);

	world->addRigidBody(body);

	bodies.push_back(body);
	collision_meshes.push_back(geom);
	
	std::cout << "ball added: " << xp << ", " << yp << ", " << zp << std::endl;
}

void render_balls()
{
	int num = bodies.size();
	
	btDefaultMotionState* ms;
	float m[16];
	
	for(int i=0; i<num; i++)
	{
		btPoint3 com = bodies[i]->getCenterOfMassPosition();
		
		ms = (btDefaultMotionState*)bodies[i]->getMotionState();

		ms->m_graphicsWorldTrans.getOpenGLMatrix(m);
		
		glColor3f(0.0f, 1.0f, 0.0f);

		glPushMatrix();
		glMultMatrixf(m);
		gluSphere(ball, ball_radius, 10, 10);
		glPopMatrix();
	}
}

void step_physics()
{
	world->updateAabbs();
	world->stepSimulation(1.0 / 60.0f);
}

Maybe I need to tell bullet that I've modified the trimesh? I'm a real newbie so any help is greatly appreciated
User avatar
Erwin Coumans
Site Admin
Posts: 4221
Joined: Sun Jun 26, 2005 6:43 pm
Location: California, USA

Post by Erwin Coumans »

Are you only modifying the vertices of terrain_vertices ?

In that case we need to add a 'refit' to Bullet optimized tree. That should work as long as you don't change the topology of the mesh (like add/remove/re-order triangles)

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

Post by Erwin Coumans »

Bullet 2.48 has the new refit feature, and ConcaveDemo shows an example how to use this.

Can you please try this, and let us know if that works for you?

Thanks,
Erwin
alexmac
Posts: 4
Joined: Tue Mar 20, 2007 4:56 pm

Post by alexmac »

ahh, I was using the google code repository which seems to be rather out of date.

I just downloaded 2.48 and managed to get it compiled after fixing a few errors:

1) file named incorrectly:
src/BulletDynamics/ConstraintSolver/btsolverconstraint.h
should be uppercase:
src/BulletDynamics/ConstraintSolver/btSolverConstraint.h

2) some commas at the end of enums:

/usr/include/bullet/BulletCollision/CollisionDispatch/btCollisionObject.h:87: error: comma at end of enumerator list
/usr/include/bullet/BulletCollision/BroadphaseCollision/btBroadphaseProxy.h:76: error: comma at end of enumerator list


Now that I have 2.48 compiled I have switched to using btBvhTriangleMesh and calling refitTree each time the mesh changes and my balls now work just fine!

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

Post by Erwin Coumans »

Would it be possible to share a Windows SDL demo binary .exe +your source,
http://www.continuousphysics.com/Bullet ... m.php?f=17

That would be fun to play with for others too.

Thanks!
Erwin
alexmac
Posts: 4
Joined: Tue Mar 20, 2007 4:56 pm

Post by alexmac »

I've put a page up with the updated code and a picture here: http://alexmac.cc/bullet-test/ but I'm not a windows user and I don't have access to a windows box with any sort of compiler so maybe someone else can provide me with an exe of it.

I'll make a post in the user gallery as well.