bulletphysics / bullet3

Bullet Physics SDK: real-time collision detection and multi-physics simulation for VR, games, visual effects, robotics, machine learning etc.
http://bulletphysics.org
Other
12.45k stars 2.86k forks source link

Question: What is the unit of Damping in Generic Spring Constraint? #345

Closed alda30 closed 3 years ago

alda30 commented 9 years ago

Hey all,

In a simulation I have to use a spring with damping. It is an engineering simulation, so I should take the correct value for damping. As far as I understood there are two sort of spring definitions in Bullet: btGeneric6DofSpringConstraint and btGeneric6DofSpring2Constraint. The dampings used in both are different in the units. (for example for btGeneric6DofSpringConstraint if you take damping =1 means no damping, and for btGeneric6DofSpring2Constraint zero damping means no damping condition.)

And surprisingly non of them don't seem to be in the units of N.s/m. I looked through the code and found out that the damping parameter used in the original spring (btGeneric6DofSpringConstraint) code is just a factor that applied to introduce some loss of the resilient force of the spring:

btScalar force = delta * m_springStiffness[i];
            btScalar velFactor = info->fps * m_springDamping[i] / btScalar(info->m_numIterations);
            m_linearLimits.m_targetVelocity[i] =  velFactor * force;

So, the unit of this damping should be something like [m/N] which is quite strange! (to me)

However, in the new spring code (btGeneric6DofSpring2Constraint) the damping ratio is multiplied directly to the current velocity of the oscillating object:

btScalar kd = limot->m_springDamping;
        btScalar ks = limot->m_springStiffness;
        btScalar vel = rotational ? angVelA.dot(ax1) - angVelB.dot(ax1) : linVelA.dot(ax1) - linVelB.dot(ax1);
//      btScalar erp = 0.1;
        btScalar cfm = 0.0;
        btScalar mA = 1.0 / m_rbA.getInvMass();
        btScalar mB = 1.0 / m_rbB.getInvMass();
        btScalar m = mA > mB ? mB : mA;
        btScalar angularfreq = sqrt(ks / m);
.
.
.
btScalar fs = ks * error * dt;
        btScalar fd = -kd * (vel) * (rotational ? -1 : 1) * dt;
        btScalar f = (fs+fd);

This damping seems quite reasonable in algorithm and the unit seems to be [N.s/m], however, when I compare the behaviour of oscillation of a simple linear spring-mass system with the results of analytical solution, the behaviour is not quite in conformation. For comparison you can simply model a spring and a mass at the end, and monitor the location of the object attached to the spring, and for the analytical solution you can easily refer to here. Note that the resistance coef. is damping and undamped angular frequency is the calculated by sqrt(springStiffness/massOfOscillatingRigidBody).

Can someone comment on this? What do you think about the units of damping in bullet? How can I choose the exact amount of damping as I wish in Bullet?

erwincoumans commented 9 years ago

I asked the developer of the btGeneric6DofSpring2Constraint for some comments, so hopefully he will reply here later. Although I haven't looked into the damping terms myself yet, here are some possible reasons for differences between analytical solution and btGeneric6DofSpring2Constraint: 1) damping might be time-step size dependent 2) we only simulate first order (velocity level) so differences might be in second order terms (acceleration) 3) the use of integrator

It would be good to create a spring demo, based on btGeneric6DofSpring2Constraint (the older variant will be deprecated), and provide actual comparison numbers/graphs.

GaborPuhr commented 9 years ago

Hi,

The equation in http://keisan.casio.com/exec/system/1224772199 is a transformed version of the original F = -k * x - c * dx/dt equation.

In here the c is the viscous damping coefficient. The btGeneric6DofSpring2Constraint uses this.

You have to transform your resistance coefficient (Kappa)

c = Kappa / (2 * m)

However I think it is generally better to use the damping ratio (zeta), because in this case: zeta > 1 -> overdamped zeta = 1 -> critically damped zeta < 1 -> underdamped

c = zeta * (2 * sqrt(m * k))

As for the frequency that you wrote is correct:

k = omega0 ^ 2 * m

Please note that while the analytic equation is the perfect solution for the above differential equation, the Bullet can't use this because other forces and constraints have to be considered. So the result is an approximation. The good news is: if you set up the k and c values correctly the solution of the Bullet is very close for the analytic solution. (even with the original SI/PGS solver) (My colleague Tamas Ummenhoffer made small example with a few different spring solvers and the Bullet's solution was the closest.) Obviously you will never be able got a perfect solution (but that would be impossible in computer calculation world anyway)

You can always increase a precision by decreasing the delta t of the Bullet or play with the solver. (change it to Dijkstra, NNCG or increase the iteration count if it has)

Let me know if it solves your problem.

Best Regards: Gabor

alda30 commented 9 years ago

Thank you Gabor, it solves the problem. Small correction is that " c = Kappa * (2 * m) " I did simulation for single direction linear spring and here is the results (with default solver). it seems good now: ss

It is for two cases with different mass, stiffness and damping, but with the same initial amplitude.

It may be concluded that for engineering simulations (or even in other applications) usage of btGeneric6DofSpring2Constraint would be preferred, since the damping here is not dependent on the time step size (tested). Moreover, its is more physically correct.

GaborPuhr commented 9 years ago

You are welcome. Thanks for the correction. I was lost in those lot of damping values. :) Your results are nice. That difference in the case with the bigger damping can be decreased if you decrease the time step. (if you need it) I made the btGeneric6DofSpring2Constraint for the Engineering simulation that I am working on, because there was precision problems with the original. So I also think it is preferred to be used at least with Engineering simulations. :) Best Regards

erwincoumans commented 9 years ago

Thanks for the help Gabor and for the report Ehsanizadi. Ehsanizadi, do you mind helping out with some code snippet for Bullet that can help re-creating that spring test case, as well as the values you entered for the analytic solution (used to create that graph)?

alda30 commented 9 years ago

Not at all, Its a pleasure. I am currently working on Bullet for my research dealing with applicability of physics engines (I've already chosen Bullet) in simulation of (geotechnical) engineering problems. The example problems I work on, all are here. They are now at very basic level, because I had to first check the some basic features of Bullet, such as accuracy of friction calculation with different pairs of collision shapes (box-box, box sphere, trimnesh-box, etc.) and also the spring simulation. Currently, I have some results on the accuracy of the friction in Bullet, if you are interested I can share them with you. The codes are not written in the pattern of Bullet app demos, but in a very simple form, mostly like the format of "HelloWorld" example! :) Afterwards, I will simulate some more sophisticated geotechnical engineering-based problems including thousands of rigidbodies as well as softbodies.

In the above link, the friction calculation example is put in the "tiltPlaneTest" folder (since the friction test was simulated using a tilting plane) and the springSimulation folder contains the code I posted the results of that.

For the above graph there are two cases, lets call them 'high damping' and 'low damping' cases, the chosen parameters are as listed below:

High damping case:


Bullet parameters

Analytical solution

Low damping case:


Bullet parameters

Analytical solution

Apart from that, I did a small test on the effect of time step size on the accuracy of Bullet. Favorable accuracy can be achieved with tunning of the time step size: 2 The chosen parameters here, are the same as the Low damping case.

Thank you for developing this great engine! Ehsan

GaborPuhr commented 9 years ago

Hi Ehsan,

For the time steps: <30hz is usually not advised 30hz can work, but the result will be very approximate (for games sometimes it is enough) 50-60hz is the most common for realtime applications. 100-120hz for high precision.

For a few special application for example in robotics it is not rare the 1000hz, but it can be usually realtime only with a very few objects and/or constraints.

Above 100hz it is usually advised to use the double precision version.

Best Regards

alda30 commented 9 years ago

Hi Gabor,

Yes indeed you are right. The graph was only to give an idea to the user how the accuracy would be affected by the range of time step.

erwincoumans commented 9 years ago

There might be other issues with the spring in the btGeneric6DofSpring2Constraint See http://bulletphysics.org/Bullet/phpBB3/viewtopic.php?f=9&t=10541 We need to look at it again.