Problems occurred when the validation of the Bullet's accuracy with a bouncing ball test

Post Reply
daye
Posts: 8
Joined: Mon Sep 04, 2017 2:59 am

Problems occurred when the validation of the Bullet's accuracy with a bouncing ball test

Post by daye »

Hello all,
I want to validate the accuracy of Bullet. I simulated a bouncing ball contacting with a static plane only with the gravity. The ball's trajectory was recorded and compared with the analytic solution. But large errors occurred after a few collisions. I don't know what caused the discrepancy and how to minimize this discrepancy. Any suggestions about this?
Thank you at first!
Daye
Here is the compared curves:(the blue one is the analytic solution and the other one is Bullet)
untitled.jpg
untitled.jpg (13.93 KiB) Viewed 4650 times
User avatar
drleviathan
Posts: 849
Joined: Tue Sep 30, 2014 6:03 pm
Location: San Francisco

Re: Problems occurred when the validation of the Bullet's accuracy with a bouncing ball test

Post by drleviathan »

I dunno the answer but I have some questions about your simulation:

(1) What was your simulation stepping strategy? Fixed substep? If so, what was its duration? How man max substeps?

(2) Are you using single or double precision?

(3) Your ball was an implicit btSphereShape, I assume, but what shape were you using for the "floor"?

(4) The discrepancy: does it reproduce reliably?

(5) What version of Bullet are you using?

(5) Why not publish the full code here for examination?
daye
Posts: 8
Joined: Mon Sep 04, 2017 2:59 am

Re: Problems occurred when the validation of the Bullet's accuracy with a bouncing ball test

Post by daye »

Thank you for your reply!
The simulation used the fixed substep and its duration is 1/600. The max substeps is 10. I am using double precision and the version is bullet3-2.87. In the simulation, the floor was set as btStaticPlaneShape. Here is part of my code:

Code: Select all

	btTransform t;
	t.setIdentity();
	t.setOrigin(btVector3(0,0,0));
	btStaticPlaneShape* plane=new btStaticPlaneShape(btVector3(0,1,0), 0);
	btMotionState* motion=new btDefaultMotionState(t);
	btRigidBody::btRigidBodyConstructionInfo info(0.0, motion, plane);
	info.m_restitution = 1.0;
	info.m_friction = 0.0;
	
	info.m_linearDamping = 0.0;
	info.m_angularDamping = 0.0;
	info.m_linearSleepingThreshold = 0.0;
	info.m_angularSleepingThreshold = 0.0;
	info.m_additionalDamping=false;
	btRigidBody* body=new btRigidBody(info);
	body->setActivationState(DISABLE_DEACTIVATION);
	world->addRigidBody(body);
	
	btTransform ts;
	ts.setIdentity();
	ts.setOrigin(btVector3(0,20,0));
	btSphereShape* sphere=new btSphereShape(1);
	btVector3 inertia(0,0,0);
	float mass=1.0;
	sphere->calculateLocalInertia(mass, inertia);
	btMotionState* motions=new btDefaultMotionState(ts);
	btRigidBody::btRigidBodyConstructionInfo info_fall(mass, motions, sphere, inertia);
	info_fall.m_restitution = 0.8;
	info_fall.m_friction = 0.0;

	info_fall.m_linearDamping = 0.0;
	info_fall.m_angularDamping = 0.0;
	info_fall.m_linearSleepingThreshold = 0.0;
	info_fall.m_angularSleepingThreshold = 0.0;
	info_fall.m_additionalDamping=false;


	btRigidBody* body_fall=new btRigidBody(info_fall);
	body_fall->setActivationState(DISABLE_DEACTIVATION);
	world->addRigidBody(body_fall);
	FILE* dfPtr;
	dfPtr = fopen("Height.dat", "w+");
	for(int i=0; i<15000; i++)
	{
		world->stepSimulation(1/600.0,10);
		btTransform trans;
		body_fall->getMotionState()->getWorldTransform(trans);
		std::cout<<"sphere height: "<<trans.getOrigin().getY()<<std::endl;
		fprintf(dfPtr, "%lf %lf\n", i/600.0, trans.getOrigin().getY());
	}
	fclose(dfPtr);
	
User avatar
drleviathan
Posts: 849
Joined: Tue Sep 30, 2014 6:03 pm
Location: San Francisco

Re: Problems occurred when the validation of the Bullet's accuracy with a bouncing ball test

Post by drleviathan »

This might affect things, you'll have to test:

I don't think your world->stepSimulation() is doing what you think it is. You're specifying the "step" but not the "substep" duration and hence it uses the default substep of 1/60 sec. So your world "steps" forward in 1/600 sec increments and does nothing each time until it has accumulated enough time to take a full default substep of 1/60 sec. What you really want to do is something like this:

Code: Select all

double substep = 1.0 / 600.0;
double step = substep;
world->stepSimuation(step, 1, substep);
Now you might be wondering: "If the world was doing nothing for 9 steps and then stepping forward 1/60th of a second on the 10th step... how did the ball's RigidBody advance during those no-op steps?".

The answer is: the btDefaultMotionState::getWorldTransform() method uses a trick under the hood where it supplies a transform extrapolated forward by the world's step accumulation remainder rather than the RigidBody's true transform. This to prevent aliased motion of a GameObject when the physics substep does not match the render frame period.
daye
Posts: 8
Joined: Mon Sep 04, 2017 2:59 am

Re: Problems occurred when the validation of the Bullet's accuracy with a bouncing ball test

Post by daye »

I have tested your suggestion. But the simulated result is even worse. When the ball contacted with the floor, it rested on the floor. :shock: When I set the time step as world->stepSimuation(1/60.0, 1, 1/60.0), the simulation gave the results as the figure in my first post.
There is another question. I compared the results under timestep 1/60.0 and 1/600.0. The result under 1/600.0 is worse than under 1/60.0. I am confused why the smaller timestep generates the worse result. I think there is a damping coefficient which is associated with time step. But I don't know how to turn off it.
Bullet is really like a black box. I don't know if I set the correct configuration for the simulation. Sometimes I set the wrong configuration just like the sub-timestep for the solver, it will also give the plausible results. Are there some validation tests for Bullet?
Thanks again!
Daye
User avatar
drleviathan
Posts: 849
Joined: Tue Sep 30, 2014 6:03 pm
Location: San Francisco

Re: Problems occurred when the validation of the Bullet's accuracy with a bouncing ball test

Post by drleviathan »

It has been reported in previous forum posts (which I wasn't able to find with a quick search) that an object will sometimes NOT bounce on collision when the substep is too small. Since I couldn't find those threads I have to rely on my memory which tells me the problem was seen at substeps of 1/1000 sec (I'm sure about this) but maybe not at 1/500 sec (not sure).

My advice would be: try a longer substep of about 1/250 sec, which is what some of the pybpullet robotics simulations run at. If that works better and you have the time: it would be interesting to know, for this simple example, at what substep duration the "does not bounce" problem shows up.

Bullet is open source, so it is possible to open the "black box" and examine the code. However it is a real-time physics engine which means some aspects of the architecture may be more complex than you might expect.
Post Reply