How to solve MLCP with Projected Gauss-Seidel?

Please don't post Bullet support questions here, use the above forums instead.
leromi
Posts: 6
Joined: Thu Oct 07, 2010 8:27 pm

How to solve MLCP with Projected Gauss-Seidel?

Post by leromi »

Hi,
I'm new to Rigid Body simulations

Question to those who worked with constrain-based approach.

I try to implement constrain-based solver similarly as in the Kenny Erleben dissertation.
Erleber in his work uses Gauss-Seidel method to solve MLCP.
He doesn't show the details of how to do this.
Can someone explain how PGS works with friction?

When adding the friction law we have to add one more auxiliary row to the matrix: [0, myu, -E, 0] - this last zero in the row goes to the diagonal in the matrix.
How can it be solved using Gauss-Seidel if it needs non-zero diagonal:

x[i+1] = (b - L*x[i+1] - U*x)/D[i,i] + x .

In this case I get division by zero, since D[i,i]=0.

Did anyone have the similar problem with friction and projected Gauss-Seidel in this approach?
Please advice.

Thank you.
Dirk Gregorius
Posts: 861
Joined: Sun Jul 03, 2005 4:06 pm
Location: Kirkland, WA

Re: How to solve MLCP with Projected Gauss-Seidel?

Post by Dirk Gregorius »

The diagonal element is not zero. You must have made a mistake. I recommend using sequential impulses (SI) over PGS. Both methods are mathemetical equivalent, but SI is easier to implement. Especially for friction it allows some easy optimizations. Search the forum for "Central friction". For an introduction on SI see Erin Catto's GDC presentations.

-Dirk
leromi
Posts: 6
Joined: Thu Oct 07, 2010 8:27 pm

Re: How to solve MLCP with Projected Gauss-Seidel?

Post by leromi »

Thank you Dirk for your answer.

I really can find a mistake.
Here is how Sauer and Schomer build the system http://citeseerx.ist.psu.edu/viewdoc/do ... 1&type=pdf , in chapter 2.2 he show the structure of A matrix which clearly has 0 diagonal elements in the bottom.
The same did Denny Erleber in his dissertation ftp://ftp.diku.dk/diku/image/publicatio ... 050401.pdf , chapter 4.6, page 59.
Erleber said that he solve it using Gauss-Seidel. How did he avoid division by zero in PGS?
the system looks like:

Image

I will appreciate if someone give me a hint on where I made a mistake.

Also thank you Dirk for your advise about SI method, I will try to take a closer look at this.

- Ros.
Dirk Gregorius
Posts: 861
Joined: Sun Jul 03, 2005 4:06 pm
Location: Kirkland, WA

Re: How to solve MLCP with Projected Gauss-Seidel?

Post by Dirk Gregorius »

It cannot be zero. You split the inverse effective mass matrix from J*M^-1*JT * lambda = -J*v - beta * C / dt. Here M^-1 is a diagonal matrix and J has the following form (from inspection of the velocity constraint):

(v2 + cross( omega2, r2 ) - v1 - cross( omega1, r1 ) ) * t = 0 => J = [ -t -cross( r2, t ) t cross( r1, t ) ] // Note: Elements in the Jacobian are row vectors

If you now build the diagonal element D = m1 + m2 + cross( r1, t ) * [ I1 * cross( r1, t ) ] + cross( r2, t ) * [ I2 * cross( r2, t ) ] != 0 // Assuming |t| = 1

Write down a simple contact configuration for a ball on a plane yourself and fill the 3x3 matrix. You will find out that the diagonal elements are not zero. In the presence of friction the inverse effective mass matrix becomes positive-semi-definite but not singular. The best way to understand these kind of problems are examples. Think of the simplest problem (e.g. ball on plane) and solve it on paper. This is how I do it.


Cheers,
-Dirk
User avatar
Erwin Coumans
Site Admin
Posts: 4221
Joined: Sun Jun 26, 2005 6:43 pm
Location: California, USA

Re: How to solve MLCP with Projected Gauss-Seidel?

Post by Erwin Coumans »

Hi Ros,

The formulation that you pointed out, described by Steward Trinkle, Anitescu Potra, Sauer Schomer and Kenny's PhD thesis in chapter 4.6, indeed leads to an (M)LCP with zero's on the main diagonal. This is due to the Coulomb friction model, that supports rolling friction etc.
I think that this formulation cannot be solved using PGS, but using something like Lemke for example. Maybe someone more familiar with the Stewart Trinkle/Anitescu Potra formulation can give more background.

Dirk refers to a different formulation, with simplified friction that depends on the current normal force, hence a Non-linear Complementarity Problem (NCP).
This NCP can be solved using Projected Gauss Seidel, or the mathematically equivalent Sequential Impulse. Kenny describes the PGS solution in chapter 6 of his PhD thesis:
sor_lcp_6.59a.jpg
You can find a full derivation of the PGS method in "Heuristic Convergence Rate Improvements of the Projected Gauss–Seidel Method for Frictional Contact Problems." page 145 of the full proceedings of this conference: http://wscg.zcu.cz/WSCG2010/wscg2010.htm.
Erin Catto's slides on sequential impulse are easier to digest. Note that this PGS/SI solution is very popular, and implemented in Bullet and ODE (quickstep).

Thanks,
Erwin
You do not have the required permissions to view the files attached to this post.
ngbinh
Posts: 117
Joined: Fri Aug 12, 2005 3:47 pm
Location: Newyork, USA

Re: How to solve MLCP with Projected Gauss-Seidel?

Post by ngbinh »

leromi wrote:Thank you Dirk for your answer.

Image

- Ros.
This one looks like what we called Stewart-Trinkle or Anitescu-Potra time stepping method. The formulation dates back to 1996 ( Stewart-Trinke paper). Note that it's not the same formulation that Bullet, ODE (and probably PhysX and Havok) are using.

Currently, the only known robust direct solver for it is PATH ( http://www.cs.wisc.edu/cpnet/cpnetsoftware/ ) which is a general MCP solver. The underlying of PATH is a Newton-based method applying to normal map reformulation of the MCP. Based on my experience, PATH is very robust and should be able to solve all simulation problems. On the downside, it's much slower than, say, Bullet or ODE (O(n^3) in general).

Another popular approach is described in http://www.cs.ubc.ca/labs/sensorimotor/ ... sigasia08/ . Basically, it separate the main problem (non-convex) into two sub convex problems. One to solve normal forces only (assumed friction known) and the other solve for friction (assumed normal forces known). Advantage: fast (linear) and "good" behavior (better approximation than Bullet). Disadvantage: could never converge to the real solution.

There are other general methods to solve it too but I haven't seen any successful implementation yet.

@shameless plug: My PhD thesis (working on it right now) proposed two different solution methods. One of which could be almost as fast (linear). Too bad I haven't got time to publish it yet. Maybe in the near future.

So my advice for you for now is to use PATH. I doubt "normal" Lemke could solve all your problems because it's very numerical sensitive and implementing a robust Lemke is a very challenging task and the method (lemke) is also O(n^3).

Hope it helps,

You can also go here: http://bulletphysics.org/Bullet/phpBB3/ ... f=4&t=5672 to see the demo of our 3D engine using Stewart-Trinkle and PATH.
ngbinh
Posts: 117
Joined: Fri Aug 12, 2005 3:47 pm
Location: Newyork, USA

Re: How to solve MLCP with Projected Gauss-Seidel?

Post by ngbinh »

I will try to answer the question: "Why there are zeroes in the diagonal?"

The answer is that:...they are always there. That's the only way we can model (linearized) Coulomb friction. The third line in the matrix formulation is: -transpose(e)*f_b + mu*f_c \perp lambda, where f_b, f_c,lambda are normal forces,friction forces,sliding speed along chosen directions (depend on how we approximate the true Coulomb friction cone). In a way, you can view it as constraining friction forces in both values and directions. The problem here is the coupling between the normal and friction forces so we cannot treat friction constraint the same as normal ones.

In Bullet and ODE formulation, f_b is usually assumed to be known when computing friction forces. That assumption allows us to optimize away the last line and thus treat friction constraint the same as normal constraint. Note that the assumption remove the dependance of normal to friction force which is in general not correct. But for games, it's enough!
User avatar
Erwin Coumans
Site Admin
Posts: 4221
Joined: Sun Jun 26, 2005 6:43 pm
Location: California, USA

Re: How to solve MLCP with Projected Gauss-Seidel?

Post by Erwin Coumans »

ngbinh wrote:In Bullet and ODE formulation, f_b is usually assumed to be known when computing friction forces. That assumption allows us to optimize away the last line and thus treat friction constraint the same as normal constraint. Note that the assumption remove the dependance of normal to friction force which is in general not correct. But for games, it's enough!
This is not correct. The friction force in the formulation used by Bullet and ODE depends on the normal force and vise versa. The friction rows are solved at the end of each PGS iteration, and the most up-to-date normal force is used for the friction force magnitude. The next iteration, effect of the friction constraint propagates back to the normal force. So there is a two-way dependency between normal and friction forces.

Bullet has several friction settings. The default setting keeps the two friction directions, orthogonal to the contact normal, constant during the iterations. This leads to errors, clamping against a 'box' pyramid. Objects that are sliding almost parallel to one of the friction directions will move towards the friction direction. To avoid this unwanted effect, another settings allows to adjust the friction direction every iteration. In that case, we cannot reliably use warm starting or 'accumulated impulse', so we make an error either in the direction or the magnitude of the friction constrains. Stewart Trinkle and Anitescu Potra is physically more realistic in this perspective.

Another drawback is that the high and low limits are updated every iteration, so it is not a usual PGS. This means, we cannot prove convergence anymore.
Still, in practice the friction model is realistic enough for movies and games.
Thanks,
Erwin
ngbinh
Posts: 117
Joined: Fri Aug 12, 2005 3:47 pm
Location: Newyork, USA

Re: How to solve MLCP with Projected Gauss-Seidel?

Post by ngbinh »

Let me put it another way: Bullet does not solve for friction and normal forces together but first assume zero (or known) friction, solve for normal forces, then plug that in to solve for friction forces. In a way, it's exactly the same as method described in http://www.cs.ubc.ca/labs/sensorimotor/ ... sigasia08/ with only one iteration. For games/movies it's enough but maybe not in robotics. One example, when simulating a robot hand grasping a cone shape, it's important to solve for BOTH normal and friction at the same time in order to have a realistic "squeezing" effect.
Dirk Gregorius
Posts: 861
Joined: Sun Jul 03, 2005 4:06 pm
Location: Kirkland, WA

Re: How to solve MLCP with Projected Gauss-Seidel?

Post by Dirk Gregorius »

Sorry, I read the thread way too quick. So what we usually do for games and what is also explained in Kenny Erleben's thesis is a velocity based time stepper. The original problem (using only holonome constraints to get you the idea is):

x' = v
v' = M^-1 * ( JT * lambda + f_ext )
C(x) = 0

So you have three equations for three unknowns (x', v', lambda), but you cannot solve it. The first two and the third equations are not related. Many ways exist, but the one usually used in games uses a symplectic Euler and solves on the velocity level instead of the position level. This is already a linearization since you now look at the tangent space of the original constraint space. So basically you have:

x2 = x1 + v2 * dt
v2 = v1 + M^-1 * ( JT * lambda + f_ext ) * dt
J * v2 = 0

M * v2 - JT * lambda * dt = M * v1 + f_ext * dt
-J* v2 = 0

[ M -JT ] [ v2 ] = b
[ -J 0 ] [ lambda' ] = 0 // lambda' = lambda * dt

This system could *not* be solved with PGS (it also has zeros on its diagonals). But it has other interesting properties, e.g. it is always sparse and for hierarchical structures you can solve it in linear time. If you now plug the second into the third equation you get the so called effective mass form which I already mentioned above:

J*M-^1*JT * lambda = -J * ( v1 + M-^1 * f_ext * dt )


This can be solved with PGS now since J*M-^1*JT is PD diagonal dominant. Usually you don't have only holonome constraints, but also contact, friction, limits, and motors. From there it is pretty simple to add these. Erwin summarized the friction differences very well and I agree that this is usally sufficient for games. I cannot comment on robotics though. Still I recommed using an impulse implementation like SI since they are very efficient and easy to implement. You can also play with different friction ideas like e.g. circular clamping very, very easily. You cannot prove convergence in these cases (at least I can't), but this works really well in practise.


HTH,
-Dirk
leromi
Posts: 6
Joined: Thu Oct 07, 2010 8:27 pm

Re: How to solve MLCP with Projected Gauss-Seidel?

Post by leromi »

Thank you all.

Erwin, you are right Stewart used Lemke to solve MLCP. I was confused by Kenny's dissertation were he presented results and said that he used PSG. I wonder how he did that.

Currently, I have implemented NCP from the paper "Poulsen,M., Niebe,S., Erleben,K.: Heuristic Convergence Rate Improvements of
the Projected Gauss-Seidel Method for Frictional Contact Problems", the link you gave me http://wscg.zcu.cz/WSCG2010/Papers_2010 ... edings.pdf .
It works well for simple configuration, I didn't have a chance to test it for complicated systems.

As I understand SI is very similar to this approach and much faster. I will try to implement it later and compare the results.

I am interested in simulation of stiff systems like large vehicles.
What scheme would you recommend for time stepping, especially for stiff systems?
Explicit - problem with convergence?
Implicit - additional iteration to bring joints to the current time step?
Maybe Verlet? - how does it work with stiff configurations?

Thank you.

Ros.
User avatar
Erwin Coumans
Site Admin
Posts: 4221
Joined: Sun Jun 26, 2005 6:43 pm
Location: California, USA

Re: How to solve MLCP with Projected Gauss-Seidel?

Post by Erwin Coumans »

* Correction: NNCP should be NNCG *
ngbinh wrote:Let me put it another way: Bullet does not solve for friction and normal forces together
I think you misunderstand, Bullet does solve friction and normal forces together during all PGS iterations. The interaction (or impulse exchange) between contact constraints is the same as the interaction between contact and friction constraints. In other words, for n iterations, the friction is based on the most up-to-date normal force for n times, and the normal force is based on the friction force for previous iteration for (n-1) times. By default, Bullet uses 10 iterations, but you can increase this if you like higher quality/stiffness.
leromi wrote: Erwin, you are right Stewart used Lemke to solve MLCP. I was confused by Kenny's dissertation were he presented results and said that he used PSG. I wonder how he did that.
The PGS that Kenny describes in his PhD thesis chapter 6 (did you read chapter 6?) is based on the NCP/PGS formulation used by ODE quickstep or the Bullet PGS/SI constraint solver.
Sequential Impulse is just a different name than PGS, it is not more efficient, just more intuitively explained that's all. The PGS derivation is more math-heavy.

For very stiff systems, or systems with large math ratios, you might want to try a direct solver instead of an iterative solver. You should check out ODE's Dantzig solver (dWorldStep instead of dWorldQuickstep) or ngbinh's work on Trinkle/Stewart using the PATH solver. Perhaps Kenny Erleben's latest NN-CG work might help too?
Thanks,
Erwin
silcowitz
Posts: 2
Joined: Thu Jul 05, 2007 8:25 pm

Re: How to solve MLCP with Projected Gauss-Seidel?

Post by silcowitz »

Just to clear out some potential confusion early on, its not NN-CP, its NN-CG, because the last two letters refers to Conjugate Gradients :) Anyways, I had good results using the NNCG solver in Jinngine (http://code.google.com/p/jinngine/). But I would really like to hear about other peoples experiences, in case somebody should try it out.

/morten silcowitz
Dirk Gregorius
Posts: 861
Joined: Sun Jul 03, 2005 4:06 pm
Location: Kirkland, WA

Re: How to solve MLCP with Projected Gauss-Seidel?

Post by Dirk Gregorius »

I was confused by Kenny's dissertation were he presented results and said that he used PSG. I wonder how he did that.
Look at my post before. It shows quite easily how you arrive at a velocity level formulation that can be solved using PGS.

Note that there is no difference between SI and PGS as Erwin points out correctly. The view of of the problem with SI is much easier (at least in my opinion) and allows some optimizations which are maybe not directly apparent if you take the PGS route. SI is not as abstract as PGS and helps understanding everything better if you ask me.



-Dirk
Dirk Gregorius
Posts: 861
Joined: Sun Jul 03, 2005 4:06 pm
Location: Kirkland, WA

Re: How to solve MLCP with Projected Gauss-Seidel?

Post by Dirk Gregorius »

@Erwin/Morten: You are refering to non-linerar complementary problems. Where did we move from the LCP to the NCP? Which part is actually non-linear in the ODE/Bullet formulation?