Advanced Character Physics
[ August 31, 2005 ] by Thomas Jakobsen
This article explains the basic elements of an approach to physically-based modeling, which allows simulation of cloth, soft and rigid bodies and even articulated or constrained bodies using both forward and inverse kinematics.


Abstract

This paper explains the basic elements of an approach to physically-based modeling which is well suited for interactive use. It is simple, fast, and quite stable, and in its basic version the method does not require knowledge of advanced mathematical subjects (although it is based on a solid mathematical foundation). It allows for simulation of both cloth; soft and rigid bodies; and even articulated or constrained bodies using both forward and inverse kinematics.

The algorithms were developed for IO Interactive’s game Hitman: Codename 47. There, among other things, the physics system was responsible for the movement of cloth, plants, rigid bodies, and for making dead human bodies fall in unique ways depending on where they were hit, fully interacting with the environment (resulting in the press oxymoron “lifelike death animations”).

The article also deals with subtleties like penetration test optimization and friction handling.


1. Introduction

The use of physically-based modeling to produce nice-looking animation has been considered for some time and many of the existing techniques are fairly sophisticated. Different approaches have been proposed in the literature [Baraff, Mirtich, Witkin, and others] and much effort has been put into the construction of algorithms that are accurate and reliable. Actually, precise simulation methods for physics and dynamics have been known for quite some time from engineering. However, for games and interactive use, accuracy is really not the primary concern (although it’s certainly nice to have) – rather, here the important goals are believability (the programmer can cheat as much as he wants if the player still feels immersed) and speed of execution (only a certain time per frame will be allocated to the physics engine). In the case of physics simulation, the word believability also covers stability; a method is no good if objects seem to drift through obstacles or vibrate when they should be lying still, or if cloth particles tend to “blow up”.

The methods demonstrated in this paper were created in an attempt to reach these goals. The algorithms were developed and implemented by the author for use in IO Interactive’s computer game Hitman: Codename 47, and have all been integrated in IO’s in-house game engine Glacier. The methods proved to be quite simple to implement (compared to other schemes at least) and have high performance.

The algorithm is iterative such that, from a certain point, it can be stopped at any time. This gives us a very useful time/accuracy trade-off: If a small source of inaccuracy is accepted, the code can be allowed to run faster; this error margin can even be adjusted adaptively at run-time. In some cases, the method is as much as an order of magnitude faster than other existing methods. It also handles both collision and resting contact in the same framework and nicely copes with stacked boxes and other situations that stress a physics engine.

In overview, the success of the method comes from the right combination of several techniques that all benefit from each other:

  • A so-called Verlet integration scheme.
  • Handling collisions and penetrations by projection.
  • A simple constraint solver using relaxation.
  • A nice square root approximation that gives a solid speed-up.
  • Modeling rigid bodies as particles with constraints.
  • An optimized collision engine with the ability to calculate penetration depths.

Each of the above subjects will be explained shortly. In writing this document, the author has tried to make it accessible to the widest possible audience without losing vital information necessary for implementation. This means that technical mathematical explanations and notions are kept to a minimum if not crucial to understanding the subject. The goal is demonstrating the possibility of implementing quite advanced and stable physics simulations without dealing with loads of mathematical intricacies.

The content is organized as follows. First, in Section 2 , a “velocity-less” representation of a particle system will be described. It has several advantages, stability most notably and the fact that constraints are simple to implement. Section 3 describes how collision handling takes place. Then, in Section 4 , the particle system is extended with constraints allowing us to model cloth. Section 5 explains how to set up a suitably constrained particle system in order to emulate a rigid body. Next, in Section 6 , it is demonstrated how to further extend the system to allow articulated bodies (that is, systems of interconnected rigid bodies with angular and other constraints). Section 7 contains various notes and shares some experience on implementing friction, etc. Finally, in Section 8 a brief conclusion.

In the following, bold typeface indicates vectors. Vector components are indexed by using subscript, i.e.: x =(x1, x2, x3) .


2. Verlet integration

The heart of the simulation is a particle system. Typically, in implementations of particle systems, each particle has two main variables: Its position x and its velocity v. Then in the time-stepping loop, the new position x’ and velocity v’ are often computed by applying the rules:

x' = x + v·Δt
v' = v + a·Δt

where Δt is the time step, and a is the acceleration computed using Newton’s law f = m·a (where f is the accumulated force acting on the particle). This is simple Euler integration.

Here, however, we choose a velocity-less representation and another integration scheme: Instead of storing each particle’s position and velocity, we store its current position x and its previous position x*. Keeping the time step fixed, the update rule (or integration step) is then:

x' = 2x - x* + a·Δt2
x* = x

This is called Verlet integration (see [Verlet]) and is used intensely when simulating molecular dynamics. It is quite stable since the velocity is implicitly given and consequently it is harder for velocity and position to come out of sync. (As a side note, the well-known demo effect for creating ripples in water uses a similar approach.) It works due to the fact that 2x-x*=x+(x-x*) and x-x* is an approximation of the current velocity (actually, it’s the distance traveled last time step). It is not always very accurate (energy might leave the system, i.e., dissipate) but it’s fast and stable. By lowering the value 2 to something like 1.99 a small amount of drag can also be introduced to the system.

At the end of each step, for each particle the current position x gets stored in the corresponding variable x*. Note that when manipulating many particles, a useful optimization is possible by simply swapping array pointers.

The resulting code would look something like this (the Vector3 class should contain the appropriate member functions and overloaded operators for manipulation of vectors):

// Sample code for physics simulation
class ParticleSystem {
	Vector3	m_x[NUM_PARTICLES]; // Current positions
	Vector3	m_oldx[NUM_PARTICLES]; // Previous positions
	Vector3	m_a[NUM_PARTICLES]; // Force accumulators
	Vector3	m_vGravity; // Gravity
	float		m_fTimeStep;
public:
	void 		TimeStep();
private:
	void 		Verlet();
	void 		SatisfyConstraints();
	void		AccumulateForces();
//	(constructors, initialization etc. omitted)
};
// Verlet integration step
void ParticleSystem::Verlet() {
	for(int i=0; i<NUM_PARTICLES; i++) {
		Vector3& x = m_x[i];
		Vector3 temp = x;
		Vector3& oldx = m_oldx[i];
		Vector3& a = m_a[i];
		x += x-oldx+a*fTimeStep*fTimeStep;
		oldx = temp;
	}
}
// This function should accumulate forces for each particle
void ParticleSystem::AccumulateForces()
{	
// All particles are influenced by gravity
	for(int i=0; i<NUM_PARTICLES; i++)  m_a[i] = m_vGravity;
}
// Here constraints should be satisfied
void ParticleSystem::SatisfyConstraints() {
// Ignore this function for now
}
void ParticleSystem::TimeStep() {
	AccumulateForces();
	Verlet();
	SatisfyConstraints();
}

The above code has been written for clarity, not speed. One optimization would be using arrays of float instead of Vector3 for the state representation. This might also make it easier to implement the system on a vector processor.

This probably doesn’t sound very groundbreaking yet. However, the advantages should become clear soon when we begin to use constraints and switch to rigid bodies. It will then be demonstrated how the above integration scheme leads to increased stability and a decreased amount of computation when compared to other approaches.

Try setting a=(0,0,1), for example, and use the start condition x=(1,0,0), x*=(0,0,0), then do a couple of iterations by hand and see what happens.


3. Collision and contact handling by projection

So-called penalty-based schemes handle contact by inserting springs at the penetration points. While this is very simple to implement, it has a number of serious drawbacks. For instance, it is hard to choose suitable spring constants such that, on one hand, objects don’t penetrate too much and, on the other hand, the resulting system doesn’t get unstable. In other schemes for simulating physics, collisions are handled by rewinding time (by binary search for instance) to the exact point of collision, handling the collision analytically from there and then restarting the simulation – this is not very practical from a real-time point of view since the code could potentially run very slowly when there are a lot of collisions.

Here, we use yet another strategy. Offending points are simply projected out of the obstacle. By projection, loosely speaking, we mean moving the point as little as possible until it is free of the obstacle. Normally, this means moving the point perpendicularly out towards the collision surface.

Let’s examine an example. Assume that our world is the inside of the cube (0,0,0)-(1000,1000,1000) and assume also that the particles’ restitution coefficient is zero (that is, particles do not bounce off surfaces when colliding). To keep all positions inside the valid interval, the corresponding projection code would be:

// Implements particles in a box
void ParticleSystem::SatisfyConstraints() {
	for(int i=0; i<NUM_PARTICLES; i++) { // For all particles
		Vector3& x = m_x[i];
		x = vmin(vmax(x, Vector3(0,0,0)), Vector3(1000,1000,1000));
	}
}

(vmax operates on vectors taking the component-wise maximum whereas vmin takes the component-wise minimum.) This keeps all particle positions inside the cube and handles both collisions and resting contact. The beauty of the Verlet integration scheme is that the corresponding changes in velocity will be handled automatically. In the following calls to TimeStep(), the velocity is automatically regulated to contain no component in the normal direction of the surface (corresponding to a restitution coefficient of zero). See Figure 1.

Figure 1. Ten timesteps and two particles.

Try it out – there is no need to directly cancel the velocity in the normal direction. While the above might seem somewhat trivial when looking at particles, the strength of the Verlet integration scheme is now beginning to shine through and should really become apparent when introducing constraints and coupled rigid bodies in a moment.


4. Solving several concurrent constraint s by relaxation

A common model for cloth consists of a simple system of interconnected springs and particles. However, it is not always trivial to solve the corresponding system of differential equations. It suffers from some of the same problems as the penalty-based systems: Strong springs leads to stiff systems of equations that lead to instability if only simple integration techniques are used, or at least bad performance – which leads to pain. Conversely, weak springs lead to elastically looking cloth.

However, an interesting thing happens if we let the stiffness of the springs go to infinity: The system suddenly becomes solvable in a stable way with a very simple and fast approach. But before we continue talking about cloth, let’s revisit the previous example. The cube considered above can be thought of as a collection of unilateral (inequality) constraints (one for each side of the cube) on the particle positions that should be satisfied at all times:

xi ≥ 0 and ≤ 1000 for i = 1,2,3  (C1)

In the example, constraints were satisfied (that is, particles are kept inside the cube) by simply modifying offending positions by projecting the particles onto the cube surface. To satisfy (C1), we use the following pseudo-code:

// Pseudo-code to satisfy (C1)
for i=1,2,3
	set xi=min{max{xi, 0}, 1000}

One may think of this process as inserting infinitely stiff springs between the particle and the penetration surface – springs that are exactly so strong and suitably damped that instantly they will attain their rest length zero.

We now extend the experiment to model a stick of length 100. We do this by setting up two individual particles (with positions x1 and x2) and then require them to be a distance of 100 apart. Expressed mathematically, we get the following bilateral (equality) constraint:

|x2 - x1| = 100  (C2)

Although the particles might be correctly placed initially, after one integration step the separation distance between them might have become invalid. In order to obtain the correct distance once again, we move the particles by projecting them onto the set of solutions described by (C2). This is done by pushing the particles directly away from each other or by pulling them closer together (depending on whether the erroneous distance is too small or too large). See Figure 2.

Figure 2. Fixing an invalid distance by moving the particles.

The pseudo-code for satisfying the constraint (C2) is:

// Pseudo-code to satisfy (C2)
delta = x2-x1;
deltalength = sqrt(delta*delta);
diff = (deltalength-restlength)/deltalength;
x1 -= delta*0.5*diff;
x2 += delta*0.5*diff;

Note that delta is a vector so delta*delta is actually a dot product. With restlength=100 the above pseudo-code will push apart or pull together the particles such that they once more attain the correct distance of 100 between them. Again we may think of the situation as if a very stiff spring with rest length 100 has been inserted between the particles such that they are instantly placed correctly.

Now assume that we still want the particles to satisfy the cube constraints. By satisfying the stick constraint, however, we may have invalidated one or more of the cube constraints by pushing a particle out of the cube. This situation can be remedied by immediately projecting the offending particle position back onto the cube surface once more – but then we end up invalidating the stick constraint again.

eally, what we should do is solve for all constraints at once, both (C1) and (C2). This would be a matter of solving a system of equations. However, we choose to proceed indirectly by local iteration. We simply repeat the two pieces of pseudo-code a number of times after each other in the hope that the result is useful. This yields the following code:

// Implements simulation of a stick in a box 
void ParticleSystem::SatisfyConstraints() {
for(int j=0; j<NUM_ITERATIONS; j++) {
	// First satisfy (C1)
		for(int i=0; i<NUM_PARTICLES; i++) { // For all particles
			Vector3& x = m_x[i];
			x = vmin(vmax(x, Vector3(0,0,0)), Vector3(1000,1000,1000));
		}

		// Then satisfy (C2)
		Vector3& x1 = m_x[0];
		Vector3& x2 = m_x[1];
		Vector3 delta = x2-x1;
		float deltalength = sqrt(delta*delta);
		float diff = (deltalength-restlength)/deltalength;
		x1 -= delta*0.5*diff;
		x2 += delta*0.5*diff;
	}
}

(Initialization of the two particles has been omitted.) While this approach of pure repetition might appear somewhat naïve, it turns out that it actually converges to the solution that we are looking for! The method is called relaxation (or Jacobi or Gauss-Seidel iteration depending on how you do it exactly, see [Press]). It works by consecutively satisfying various local constraints and then repeating; if the conditions are right, this will converge to a global configuration that satisfies all constraints at the same time. It is useful in many other situations where several interdependent constraints have to be satisfied at the same time.

The number of necessary iterations varies depending on the physical system simulated and the amount of motion. It can be made adaptive by measuring the change from last iteration. If we stop the iterations early, the result might not end up being quite valid but because of the Verlet scheme, in next frame it will probably be better, next frame even more so etc. This means that stopping early will not ruin everything although the resulting animation might appear somewhat sloppier.

CLOTH SIMULATION

The fact that a stick constraint can be thought of as a really hard spring should make apparent its usefulness for cloth simulation as sketched in the beginning of this section. Assume, for example, that a hexagonal mesh of triangles describing the cloth has been constructed. For each vertex a particle is initialized and for each edge a stick constraint between the two corresponding particles is initialized (with the constraint’s “rest length” simply being the initial distance between the two vertices).

The function HandleConstraints() then uses relaxation over all constraints. The relaxation loop could be iterated several times. However, to obtain nicely looking animation, actually for most pieces of cloth only one iteration is necessary! This means that the time usage in the cloth simulation depends mostly on the N square root operations and the N divisions performed (where N denotes the number of edges in the cloth mesh). As we shall see, a clever trick makes it possible to reduce this to N divisions per frame update – this is really fast and one might argue that it probably can’t get much faster.

// Implements cloth simulation
struct Constraint {
	int	particleA, particleB;
	float	restlength;
};
// Assume that an array of constraints, m_constraints, exists
void ParticleSystem::SatisfyConstraints() {
for(int j=0; j<NUM_ITERATIONS; j++) {
	for(int i=0; i<NUM_CONSTRAINTS; i++) {
	 	Constraint& c = m_constraints[i];
		Vector3& x1 = m_x[c.particleA];
		Vector3& x2 = m_x[c.particleB];
		Vector3 delta = x2-x1;
		float deltalength = sqrt(delta*delta);
		float diff=(deltalength-c.restlength)/deltalength;
		x1 -= delta*0.5*diff;
		x2 += delta*0.5*diff;
	}

	// Constrain one particle of the cloth to origo
	m_x[0] = Vector3(0,0,0);
	}
}

We now discuss how to get rid of the square root operation. If the constraints are all satisfied (which they should be at least almost), we already know what the result of the square root operation in a particular constraint expression ought to be, namely the rest length r of the corresponding stick. We can use this fact to approximate the square root function. Mathematically, what we do is approximate the square root function by its 1 st order Taylor-expansion at a neighborhood of the rest length r (this is equivalent to one Newton-Raphson iteration with initial guess r). After some rewriting, we obtain the following pseudo-code:

// Pseudo-code for satisfying (C2) using sqrt approximation
delta = x2-x1;
delta*=restlength*restlength/(delta*delta+restlength*restlength)-0.5;
x1 -= delta;
x2 += delta;

Notice that if the distance is already correct (that is, if |delta|=restlength), then one gets delta=(0,0,0) and no change is going to happen.

Per constraint we now use zero square roots, one division only, and the squared value restlength*restlength can even be precalculated! The usage of time consuming operations is now down to N divisions per frame (and the corresponding memory accesses) – it can’t be done much faster than that and the result even looks quite nice. Actually, in Hitman, the overall speed of the cloth simulation was limited mostly by how many triangles it was possible to push through the rendering system.

The constraints are not guaranteed to be satisfied after one iteration only, but because of the Verlet integration scheme, the system will quickly converge to the correct state over some frames. In fact, using only one iteration and approximating the square root removes the stiffness that appears otherwise when the sticks are perfectly stiff.

By placing support sticks between strategically chosen couples of vertices sharing a neighbor, the cloth algorithm can be extended to simulate plants. Again, in Hitman only one pass through the relaxation loop was enough (in fact, the low number gave the plants exactly the right amount of bending behavior).

The code and the equations covered in this section assume that all particles have identical mass. Of course, it is possible to model particles with different masses, the equations only get a little more complex.

To satisfy (C2) while respecting particle masses, use the following code:

// Pseudo-code to satisfy (C2)
delta = x2-x1;
deltalength = sqrt(delta*delta);
diff = (deltalength-restlength)/(deltalength*(invmass1+invmass2));
x1 -= invmass1*delta*diff;
x2 += invmass2*delta*diff;

Here invmass1 and invmass2 are the numerical inverses of the two masses. If we want a particle to be immovable, simply set invmass=0 for that particle (corresponding to an infinite mass). Of course in the above case, the square root can also be approximated for a speed-up.

continues on page 2 »


References

[Baraff]
Baraff, David, Dynamic Simulation of Non-Penetrating Rigid Bodies, Ph.D. thesis, Dept. of Computer Science, Cornell University, 1992.
http://www.cs.cmu.edu/~baraff/papers/index.html

[Mirtich]
Mirtich, Brian V., Impulse-base Dynamic Simulation of Rigid Body Systems, Ph.D. thesis, University of California at Berkeley, 1996.
http://www.merl.com/people/mirtich/papers/thesis/thesis.html

[Press]
Press, William H. et al, Numerical Recipes, Cambridge University Press, 1993.
http://www.nr.com/nronline_switcher.html

[Stewart]
Stewart, D. E., and J. C. Trinkle, “An Implicit Time-Stepping Scheme for Rigid Body Dynamics with Inelastic Collisions and Coulomb Friction”, International Journal of Numerical Methods in Engineering, to appear.
http://www.cs.tamu.edu/faculty/trink/Papers/ijnmeStewTrink.ps

[Verlet]
Verlet, L. "Computer experiments on classical fluids. I. Thermodynamical properties of Lennard-Jones molecules", Phys. Rev., 159, 98-103 (1967).

[Witkin]
Witkin, Andrew and David Baraff, Physically Based Modeling: Principles and Practice, Siggraph ’97 course notes, 1997.
http://www.cs.cmu.edu/~baraff/sigcourse/index.html

     
 
 
Name: Thomas Jakobsen
Location: Copenhagen, Denmark
Age: N/A
Flash experience: N/A
Job: Thomas Jakobsen used to be head of research at IO Interactive, where developed new technology for the in-house engine, Glacier. He created the physics simulation and the 3D pathfinder for IO's Hitman: Codename 47. Jakobsen earned his M.Sc. in engineering from The Technical University of Denmark, where he also obtained his Ph.D. in mathematics. He spent a number of years in academia and has published several scientific articles on cryptanalysis. Thomas Jakobsen now works at an investment bank applying his number crunching skills to financial data.
Website: http://www.teknikus.dk/tj
 
 
| Homepage | News | Games | Articles | Multiplayer Central | Reviews | Spotlight | Forums | Info | Links | Contact us | Advertise | Credits |

| www.smartfoxserver.com | www.gotoandplay.biz | www.openspace-engine.com |

gotoAndPlay() v 3.0.0 -- (c)2003-2008 gotoAndPlay() Team -- P.IVA 03121770048