Bullet 2.78 Restitution Bug?

bullphy
Posts: 4
Joined: Sat Jul 09, 2011 7:42 am

Bullet 2.78 Restitution Bug?

Post by bullphy »

Hi there,
I have this scene : three bouncy balls free fall onto ground, higher position ball will be bounced higher. this is correct in SDK 2.77 but now there is something wrong with SDK 2.78 : higher position balls is not bounced higher.

I have read tutorial article about BtContactSolverInfo : http://bulletphysics.org/mediawiki-1.5. ... SolverInfo, changed solver info etc. but still incorrect. What should i do to make their behavior just like old times? thank you.

1. Ball start positions are : <-3, 3, 0>, <0, 7, 0>, <3, 11, 0>, in SDK 2.78, the 3rd ball (highest one) bounced obviously lower than 2nd ball.
2. step simulation parameters are : dynamicsWorld->stepSimulation(timeDelta, 4);
3. Gravity is 9.81, By the way, in SDK 2.78 gravity=-10 and gravity = -9.8 makes big difference : take first ball for example (3 units from ground), if gravity is 9.8, it bounces correctly but with gravity is 10, it almost no bounce, why is so different? in SDK 2.77 it bounces always correct.

Ball Settings (same for all 3 balls) :

Code: Select all

angularDamping = 0.3f;
linearDamping = 0.3f;
friction = 0.5f;
restitution = 0.9f;
mass = 1.0f;
radius = 0.3;
Ground Settings :

Code: Select all

angularDamping = 0.3f;
linearDamping = 0.3f;
friction = 0.5f;
restitution = 1.0f;
mass = 0.0f;
half-extents = <50, 50, 50>
bullphy
Posts: 4
Joined: Sat Jul 09, 2011 7:42 am

Re: Bullet 2.78 Restitution Bug?

Post by bullphy »

Okay, for you convenience i write some test code, just copy and paste it to SDK 2.78 basic demo and replace 'basicDemo::initPhysics()'. to see how it differs from SDK 2.77, please also copy and paste it to 2.77, thank you.

Code: Select all

void	BasicDemo::initPhysics()
{
	setTexturing(true);
	setShadows(true);

	//setCameraDistance(btScalar(SCALING*50.));
	setCameraDistance(btScalar(0.3f * 50.));

	///collision configuration contains default setup for memory, collision setup
	m_collisionConfiguration = new btDefaultCollisionConfiguration();
	//m_collisionConfiguration->setConvexConvexMultipointIterations();

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

	m_broadphase = new btDbvtBroadphase();

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

	m_dynamicsWorld = new btDiscreteDynamicsWorld(m_dispatcher,m_broadphase,m_solver,m_collisionConfiguration);
	
	m_dynamicsWorld->setGravity(btVector3(0, -10, 0));

	///create a few basic rigid bodies
	btCollisionShape* groundShape = new btBoxShape(btVector3(btScalar(50.),btScalar(50.),btScalar(50.)));	
	m_collisionShapes.push_back(groundShape);

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

	//We can also use DemoApplication::localCreateRigidBody, but for clarity it is provided here:
	{
		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);

		rbInfo.m_linearDamping = 0.0f;
		rbInfo.m_angularDamping = 0.0f;
		rbInfo.m_friction = 0.0f;
		rbInfo.m_restitution = 1.0f;

		btRigidBody* body = new btRigidBody(rbInfo);
		body->updateInertiaTensor();

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

	{
		btCollisionShape *sp = new btSphereShape(1.0f);
		sp->setLocalScaling(btVector3(0.3f, 0.3f, 0.3f));
		m_collisionShapes.push_back(sp);

		const float mass = 1;

		for (int i = 0; i < 3; ++i)
		{
			btVector3 localInertia(0, 0, 0);
			sp->calculateLocalInertia(mass, localInertia);

			btDefaultMotionState *mp = new btDefaultMotionState;

			btTransform tm;
			tm.setIdentity();
			tm.setOrigin(btVector3(-3 + i * 3.0f, 3 + i * 4.0f, 0));
			mp->setWorldTransform(tm);

			btRigidBody::btRigidBodyConstructionInfo rbInfo(mass, mp, sp, localInertia);
			rbInfo.m_linearDamping = 0.0f;
			rbInfo.m_angularDamping = 0.0f;
			rbInfo.m_friction = 0.0f;
			rbInfo.m_restitution = 0.9f;

			btRigidBody* body = new btRigidBody(rbInfo);

			m_dynamicsWorld->addRigidBody(body);
		}
	}
}