unnatural collision

yaoyansi
Posts: 17
Joined: Thu Jan 01, 2009 2:14 pm

unnatural collision

Post by yaoyansi »

hi, all
I am redesigning a bullet plugin for maya. Here is my test. The animation is rendered by maya, and I use DemoApplication::renderme() to render the triangles of meshes in maya. So, the position of each vertex rendered should be same as the position that rendered in bullet. And I am sure of it because of a special test.
My problem is when I create ONE cube in the scene, then simulate it and play the animation, it seems good.
but ,when I create TWO and more cubes (or other shapes) the collision behavior seems unnatural.
The collision animation of two cubes is attached.(I am sorry but it seems that firefox plays the animation only once even you refresh the page. But IE replays it everytime you refresh the page.)
Image

And here is my code of simulation Solver:

Code: Select all

//---------   Solver.h   -------------------
class Solver
{
public:
	static Solver* getInstance();
	virtual ~Solver();

	void initWorld();
	void initGround();

	void addRigidbody2(const Mesh_ &mesh);
	void simulate(const float time, const double duration);
	void destructALL();
	
	// get transform matrix for maya
	void getMatrixAndRot( size_t bodyIndex, btScalar *m, btMatrix3x3& rot);

	void debugDrawWorld();
	void renderScene(M3dView::DisplayStyle style);
	btScalar getDeltaTimeSeconds();
protected:
	Solver();
	static Solver* m_instance;

	btDefaultCollisionConfiguration* collisionConfiguration;
	btCollisionDispatcher* dispatcher ;
	btSequentialImpulseConstraintSolver* solver ;
	btAxisSweep3* overlappingPairCache ;

	btDiscreteDynamicsWorld* dynamicsWorld ;
	btAlignedObjectArray<btCollisionShape*> collisionShapes;

	GL_ShapeDrawer*	m_shapeDrawer;
	btClock m_clock;
};
//--------------------  Solver.cpp  -------------------------
btRigidBody* localCreateRigidBody(float mass, const btTransform& startTransform,btCollisionShape* shape)
{
	btAssert((!shape || shape->getShapeType() != INVALID_SHAPE_PROXYTYPE));

	//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)
		shape->calculateLocalInertia(mass,localInertia);

	//using motionstate is recommended, it provides interpolation capabilities, and only synchronizes 'active' objects

#define USE_MOTIONSTATE 1
#ifdef USE_MOTIONSTATE
	btDefaultMotionState* myMotionState = new btDefaultMotionState(startTransform);

	btRigidBody::btRigidBodyConstructionInfo cInfo(mass,myMotionState,shape,localInertia);

	btRigidBody* body = new btRigidBody(cInfo);

#else
	btRigidBody* body = new btRigidBody(mass,0,shape,localInertia);	
	body->setWorldTransform(startTransform);
#endif//

	//m_dynamicsWorld->addRigidBody(body);

	return body;
}
//----------------
Solver* Solver::m_instance = NULL;

Solver::Solver()
{
	collisionConfiguration = NULL;
	dispatcher = NULL;
	solver = NULL;
	overlappingPairCache = NULL;

	dynamicsWorld = NULL;
	m_shapeDrawer = new GL_ShapeDrawer ();
}

Solver::~Solver()
{
	if (m_shapeDrawer){
		delete m_shapeDrawer;
		m_shapeDrawer = NULL;
	}

	if(m_instance  != NULL){
		delete m_instance ;
		m_instance = NULL;
	}
}

Solver* Solver::getInstance()
{
	if(m_instance  == NULL){
		m_instance = new Solver();
	}
	return m_instance;
}

///MyContactCallback is just an example to show how to get access to the child shape that collided
bool MyContactCallback (
						btManifoldPoint& cp,
						const btCollisionObject* colObj0,
						int partId0,
						int index0,
						const btCollisionObject* colObj1,
						int partId1,
						int index1)
{

	if (colObj0->getRootCollisionShape()->getShapeType()==COMPOUND_SHAPE_PROXYTYPE)
	{
		btCompoundShape* compound = (btCompoundShape*)colObj0->getRootCollisionShape();
		btCollisionShape* childShape;
		childShape = compound->getChildShape(index0);
	}

	if (colObj1->getRootCollisionShape()->getShapeType()==COMPOUND_SHAPE_PROXYTYPE)
	{
		btCompoundShape* compound = (btCompoundShape*)colObj1->getRootCollisionShape();
		btCollisionShape* childShape;
		childShape = compound->getChildShape(index1);
	}

	return true;
}
void Solver::initWorld()
{
	gContactAddedCallback = &MyContactCallback;
	///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 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(-10000,-10000,-10000);
	btVector3 worldAabbMax(10000,10000,10000);
	int	maxProxies = 1024;
	overlappingPairCache = new btAxisSweep3(worldAabbMin,worldAabbMax,maxProxies);

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

	dynamicsWorld = new btDiscreteDynamicsWorld(dispatcher,overlappingPairCache,solver,collisionConfiguration);

	dynamicsWorld->setGravity(btVector3(0,-10,0));

}

void Solver::initGround()
{
	///create a few basic rigid bodies
	btCollisionShape* groundShape = new btBoxShape(btVector3(btScalar(50.),btScalar(0.4),btScalar(50.)));

	//keep track of the shapes, we release memory at exit.
	//make sure to re-use collision shapes among rigid bodies whenever possible!
	collisionShapes.push_back(groundShape);

	btTransform groundTransform;
	groundTransform.setIdentity();
	groundTransform.setOrigin(btVector3(0,-7.0f,0));

	{
		btScalar mass(0.);

		//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)
			groundShape->calculateLocalInertia(mass,localInertia);

		//using motionstate is recommended, it provides interpolation capabilities, and only synchronizes 'active' objects
		btDefaultMotionState* myMotionState = new btDefaultMotionState(groundTransform);
		btRigidBody::btRigidBodyConstructionInfo rbInfo(mass,myMotionState,groundShape,localInertia);
		btRigidBody* body = new btRigidBody(rbInfo);

		//add the body to the dynamics world
		dynamicsWorld->addRigidBody(body);
	}
}


void Solver::addRigidbody2(const Mesh_ &mesh)
{
	btTriangleMesh* trimesh = new btTriangleMesh();
	for (size_t tri=0; tri<mesh.indices.size()/3; tri++)
	{
		//vertex index
		int vi0 = mesh.indices[3*tri+0];
		int vi1 = mesh.indices[3*tri+1];
		int vi2 = mesh.indices[3*tri+2];

		btVector3 pos0(mesh.position[vi0].x, mesh.position[vi0].y,mesh.position[vi0].z);
		btVector3 pos1(mesh.position[vi1].x, mesh.position[vi1].y,mesh.position[vi1].z);
		btVector3 pos2(mesh.position[vi2].x, mesh.position[vi2].y,mesh.position[vi2].z);

		trimesh->addTriangle(pos0,pos1,pos2);
	}
	//------------------------------------------------------
	//trimesh --> btConvexShape --> btShapeHull --> btConvexHullShape
	btConvexShape* tmpConvexShape = new btConvexTriangleMeshShape(trimesh);
	printf("reducing vertices by creating a convex hull\n");

	//create a hull approximation
	btShapeHull* hull = new btShapeHull(tmpConvexShape);
	btScalar margin = tmpConvexShape->getMargin();
	hull->buildHull(margin);
	tmpConvexShape->setUserPointer(hull);

	btConvexHullShape* convexShape = new btConvexHullShape();
	for (int i=0;i<hull->numVertices();i++)
	{
		convexShape->addPoint(hull->getVertexPointer()[i]);	
	}

	delete tmpConvexShape;
	delete hull;
	//------------------------------------------------------
	float mass = 1.f;
	btTransform startTransform;
	startTransform.setIdentity();
// 	startTransform.setFromOpenGLMatrix((btScalar*)mesh.m);//startTransform.setOrigin(btVector3(0,30,0));
// 	mesh.print("addRigidbody --> startTransform.setFromOpenGLMatrix(m)");

	//
	btRigidBody* body = localCreateRigidBody(mass, startTransform,convexShape);
	//add the body to the dynamics world
	dynamicsWorld->addRigidBody(body);
}

void Solver::simulate(const float time, const double duration)
{
	btScalar btduration = getDeltaTimeSeconds();
	printf("duration=%f, btduration=%f\n", duration, btduration);

	//dynamicsWorld->stepSimulation(duration,  1);
	//dynamicsWorld->stepSimulation(duration,  10);
	//dynamicsWorld->stepSimulation(duration,  20);
	//dynamicsWorld->stepSimulation(duration,  60);

	//dynamicsWorld->stepSimulation(btduration,  1);
	//dynamicsWorld->stepSimulation(duration,  10);
	//dynamicsWorld->stepSimulation(duration,  20);
	dynamicsWorld->stepSimulation(duration,  60);

//	dynamicsWorld->stepSimulation(1.f/60.f, 1);

} 

// get transform matrix for maya
void Solver::getMatrixAndRot( size_t bodyIndex, 
						  btScalar *m, btMatrix3x3& rot)
{
	rot.setIdentity();

#ifdef USE_GROUND
	bodyIndex++;//skip ground
#endif
	assert(bodyIndex < dynamicsWorld->getNumCollisionObjects() && bodyIndex>=0);

	btCollisionObject*	colObj=dynamicsWorld->getCollisionObjectArray()[bodyIndex];
	btRigidBody*		body=btRigidBody::upcast(colObj);
	
	if(body&&body->getMotionState())
	{
		btDefaultMotionState* myMotionState = (btDefaultMotionState*)body->getMotionState();
		myMotionState->m_graphicsWorldTrans.getOpenGLMatrix(m);
		rot=myMotionState->m_graphicsWorldTrans.getBasis();
	}else{
		colObj->getWorldTransform().getOpenGLMatrix(m);
		rot=colObj->getWorldTransform().getBasis();
	}
}


void Solver::destructALL()
{
	//cleanup in the reverse order of creation/initialization

	//remove the rigidbodies from the dynamics world and delete them
	for (int 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;
	}

	//delete dynamics world
	delete dynamicsWorld;
	dynamicsWorld = NULL;

	//delete solver
	delete solver;
	solver = NULL;

	//delete broadphase
	delete overlappingPairCache;
	overlappingPairCache = NULL;

	//delete dispatcher
	delete dispatcher;
	dispatcher = NULL;

	delete collisionConfiguration;
	collisionConfiguration = NULL;


	//next line is optional: it will be cleared by the destructor when the array goes out of scope
	collisionShapes.clear();

}

void Solver::debugDrawWorld()
{
	if (dynamicsWorld){
		dynamicsWorld->debugDrawWorld();
	}else{
		cout << "dynamicsWorld is NULL"<< endl;
	}
}

void Solver::renderScene(M3dView::DisplayStyle style)
{

		btScalar	m[16];
		btMatrix3x3	rot;rot.setIdentity();
		const int	numObjects=dynamicsWorld->getNumCollisionObjects();
		//cout << "Solver::renderScene() numObjects="<<  numObjects <<endl;
		btVector3 wireColor(1,0,0);

		for(int i=0; i<numObjects; i++)
		{
			//cout << "i="<< i<< endl;
			btCollisionObject*	colObj=dynamicsWorld->getCollisionObjectArray()[i];
			btRigidBody*		body=btRigidBody::upcast(colObj);
			if(body&&body->getMotionState())
			{
				btDefaultMotionState* myMotionState = (btDefaultMotionState*)body->getMotionState();
				myMotionState->m_graphicsWorldTrans.getOpenGLMatrix(m);
				rot=myMotionState->m_graphicsWorldTrans.getBasis();
			}
			else
			{
				colObj->getWorldTransform().getOpenGLMatrix(m);
				rot=colObj->getWorldTransform().getBasis();
			}

			btVector3 wireColor(1.f,1.0f,0.5f); //wants deactivation
			if(i&1) 
				wireColor=btVector3(0.f,0.0f,1.f);
			///color differently for active, sleeping, wantsdeactivation states
			if (colObj->getActivationState() == 1){ //active
				if (i & 1)
				{
					wireColor += btVector3 (1.f,0.f,0.f);
				}else{			
					wireColor += btVector3 (.5f,0.f,0.f);
				}
			}
			if(colObj->getActivationState()==2) {//ISLAND_SLEEPING
				if(i&1){
					wireColor += btVector3 (0.f,1.f, 0.f);
				}else{
					wireColor += btVector3 (0.f,0.5f,0.f);
				}
			}

			btVector3 aabbMin,aabbMax;
			dynamicsWorld->getBroadphase()->getBroadphaseAabb(aabbMin,aabbMax);

			aabbMin-=btVector3(BT_LARGE_FLOAT,BT_LARGE_FLOAT,BT_LARGE_FLOAT);
			aabbMax+=btVector3(BT_LARGE_FLOAT,BT_LARGE_FLOAT,BT_LARGE_FLOAT);
			//		printf("aabbMin=(%f,%f,%f)\n",aabbMin.getX(),aabbMin.getY(),aabbMin.getZ());
			//		printf("aabbMax=(%f,%f,%f)\n",aabbMax.getX(),aabbMax.getY(),aabbMax.getZ());
			//		m_dynamicsWorld->getDebugDrawer()->drawAabb(aabbMin,aabbMax,btVector3(1,1,1));


			int	debugMode;
			switch(style)
			{
			case M3dView::kBoundingBox:		
				debugMode = btIDebugDraw::DBG_DrawAabb; 
				break;
			case M3dView::kFlatShaded:
			case M3dView::kGouraudShaded:	
				debugMode = btIDebugDraw::DBG_NoDebug; 
				break;
			case M3dView::kWireFrame:
			case M3dView::kPoints:			
				debugMode = btIDebugDraw::DBG_DrawWireframe; 
				break;
			default:
				debugMode = btIDebugDraw::DBG_NoDebug;
			}
			if(i==0){
				debugMode = btIDebugDraw::DBG_DrawWireframe;//ground wire frame
			}

			m_shapeDrawer->drawOpenGL(m,colObj->getCollisionShape(),wireColor*0.3, debugMode, aabbMin,aabbMax);
			
		}//for
}

btScalar Solver::getDeltaTimeSeconds()
{
	btScalar dt = m_clock.getTimeMicroseconds();
	m_clock.reset();
	return dt/1000000.0;

	//return btScalar(16666.);
}
Any suggestions?
You do not have the required permissions to view the files attached to this post.
OSasuke
Posts: 47
Joined: Tue Dec 09, 2008 10:12 am

Re: unnatural collision

Post by OSasuke »

I think that the problem is in the rendring.

look :

Code: Select all

btCollisionShape* groundShape = new btBoxShape(btVector3(btScalar(50.),btScalar(0.4),btScalar(50.)));
this shape is bigger than the other, but in your screen shoot, the boxes are similar.

Try to draw your shapes manually with OpenGL. :wink:
yaoyansi
Posts: 17
Joined: Thu Jan 01, 2009 2:14 pm

Re: unnatural collision

Post by yaoyansi »

OSasuke wrote:

Code: Select all

btCollisionShape* groundShape = new btBoxShape(btVector3(btScalar(50.),btScalar(0.4),btScalar(50.)));
That is ground box, and I didn't render the ground box in render loop.


Here is my initial code

Code: Select all

	solver = Solver::getInstance();
	solver->initWorld();
	solver->initGround();

	MeshUtil::getInstance()->extractMeshFromMayaScene();
	std::vector<Mesh_> &vMesh = MeshUtil::getInstance()->vMesh;

	for(int i=0; i<vMesh.size(); ++i)
	{
	    solver->addRigidbody( vMesh[i] );
	}

	solver->clientResetScene();