Split Impulses and Joints

Please don't post Bullet support questions here, use the above forums instead.
raigan2
Posts: 197
Joined: Sat Aug 19, 2006 11:52 pm

Split Impulses and Joints

Post by raigan2 »

hi,
this has been mentioned offhand in a few threads, just wanted to revive the discussion: Erin Catto's Box2D/sequential-impulse method corrects position error via baumgarte stabilization, OR via a seperate "split" impulse.

He mentioned that using a split impulse only worked well for contacts, not for joints; subsequently I tried using split impulses for joints and found the same, and I think at least one other person (Dirk) mentioned that it didn't work for him either (though that may have been due to some other error).

Today I tried split-impulse joints once more, and they now work.. sometimes. Things will blow up/diverge if the position error is too large, or if the configuration is problematic. Problematic configurations are those which are singular/ill-conditioned in Jacobian IK solvers: when the two r (center-of-mass to joint position) vectors are parallel. So, these problems are possibly due to the approximation/linearization that's used to calculate the split impulses.

Today I compared Baumgarte-Catto, Split-Catto, and Jan Bender's methods, and none of them seem to be terrific for correcting position error in joints.. Bender's method also suffers from error due to linearization. Actually, I couldn't get Bender's method to work as it's given in the paper, I had to scale the position correction down by a couple orders of magnitude to get things to converge.


Starting with full correction and gradually decreasing it with each iteration, or vice versa (starting with soft correction and gradually stiffening it) helped somewhat, but there's still noticeable oscillation with both Split-Catto and Bender. And the former explodes frequently, which is a bit frustrating.. since otherwise it behaves _much_ better (very stiff and non-bouncy) than the other two methods.


Does anyone have anything else to add? Has anyone experimented with a more sophisticated method (nonlinear solver) for calculating the split impulse?

I know of one paper (Weinstein's "Guendelman with Pre-Stabilization for Joints") that does this, but I haven't been able to successfully adapt it for Catto's solver.
crashlander
Posts: 41
Joined: Sat Apr 08, 2006 11:20 am

Post by crashlander »

I've fought with this as well for a while, as you probably noticed from my other posts.

I seem to have it to a point where things seem pretty stable. I never see the "blowing" up you mention. Even if I break the joint and let two bodies drift far apart then re-establish the joint, the bodies spring back together very smoothly.

My angular joint does occilate some, but if I decrease the "relaxation" factor from 1 to .9 or .85, it solves the occiltion problem while keeping the joint stiff enough.

How are you setting up you test? If you give me the details, I could try to mimick it in my engine and see if I get the same result as you.

btw, I have demos of my stuff posted here: http://www.codeplex.com/FarseerPhysics unfortunately, you would need to download and install all the XNA required libraries in order to run it. (no small task.)

Thanks for keeping this topic alive. It is facinating to try and make all this work.

-Jeff
raigan2
Posts: 197
Joined: Sat Aug 19, 2006 11:52 pm

Post by raigan2 »

Are you using split-impulse or Baumgarte for the position error? Baumgarte definitely behaves very well when there's lots of error, but unfortunately it also acts a bit "hyperactive" -- side-by-side with the other methods it's clearly more energetic.

My test scene is a chain of 8 rectangles with one side twice the length of the other; one end of the chain is pinned in place, the other is loose and can be pulled with the mouse. The joint anchors are setup so that the angle between a body's incoming and outgoing anchors is X degrees (where X is 45,90,135, or 180 depending on the test case).

The 180deg case is the worst, things blow up no matter what. The first time I tried split-impulses for joints, I just hacked them into the Box2D code, and the "suspension bridge" scene would instantly blow up.

When they work, split impulses look a lot better than other methods.. but the unpredictable/unstable behaviour is a big problem.
crashlander
Posts: 41
Joined: Sat Apr 08, 2006 11:20 am

Post by crashlander »

Sorry, I must have read your first post to fast. I am using Baumgarte for my joints. I do experience the "hyperactivness" occasionally, but I can deal with it enough for what I'm working on.

I hope someone has some answers for you on split impulses. It'd be nice to have the option of using stiffer joints.

-jeff
stbuzer
Posts: 23
Joined: Fri Dec 08, 2006 10:16 am

Post by stbuzer »

Hi. Sorry for offtop question, but can you tell me, what are split impulses and Baumgarte stabilization?
Jan Bender
Posts: 111
Joined: Fri Sep 08, 2006 1:26 pm
Location: Germany
Contact:

Post by Jan Bender »

Hi,
raigan2 wrote:Bender's method also suffers from error due to linearization.
I would say that the linearization is a big advantage since it prevents you from solving nonlinear equations. In my opinion the solution with the additional error from linearization is faster than e.g. the solution of a nonlinear equation by Newton iteration as Weinstein did in her paper.

The linearization is also essential for determining all impulses by a system of linear equations which can be solved in linear time for models without closed kinematic chains.
raigan2 wrote:Actually, I couldn't get Bender's method to work as it's given in the paper, I had to scale the position correction down by a couple orders of magnitude to get things to converge.
Hm, there is probably a small mistake in the implementation. If you want, I help you with the implementation of my method.

Jan
raigan2
Posts: 197
Joined: Sat Aug 19, 2006 11:52 pm

Post by raigan2 »

By "error due to linearization", I mean oscillation due to the correcting torque rotating the bodies back and forth (which often happens when the joint anchor "r" vectors are parallel).

Aha -- I just posted my code, then noticed that I indeed was making a mistake -- the inverse mass matrix wasn't being properly calculated. I was using the current body state instead of the predicted state.. whoops ;)

Things now work very well, there's no oscillation. Thanks!


I do have a question about your method though -- your paper gives the simulation order as:

-iterate: correct predicted positions
-integrate positions and velocities forward
-iterate: correct current velocities

In my code, I tried changing the order to:

-integrate positions and velocities forward
-iterate: correct current velocities
-iterate: correct predicted positions

And saw no difference -- which makes sense since really the relative order of the steps is preserved, only the point at which rendering happens changes. Am I missing something?
Jan Bender
Posts: 111
Joined: Fri Sep 08, 2006 1:26 pm
Location: Germany
Contact:

Post by Jan Bender »

Things now work very well, there's no oscillation. Thanks!
I never solved a problem that easy :wink:
-iterate: correct predicted positions
-integrate positions and velocities forward
-iterate: correct current velocities

In my code, I tried changing the order to:

-integrate positions and velocities forward
-iterate: correct current velocities
-iterate: correct predicted positions

And saw no difference -- which makes sense since really the relative order of the steps is preserved, only the point at which rendering happens changes. Am I missing something?
There should be no difference during the simulation since you simulate in a loop. Just the first step is different. In your case you integrate positions and velocities in the first step without any position correction and in my case I correct them also in the first step. I assumed that the model is in a valid state at time 0. The positions change during the first integration so you have to start with the position correction. It is just to be totally correct.

My method is very robust. So even if you forget in one step to correct the positions in the next step they will be corrected again. That's why it works even if you start with the integration. Also if you stop the iteration before all joints have been corrected totally the model will not explode. This I use to speed up the simulation.

If you have other questions concerning my method. Just ask me. I will try to help you.

Jan
crashlander
Posts: 41
Joined: Sat Apr 08, 2006 11:20 am

@raigen

Post by crashlander »

@raigan2, does the now correct Bender method give you the rigid angle joints you've been aiming for?

Now that you have it working, will you use it over split impulses for angular joints?

Thanks for doing the leg work to compare these methods.
raigan2
Posts: 197
Joined: Sat Aug 19, 2006 11:52 pm

Post by raigan2 »

yes, but with a couple grains of salt:

-so far I have only "pin" joints, not fixed/orientation joints working
-I'm also working on some particle-based methods which are competitive with impulse-based methods, however (as with rigid bodies) I haven't gotten a terrific "fixed"/orientation constraint working yet.

Rigid-body and particle-based methods seem complimentary, since rigid bodies implicitly enforce rigidity but need to explicitly enforce joint constraints, while particle-based methods implicitly enforce joint constraints -- since the particle positions _are_ the joint positions, joints are always 100% rigid -- but require explicit enforcement of rigidity.

I've been toying with the idea of simply using a dual representation, where particles are used to enforce joints, and rigid bodies are used for collision/joint limits/etc.. however, so far I just have two separate testbeds.

By the end of the weekend I'll hopefully have added orn constraints, so we'll see how things work with them. Really, I think the problem thus far has been my constraint formulation, not the solver used ;)

Anyway, here's a simple test I made: http://harveycartel.org/raigan/impTest03.swf

the terrible controls:
-click to set focus
-click to tick once, turn on capslock to tick continuously
-~ to toggle a fixed constraint at one end of the chain
-hold z to grab a box with the mouse
-1/2 select the prev/next box for grabbing
-q/w/e select catto-baumgarte, catto-split, and bender solvers

I'm using 8 iterations for the two catto methods, 4 position/4 velocity iterations for bender. Notice that if you grab one end of the chain in bender and swing it around in a circle, things can fail to converge/explode, however this is probably due to my low # of position-correction iterations.
raigan2
Posts: 197
Joined: Sat Aug 19, 2006 11:52 pm

Post by raigan2 »

I've just implemented a combined pos+orn constraint (in 2D, K = (JM^-1J^T)^-1 is a 3x3 matrix) using Bender's method, and it's much more rigid than using Catto+Baumgarte:

http://harveycartel.org/raigan/impTest05.swf

(same controls as before)

This is just using 4 iterations each of position and velocity correction.

Still not super-solid like the joint positions though. I still think that using a nonlinear solver would help a lot, I'm going to try that next.

Bender's method is a bit more costly, since the K matrix needs to be inverted once per iteration as opposed to Catto's once per simulation step. I'm not sure if this would really be noticed outside of Flash though ;) It's just a few more multiplies, and in the case of pos+orn there are several 0 elements in K which lets you reduce the work further.


Thanks very much to everyone for their patience and advice, sorry if I've been obnoxious.. I finally feel like I understand this stuff well enough. Kenny Erleben's book has been a great help also.


I really wish that split-impulses could be used for joint constraints, I don't really understand why they're not working for me. Possibly I keep making the same mistake..
Jan Bender
Posts: 111
Joined: Fri Sep 08, 2006 1:26 pm
Location: Germany
Contact:

Post by Jan Bender »

raigan2 wrote:yes, but with a couple grains of salt:

-so far I have only "pin" joints, not fixed/orientation joints working
In the paper "Fast Dynamic Simulation of Multi-Body Systems Using Impulses" I explain how to simulate other joint constraints.
raigan2 wrote:Bender's method is a bit more costly, since the K matrix needs to be inverted once per iteration as opposed to Catto's once per simulation step.
That's wrong. The matrix K is constant at a time t. So you only have to invert it once per simulation step. Then you can use it for the velocity correction and for the position correction of the same point of time.

Jan
raigan2
Posts: 197
Joined: Sat Aug 19, 2006 11:52 pm

Post by raigan2 »

hm.. I think I'm missing something yet again: For position correction, you're moving things forward in time and using that predicted-future state to calculate an impulse. Since J varies with position/orientation of the bodies, if you use a predicted position/orientation to calculate the error, don't you need to recalculate J to reflect the predicted position/orientation?

Otherwise the system that you're solving seems to be sort of mixed:
K*lambda = -error

if error is measured at time t+1, shouldn't K also be?

[EDIT: I just tried using a constant K, it seems to "blow up"/fail to converge much more easily than when using a predicted K. Maybe using the predicted K is adding a bit of damping? anyway, you can see it here: http://harveycartel.org/raigan/impTest07.swf click to set focus and turn on capslock to run the sim (or click for frame-by-frame); e changes to "predicted K", r changes to "constant K", 4 iterations of pos and vel correction in each, spacebar to reset bodies (changes to predicted K solver)]
Erin Catto
Posts: 316
Joined: Fri Jul 01, 2005 5:29 am
Location: Irvine
Contact:

Post by Erin Catto »

Split impulses are a weak attempt to mimic a more accurate solver. It is fortunate that they work so well for contact. :)

However, they don't work well with spherical joints.

A more accurate solver would perform these steps:
1: compute the exact global velocity solution without Baumgarte or any other position considerations.
2: integrate positions
3: project the current positions onto the constraint manifold with as little movement as possible.

We can address 3 independent of the accuracy of 1.

Step 3 involves solving the position constraints starting from a (hopefully) nearby solution. We can do this using Newton iteration.

Newton Iteration:

Code: Select all

while !converged
  compute the Jacobian at x
  invert the Jacobian
  x = x - invJacobian * position_error
end
Now, we don't have the exact invJacobian for the system. We are doing a Gauss-Seidel style solution using Sequential Impulses.

Code: Select all

while !converged
  pre-step (compute Jacobian)
  for iter = 1:max_iters
    apply_impulses at each joint
  end
end
The inner-loop approximately inverts the Jacobian (weight by the masses).

I put an example of this up:

http://www.gphysics.com/files/Box2D_SuperSplit.zip

I'm calling this Super Split Impulses because the position correction happens after the regular velocity integration and I have introduced an outer iteration.

I put in a new demo to test this: a multi-pendulum (Demo 0). I made the links lighter than the bomb as a stress test.

I haven't tested Super Split with contact.

A couple more comments:
- Obviously this is much more expensive than Baumgarte or split impulses.
- I have usually been satisfied with Baumgarte for joints, I'm not sure why you are seeing problems with it. Demo 0 works fined with it (it is stable if the bias factor is not too large). You might compare your test case with mine.
Jan Bender
Posts: 111
Joined: Fri Sep 08, 2006 1:26 pm
Location: Germany
Contact:

Post by Jan Bender »

@raigan2

The matrix K must be determined for the current point of time whereas the error is computed for the future. The question is how the velocities must changed NOW so that the error of the FUTURE is corrected.

Here is the code of my ball joint:

Code: Select all

	
	if (firstIteration)
	{
		// Since the matrix K is symmetric the inverse can be determined by the
		// optimized function symmInverse ()
		Kinv = ((body1->Kmatrix(point1) + body2->Kmatrix(point2)).symmInverse ();
		firstIteration = false;
	}
	
	// Determine the error at time t+h, the error is stored in the variable delta
   getDelta(error, integrationMethod, h);

	double l = delta->length ();
	if (l > maxdistance)
	{
		Vector3D imp = Kinv * (*(Vector3D*) delta) *(1.0/h);

		body1->impulse(point1, imp);
		body2->impulse(point2, -imp);					

		// Some velocities changed => do another iteration
		return true;
	}
	
	// Nothing changed
	return false;
To get the value delta you have to solve the equation

r' = angularVelocity x r

where r is the vector from the center of mass to the joint point. By numerical integration you get r(t+h). The new position of a joint point you get by

a(t+h) = r(t+h) + c(t+h) = r(t+h) + c(t) + v(t)*h + 1/2 * Fext/m * h^2

The matrix K is computed by this method:

Code: Select all

Matrix3x3 RigidBody::Kmatrix (Vector3D *p)
{
	Matrix3x3 K; 
	if (dynamic)
	{
		Vector3D v1 = *p - actState.centerOfMass;
		double a = v1[0];
		double b = v1[1];
		double c = v1[2];
		Matrix3x3 *J = &actState.inertiaInverseW;					// inertia tensor in world space
		double j1 = (*J)[0][0];
		double j2 = (*J)[0][1];
		double j3 = (*J)[0][2];
		double j4 = (*J)[1][0];
		double j5 = (*J)[1][1];
		double j6 = (*J)[1][2];
		double j7 = (*J)[2][0]; 
		double j8 = (*J)[2][1];
		double j9 = (*J)[2][2];

		double m = (1.0/mass);
		K[0][0]=c*c*j5 - b*c*(j6 + j8) + b*b*j9 +m;
		K[0][1]=-(c*c*j4) + a*c*j6 + b*c*j7 - a*b*j9;
		K[0][2]=b*c*j4 - a*c*j5 - b*b*j7 + a*b*j8;
		K[1][0]=-(c*c*j2) + b*c*j3 + a*c*j8 - a*b*j9;
		K[1][1]=c*c*j1 - a*c*(j3 + j7) + a*a*j9 + m;
		K[1][2]=-(b*c*j1) + a*c*j2 + a*b*j7 - a*a*j8;
		K[2][0]=b*c*j2 - b*b*j3 - a*c*j5 + a*b*j6;
		K[2][1]=-(b*c*j1) + a*b*j3 + a*c*j4 - a*a*j6;
		K[2][2]=b*b*j1 - a*b*(j2 + j4) + a*a*j5 +m;

	}
	else
		K = Matrix3x3 (Vector3D (), Vector3D (), Vector3D ());    // zero matrix
  return K;
}
This method is already optimized otherwise the matrix would look like this:

1/m*Identity3 - crossProd(r) * Jinv * crossProd(r)

By the way, ?t is better to limit the impulse imp to a maximum magnitude. Especially if you stop after a few iterations. This prevents the model from exploding.

Jan
Post Reply