CCD tunneling problems

ironmonkey
Posts: 1
Joined: Thu Apr 08, 2010 1:34 am

CCD tunneling problems

Post by ironmonkey »

Hey guys

We've been having a lot of problems with objects tunneling. Eventually we've cut it down to this little test based on the helloworld tutorial and the ground mesh from raycastcar.

It creates a ground mesh and a cube. Then shoots the cube at the ground mesh from position (0,10,0) at velocity (0,-2000,0) to the ground at 0,0,0. Without CCD this obviously goes straight through the mesh, with CCD it stops dead once it hits, as expected

But the problem we're having is if we start the cube at (10,10,0) it goes through the ground at some 160 units/s. CCD detects the hit, but it tunnels through anyway.

We're kind of baffled as to why changing the X start position is making the cube tunnel. If the cube has a slower start speed at the same location it doesn't tunnel, suggesting the ground mesh doesn't have a hole in it or anything obvious..

Any ideas?

I've attached our test code below.

Code: Select all

#include <iostream>
#include <btBulletDynamicsCommon.h>
	
btRigidBody* m_groundRigidBody;
btDefaultMotionState* m_groundMotionState;
btVector3*	m_groundVertices;
int*	m_groundIndices;
btTriangleIndexVertexArray* m_groundIndexVertexArrays;
btBvhTriangleMeshShape* m_groundTriMeshShape;
void createGround();
btDiscreteDynamicsWorld* dynamicsWorld;

int main (void)
{
        btBroadphaseInterface* broadphase = new btDbvtBroadphase();
        btDefaultCollisionConfiguration* collisionConfiguration = new btDefaultCollisionConfiguration();
        btCollisionDispatcher* dispatcher = new btCollisionDispatcher(collisionConfiguration);
        btSequentialImpulseConstraintSolver* solver = new btSequentialImpulseConstraintSolver;
        dynamicsWorld = new btDiscreteDynamicsWorld(dispatcher,broadphase,solver,collisionConfiguration);


        btCollisionShape* cubeShape = new btBoxShape(btVector3(2.0f,2.0f,2.0f));
 
		//btVector3 initalPos(10,10,0);
		btVector3 initalPos(0,10,0);
		btVector3 initialSpeed(0.0f,-2000.0f,0.0f);
 
        btDefaultMotionState* fallMotionState = new btDefaultMotionState(btTransform(btQuaternion(0,0,0,1),initalPos));
        btScalar mass = 1;
        btVector3 fallInertia(0,0,0);
        cubeShape->calculateLocalInertia(mass,fallInertia);
        btRigidBody::btRigidBodyConstructionInfo fallRigidBodyCI(mass,fallMotionState,cubeShape,fallInertia);
        btRigidBody* fallRigidBody = new btRigidBody(fallRigidBodyCI);
        dynamicsWorld->addRigidBody(fallRigidBody);
 
		dynamicsWorld->setGravity(btVector3(0,-40,0));

		fallRigidBody->setCcdMotionThreshold(1);
		fallRigidBody->setCcdSweptSphereRadius(0.2f);

		fallRigidBody->setLinearVelocity(initialSpeed);

		createGround();
 
		btTransform trans;
        fallRigidBody->getMotionState()->getWorldTransform(trans);
 		btVector3 speed = fallRigidBody->getLinearVelocity();
        printf(" px: %0.3f",trans.getOrigin().getX());
		printf(" py: %0.3f",trans.getOrigin().getY());
		printf(" pz: %0.3f",trans.getOrigin().getZ());
		printf(" vx: %0.3f",speed.getX());
		printf(" vy: %0.3f",speed.getY());
		printf(" vz: %0.3f",speed.getZ());
		std::cout << std::endl;

        for (int i=0 ; i<10 ; i++) {
                dynamicsWorld->stepSimulation(0.05f,1,0.05f);
 
                btTransform trans;
                fallRigidBody->getMotionState()->getWorldTransform(trans);
 
				btVector3 speed = fallRigidBody->getLinearVelocity();
                printf(" px: %0.3f",trans.getOrigin().getX());
				printf(" py: %0.3f",trans.getOrigin().getY());
				printf(" pz: %0.3f",trans.getOrigin().getZ());
				printf(" vx: %0.3f",speed.getX());
				printf(" vy: %0.3f",speed.getY());
				printf(" vz: %0.3f",speed.getZ());
				std::cout << std::endl;
        }
		m_groundRigidBody->getMotionState()->getWorldTransform(trans);
		printf(" px: %0.3f",trans.getOrigin().getX());
		printf(" py: %0.3f",trans.getOrigin().getY());
		printf(" pz: %0.3f",trans.getOrigin().getZ());
 
        dynamicsWorld->removeRigidBody(fallRigidBody);
        delete fallRigidBody->getMotionState();
        delete fallRigidBody;
 
  
        delete cubeShape;
 
  
        delete dynamicsWorld;
        delete solver;
        delete collisionConfiguration;
        delete dispatcher;
        delete broadphase;
 		return 0;
}

void createGround()
{
	const float TRIANGLE_SIZE=8.f;
	static float waveheight = 0.0f;
    const int NUM_VERTS_X = 100;
	const int NUM_VERTS_Y = 100;
	const int totalVerts = NUM_VERTS_X * NUM_VERTS_Y;
	
	int vertStride = sizeof(btVector3);
	int indexStride = 3*sizeof(int);
	const int totalTriangles = 2*(NUM_VERTS_X-1)*(NUM_VERTS_Y-1);
	
	m_groundVertices = new btVector3[totalVerts];
	m_groundIndices = new int[totalTriangles*3];
	for (int i = 0; i < NUM_VERTS_X;i++)
	{
		for (int j = 0; j < NUM_VERTS_Y;j++)
		{
			m_groundVertices[i+j*NUM_VERTS_X].setValue((i-NUM_VERTS_X*0.5f)*TRIANGLE_SIZE,
												 0,//sinf((float)i),//*cosf((float)j),
												(j-NUM_VERTS_Y*0.5f)*TRIANGLE_SIZE);
		}
	}
	
	int index=0;
	for (int i=0;i<NUM_VERTS_X-1;i++)
	{
		for (int j=0;j<NUM_VERTS_Y-1;j++)
		{
			m_groundIndices[index++] = j*NUM_VERTS_X+i;
			m_groundIndices[index++] = j*NUM_VERTS_X+i+1;
			m_groundIndices[index++] = (j+1)*NUM_VERTS_X+i+1;
			
			m_groundIndices[index++] = j*NUM_VERTS_X+i;
			m_groundIndices[index++] = (j+1)*NUM_VERTS_X+i+1;
			m_groundIndices[index++] = (j+1)*NUM_VERTS_X+i;
		}
	}
	m_groundIndexVertexArrays = new btTriangleIndexVertexArray(totalTriangles,
														 m_groundIndices,
														 indexStride,
														 totalVerts,(btScalar*) &m_groundVertices[0].x(),vertStride);
	
	bool useQuantizedAabbCompression = true;
	float mass = 0.f;
	m_groundTriMeshShape  = new btBvhTriangleMeshShape(m_groundIndexVertexArrays,useQuantizedAabbCompression,true);
	btCollisionShape* groundShape = m_groundTriMeshShape;
	btVector3 pos(0,0,0);
	m_groundMotionState = new btDefaultMotionState(btTransform(btQuaternion(0,0,0,1),pos));
	m_groundRigidBody = new btRigidBody(mass,m_groundMotionState,groundShape,btVector3(0,0,0));
	dynamicsWorld->addRigidBody(m_groundRigidBody);
}