1  Contact Simulation

When simulating any kinds of physical systems in graphics we often have to deal with contact. Contact is the interaction between two objects that are in close proximity. The forces between these objects are called contact forces and they are there to prevent the objects from interpenetrating. There are 3 rough types of contact simulations: 1. constraint based methods, 2. penalty based methods, and 3. impulse based methods. We will focus on the first two.

1.1 Basics of Contact Simulation

Newton-Euler equations of motions that govern dynamics of physical systems as a 2nd order ODE is written as:

\[ M(t) \dot u(t) = f(q(t), u(t),t),\]

where \(M(t)\) is the mass matrix over time, \(u(t)\) is the velocity of the system, \(q(t)\) is the generalized position of the system, and \(f\) is the external forces acting on the system. The contact forces are a subset of these external forces. We can abbreviate the above equation as:

\[M\dot u = f,\]

and we evaluate it using numerical integrators that take discrete steps in time. In this section we denote explicit quantities with superscript \(\square^-\) and implicit quantities with \(\square^+\). In the implict setting the 1st order Taylor approximation gives:

\[u^+ \approx u + h \dot u,\] which when placed into the Newton-Euler equation gives gives the following Euler update:

\[ Mu^+ = Mu + h f.\]

Here \(Mu\) can be seen as the momentum term and \(u^+\) is the velocity determined at the end of the timestep. The form of \(M\) will depend on the type of representation we use for our body.

Now we can similiarly update the generalized positions:

\[q^+ = q + h \textbf{H} u^+,\]

where \(\textbf{H}\) is the kinematic matrix that maps velocities to positions.

Since most contant models are based on Coulomb model, we get limited performance boost from higher order methods, so we just we assume planar surface at the contact points.

1.1.1 Basics of Constraints

To restrict movement of bodies to some desired state we introduce kinematic constraints, specifically with \(m\) constraints functions we define the desired state as a manifold \(\phi(q) \in \mathbb{R}^m\) embeeded in \(\mathbb{R}^n\).

Assuming constraints are initially satisfied, we can formulate constraints in terms of how fast they change with respect to \(q\):

\[J = \frac{\partial \phi}{\partial q} \in \mathrm{R^{m \times n}}.\] We call \(J\) the constraint Jacobian / gradient. It encodes the direction in which bodies may be pushed or pulled without exerting any forces on the system while staying on the manifold. With this the bilateral and unilateral constraints can be written as:

\[J \dot u = 0,\] and \[J \dot u \geq 0,\] respectively. More generally the constraint forces are written as:

\[f_c = J^T \lambda,\]

where \(\lambda\) is the vector of Lagrange multipliers. The multipliers relate to the magnitudes of \(f_c\) when the gradients / directions are normalized. So \(J^\top\) tells the force direction and \(\lambda\) tells the magnitude. The constraint forces can be thought of as the forces that keep the system on the manifold.

To actually enforce that our system stays on the manifold we need to add the constraint forces to the external forces acting on the system in the form of an impulse:

\[M u^+ = M u + h f + h J^T \lambda^+,\] where the constraint forces are evaluated explicity. If we just consider bilateral constraint and write this as a linear system, then we can use Shur complement to reduce the system:

\[JM^{-1}J^\top J^\top (h \lambda^+) + JM^{-1} (Mu + hf) = 0\]

which is a linear system of the form \(A h \lambda^+ + b = 0.\)

1.1.1.1 Non-interpenetration Contact

Unilateral constraints are only active when the bodies are in contact. We model the distnace between two bodies with a gap function \(\phi\)—i.e. a constraint function that \(\phi = 0\) when the bodies are in contact, \(\phi > 0\) when bodes are separated, and \(\phi < 0\) when bodies are interpenetrating.

If we make the gross assumption that surfaces are smooth, then we can imagine a plane at the contact point and its normal vectors is parallel to surface normal. If the bodies are in contact, then an impulse \(\lambda_{\hat n}\) is applied at the contact location in the direction of \(\hat n\) (i.e. perpendicular to the contact plane).

As such we have 2 cases:

  1. No contact, No force. \(\phi > 0\) and \(\lambda_{\hat n} = 0\).

  2. Contact, Force applied. \(\phi \leq 0\) and \(\lambda_{\hat n} > 0\).

Since they are independent we can write them as one “position level non-penetration complementary condition”:

\[\phi \geq 0 \quad \bot \quad \lambda_{\hat n} \geq 0.\]

Since the contact is only when \(\phi =0\) we can again think about it in terms of velocities of bodies. In the implict setting, if bodies \(A,B\) are in contact at time \(t\), then if \(\dot \phi > 0\)—that is the normal component of relative velocity is positive—they will not be in contact at time \(t+h\) (note \(\phi^+ \approx \phi + h \dot \phi = h \dot \phi\)), so \(\lambda_{\hat n} = 0\). If \(\dot \phi \leq 0\)—that is they have negative or 0 relative velocity—then they will be in contact at time \(t+h\), so \(\lambda_{\hat n} > 0\). Combined we have the condition:

\[\dot \phi \geq 0 \quad \bot \quad \lambda_{\hat n} \geq 0.\]

We replace \(\dot \phi = v_{\hat n}\), since it is the relative velocity of the contact points in the normal direction. If we want to anticipate the collision and avoid tunneling effects we can replace \(\dot \phi\) with \(\phi + hv _{\hat n}\).

Non-interpretation Jacobian. The question now is how do we compute \(\dot \phi\)? We can use the chain rule to get:

\[\dot \phi = \frac{\partial \phi}{\partial q} \dot q = J \dot q = J \dot H u = J' u,\]

where \(J'\) body-space Jacobian of the gap function.

How do we construct \(J'\)? Let’s consider collision of two bodies \(A,B\) at contact point \(p\) and centes of mass \(m_A, m_B\) respectively. Defining \(\hat n\) to point \(A \rightarrow B\), then by taking \(r_A = p - x_A\) and \(r_B = p - x_B\) we can write: \[ % \begin{align} v_{\hat n} = \hat n^\top \delta v \] \[ v_{\hat n} = \hat n^\top ((v_B + \omega_B \times r_B) - (v_A + \omega_A \times r_A)), % \end{align} \]

where \(v_A, v_B\) are linear velocities of \(A,B\) and \(\omega_A, \omega_B\) are angular velocities of \(A,B\) respectively. Finally we see how to compute \(J'\):

\[v _{\hat n} = \begin{bmatrix}-\hat n^\top& \hat n r_A^\times & \hat n^\top & -\hat n^\top r^\times_B \end{bmatrix} \begin{bmatrix} v_A \\ \omega_A \\ v_B \\ \omega_B \end{bmatrix} = J' u.\]

To extend \(J'\) to multiple contacts, we would just place a new row for each contact point.

Soft-Bodies Non-interpenetration Constraints. This is very similar to the rigid body case we were considering. We usually use a mesh with nodes to represent a deforamble model.

Considering colliding tetrahedral elements of a mesh between \(A,B\) we can formulate the contact point using Barycentric coordinates:

\[p = w_i x_{i,B} + w_j x_{j,B}+ w_k x_{k,B} + w_m x_{m,B} = x_{l,A}.\]

The relative contact point velocity in the normal direction is then:

\[v_{\hat{n}} = \hat{n}^\top \left( \sum_{i=1}^4 w_{i,B} v_{i,B} - \sum_{i=1}^4 w_{i,A} v_{i,A} \right) \]

\[ v_{\hat n} = \begin{bmatrix} -\hat{n}^\top & w_i \hat{n}^\top & w_j \hat{n}^\top & w_k \hat{n}^\top & w_m \hat{n}^\top \end{bmatrix} \begin{bmatrix} v_{l,A} \\ v_{i,B} \\ v_{j,B} \\ v_{k,B} \\ v_{m,B} \end{bmatrix} = J' u.\]

1.1.2 Coulumnb Friction Model

So far we assume that tangential movement between contacts was allowed and not opposed. In graphics we often want to simulate friction as well. We can model friction as a force that opposes the relative tangential velocity of the contact points. We can model this as a force that is proportional to the normal force and the relative tangential velocity.

To describe this friction we think about a local contact frame for each contact point. The local frame is defined by the normal vector \(\hat n\) and two tangent vectors \(\hat t, \hat b\) that are orthogonal to \(\hat n\) and each other; \(\hat b, \hat t\) define the shared contact plane between the smooth surfaces.

\(\hat n\) can be defined from \(\partial \phi\). Since we are discussing this in the local frame, we need to have relative velocity of the two surfaces

\[v = [\hat n, \hat t, \hat b,]^\top \Delta v,\]

where \(\Delta v\) is the world-space relative velocity. We rewrite the context frame basis with \(C = [\hat n, \hat t, \hat b]\). Now recalling the equation for the relative world velocity we can write:

\[v = C^\top [- I_{3\times 3}, r^{\times}_A I_{3\times 3}, -r_B^{\times}] \begin{bmatrix}v_A \\ \omega_A \\ v_B \\ \omega_B\end{bmatrix} = Ju,\]

so \[J_f = C^\top [-I_{3\times 3}, r_A^{\times} I_{3\times 3}, -r_B^{\times}].\]

To refelct we recall that in the non-friction case we actually had \(J' = \hat n [-I_{3\times 3}, r_A^{\times} I_{3\times 3}, -r_B^{\times}]\) so we indeed got the friction Jacobian by just changing the normal vector to the contact frame basis!

We defined how we can compute the contact frame relative velocity, but to determine the impulses that separate objects and the friction forces between the objects, we need to separate \(v\) into normal \(v_{\hat n}\) and tangential \(v_{\hat t}\) components.

Theory of Friction. Since Column force couples the normal and tangential impulses, we restrict the tangential friction with a cone constraint. The cone constraint is defined by the friction coefficient \(\mu\) and the normal force \(\lambda_{\hat n} \in \mathrm{R}\):

\[\| \lambda_{\hat t} \| \leq \mu \lambda_{\hat n},\]

where \(\lambda_{\hat t} \in \mathrm{R^2}\). Each \(\mu \lambda_{\hat n}\) corresponds to some slice of the cone and that slice tells us all the possible tangential forces that can be applied given the normal force. The equation is quadratic so the cone is a quadratic cone.

We separate friction into 2 types: 1. slipping and 2. sticking. If the relative tangential velocity is less than the threshold, then the contact is sticking and the tangential friction force can have any direction. If the relative tangential velocity is greater than the threshold, then the contact is slipping and the tangential friction force is is opposing the movement and has magnitude \(\mu \lambda_{\hat n}\). We can write this as:

\[\mu \lambda_{\hat n} - \|\lambda_{\hat t}\| \geq 0, \] \[\|v_{\hat t}\| (\mu \lambda_{\hat n} - \|\lambda_{\hat t}\|) = 0,\] \[\|v_{\hat t}\| \|\lambda_{\hat t}\| = -v_{\hat t}^\top \lambda_{\hat t}.\]

The first condition is always active and tells us that the tangental impulse has to be in the quadratic cone. If \(\|v_{\hat t}\| > 0\) then the other two conditions activate: first tells us that \(\mu \lambda_{\hat n} = \|\lambda_{\hat t}\|\), i.e. the impulse must be maximized in the cone, the last condition says that the tangential friction impulse should oppose the relative tangential velocity. We call this a (non-linear) complementary problem.

To give more intuition on these conditions, we can think about the friciton force as maximally decreasing energy of a system. If we define \(\mathcal{F}\) to be the set of possible friction forces, then the principle of maximum dissipiation gives:

\[\lambda_{\hat t} = \arg \min_{f \in \mathcal{F}} v_{\hat t}^\top f.\] Following this setup we can arrive to the variational inequality (VI) and you can read more about it in [the notes].

1.1.2.1 LCP - Linear Complementary Problem

We saw that our friction model is non-linear and can be hard to solve efficiently. We can linearize the problem by creating a linear approximation of our friction cone. We call it a polyhedral cone and it is given by the span of \(k+1\) unit vectors \(\{\hat n, \hat t_1, \dots, \hat t_{k}\}\). Each tangent vector has a twin in the opposite direction, so we can write all friction forces with non-negative coefficients. This allows us to re-write the quadratic constraint above as:

\[0 \leq \mu\lambda_{\hat n} - \sum_i \lambda_{\hat t_i}.\]

To form the stick-slip conditions we only need to know whether we are slipping or not. For this we can measure the maximum slipping velocity along all of the tangential directions. Then for \(\beta \geq 0\):

\[ 0 \leq \beta \textbf e + \textbf v_{\hat t}\]

where \(\textbf e\) is the vector of all ones and \(\textbf v_{\hat t}\) is the relative tangential velocity along all directions. \(\beta\) is the maximum slipping velocity and can be 0 iff \(\textbf v_{\hat t} = 0\), i.e. we are sticking. Otherwise \(\beta = \max_{v \in \textbf v_{\hat t}} \|v\|\). We also sometimes call \(\beta\) the slack variable.

Again by principle of maximum dissipation we know that:

\[\beta > 0 \implies \sum_{i}\lambda_{\hat t_i} = \mu \lambda_{\hat n}.\] To get the right direction of the friction force we let \(\beta \textbf e = -\textbf v_{\hat t}\). Finally this gives a complete linear model for 1 contact point:

\[0 < v_{\hat n} \quad \bot \quad \lambda_n \geq 0\]

\[0 \leq \beta e + v_{\hat t} \quad \text{and} \quad \lambda_{\hat t} \geq 0\]

\[0 \leq \mu \lambda_{\hat n} - \sum_i \lambda_{\hat t_i} \quad \bot \quad\beta \geq 0.\]

\(p\) contact points. To generalize our system to multiple contact points we need to assemble a global Jacobian containing non-penetration and tangential friction constraints for all \(p\) contact points. For the non-penetration conditions each contact point we have a separate row:

\[J_{\hat n, i} = \begin{bmatrix} - \hat n_i^\top & \hat n_{i}^{\top} r_{i,A}^\times & \hat n_i^\top & - \hat n_i^\top r_{i,B}^\times\end{bmatrix},\] \[J_{\hat n} = \begin{bmatrix} J_{\hat n, 1}^\top \\ \vdots \\ J_{\hat n, p}^\top \end{bmatrix}.\]

For the friction Jacobian (tangential friction) we have a similar setup for all tangential directions:

\[J_{\hat t} = [J_{\hat t, 1}^\top, \dots, J_{\hat t, p}^\top],\] \[J_{\hat t,i} = \begin{bmatrix} - \hat t_i^\top & \hat t_{i}^{\top} r_{i,A}^\times & \hat t_i^\top & - \hat t_i^\top r_{i,B}^\times \\ \vdots & \vdots & \vdots & \vdots\end{bmatrix}\]

where \(J_{\hat t, i}\) is the Jacobian for the \(i\)-th contact point. The global Jacobian is then: \[ \begin{bmatrix} M & -J_{\hat{n}}^T & -J_{\hat{t}}^T & 0 \\ J_{\hat{n}} & 0 & 0 & 0 \\ J_{\hat{t}} & 0 & 0 & E \\ 0 & \bar{\mu} & -E^T & 0 \end{bmatrix} \begin{bmatrix} u^+ \\ \lambda_{\hat{n}}^+ \\ \lambda_{\hat{t}}^+ \\ \beta \end{bmatrix} + \begin{bmatrix} -Mu - hf \\ 0 \\ 0 \\ 0 \end{bmatrix} = \begin{bmatrix} 0 \\ s_n \\ s_\beta \\ s_\lambda \end{bmatrix} \]

subject to: \[0 \leq s_n \perp \lambda_{\hat{n}}^+ \geq 0 \] \[0 \leq s_\beta \perp \lambda_{\hat{t}}^+ \geq 0 \] \[0 \leq s_\lambda \perp \beta \geq 0 \]

With rearamnging we can get the LCP form:

\[ Ax + b \geq 0 \quad \bot \quad x \geq 0.\]

After all this gargol we see that it really boils down to a nice and simple linear system!

1.1.2.2 Boxed LCP

Another way to discretize the friction cone is by using only 2 orthogonal tangent directions and have them limited:

\[-\mu \lambda_{\hat n} \leq \lambda_{\hat t_i} \leq \mu \lambda_{\hat n}\] for \(i\in \{1,2\}.\)

Note that to solve these discretizations we need more general algorithms than LCP solvers. One nice benefit we get from writing our system this way is that we can run away from the whole mess of having different constraints for friction and non-penetration and just use the same algebraic expression (with different bounds) for both! Concretely, we can write:

\[v_i > 0 \implies \lambda_i = -\mu \lambda_{\hat n} \] \[v_i = 0 \implies \lambda_i \in [-\mu \lambda_{\hat n}, \mu \lambda_{\hat n}] \] \[v_i < 0 \implies \lambda_i = \mu \lambda_{\hat n}\]

We can further decompose the residual velocity as \(v_i = v_{i,+} - v_{i,-}\) and write BLCP as 3 separate LCPs:

\[ 0 \leq v_{i,+} \perp \lambda_i + \mu \lambda_{\hat n} \geq 0\] \[ 0 \leq v_{i,-} \perp \lambda_i - \mu \lambda_{\hat n} \geq 0\] \[ 0\leq v_{i,-} \perp v_{i,+} \geq 0.\]

To assmble the global Jacobian we recall the Jacobian for a single contact as:

\[J_i = C^\top [-I_{3\times 3}, r_A^{\times} I_{3\times 3}, -r_B^{\times}]\]

where we now replace \(C^\top\) with \([\hat n, \hat t_1, \hat t_2]\). Then the global Jacobian becomes: \(J = [J_1, \dots, J_p]^\top\) and the global BLCP for the constrainted equations of motion becomes:

\[ \underbrace{ \begin{bmatrix} M & -J^T \\ J & 0 \end{bmatrix} }_{\text{A}} \begin{bmatrix} u^+ \\ \lambda^+ \end{bmatrix} + \underbrace{ \begin{bmatrix} -Mu - hf \\ 0 \end{bmatrix} }_{\text{b}} = \begin{bmatrix} 0 \\ v \end{bmatrix}, \]

\[ 0 \leq {}^+v \perp \lambda^+ - \lambda^{\text{lo}} \geq 0, \] \[ 0 \leq {}^-v \perp \lambda^{\text{hi}} - \lambda^+ \geq 0, \] \[ 0 \leq {}^-v \perp {}^+v \geq 0\]

where \(\lambda = [\lambda_{\hat n_1}, \lambda_{\hat t_{1,1}}, \lambda_{\hat t_{1,2}}, \dots]^\top.\) We could again use Shur complement to reduce the system to a smaller one and you can see that in [the notes].

Numerical stabilization. Add springs, because we have numerical drift in linear approximation.

1.1.2.3 Deformable Contact

While most of the friction contact formulations above were derived from a rigid-body setting, we can extend them to deformable bodies too. The main differneces are that there are more variables and we use implicit discretization approaches in deformable objects.

If we first consider the \(k^{th}\) contact between 2 rigid bodies, we can write the relative contact point velocity as:

\[ \begin{bmatrix} v_{\hat{n}_k} \\ v_{\hat{i}_k} \\ v_{\hat{b}_k} \\ v_{\hat{r}_k} \end{bmatrix} = \begin{bmatrix} -\mathbf{C}_k^T & -(\mathbf{r}_{k_i} \times \mathbf{C}_k)^T & \mathbf{C}_k^T & (\mathbf{r}_{k_j} \times \mathbf{C}_k)^T \\ \mathbf{0}^T & -\hat{\mathbf{n}}_k^T & \mathbf{0}^T & \hat{\mathbf{n}}_k^T \end{bmatrix} \begin{bmatrix} \mathbf{v}_i \\ \boldsymbol{\omega}_i \\ \mathbf{v}_j \\ \boldsymbol{\omega}_j \end{bmatrix}. \]

Most often we pick \(\hat t_k\) to be the direction of sliding and \(\hat b_k\) to be orthogonal to \(\hat n_k, \hat t_k\). We can combine all \(K\) contacts and \(N\) bodes into one big system of the familiar form:

\[\textbf v = \textbf J \textbf u.\] Finally we write the block \(M\) matrix, the external forces \(f\), and the generalized coordinates \(q_i = [x_i^\top \quad Q_i^\top]^\top\). Since we incorporate quaternions we have to change \(\dot q = u\) using a kinematic matrix \(\textbf H\) (refer to the notes for the exact form). Then \(q^+ = q + h \textbf H u^+\) and \(M u^+ = M u + h f\), as we have seen before.

To change this to a deformable body we need to add elastic forces. Recall that applying FEM on a deformable body results in a second order differential equation:

\[ M \ddot q + B \dot q + K u = f+ J^\top \lambda\]

where \(q\) is all the nodes in the mesh, \(K\) is the stiffnes matrix, \(B\) is the damping matrix, and \(J^\top \lambda\) is the contact forces. Observe that we do not have any quaternions or angualr spin present anymore. Using Euler integration and finite differences we get:

\[\dot u^+ \approx u + h\dot u \]

where \(u^+ = u^{t+h}, u=u^t\). Integrating genearlized poisitions we get:

\[q^+ = q + h u^+.\] Note: no \(\textbf H\), because we are not dealing with quaternion rotations anymore. Now we can write a velocity level dynamic equation for this system:

\[M \left(\frac{u^+ - u}{h}\right) + K (q^+ - q_0) +B u^+ = f + J^\top \lambda\] or equivalently in the impulse form:

\[ M u^+ + hBu^+ + h^2Ku^+ = Mu + hf - hKq^+ + hKq_0 + J^\top h\lambda, \] \[ A u^+ = b + J^\top h\lambda.\]

Here \(A\) is sparse, block-symmetric, and positive definite. That’s every numerical analysit wet dream. We can now easily solve the system using Conjugate Gradients or any other iterative solver to get \(u^+\), then \(q^+\), and repeat.

Note: Deformable objects make numerics easier compared to rigid bodies.

1.2 Contact Generation

We talked about how to simulate contact, but we did not talk about how to generate it, based on the representation of the objects. We will focus on the most common representation: tetrahedral meshes. First we define some terms: the contact position / point will be denoted as \(p\) w.r.t points \(p_A,p_B\) on the surfaces of objects \(A,B\). At the exact time of contact they obey \(p = p_A = p_B\), but since we are doing discreitzation in time, this is not guaranteed to happen. That said, we will still apply forces at \(p_A, p_B\). We will define for simplicty the contact normal \(\hat n\) to be the normal of the surface at \(p_A\). Again, note that \(\hat{n_A}\) might not be equal to \(\hat{n_B}\) if the surfaces are non-smooth. We also introduce a measure of penetration \(\phi\) (same convention as the gap function); it tells how much we have to move along \(\hat n\) to get to \(p = p_A = p_B\).

When dealing with mesh-based collisions, we recognize 2 types of collisions: 1. vertex-face \((V,E)\) and 2. edge-edge \((E,E)\). Since we are timestepping, we should expect to the detect the collision when the objects are interpenetrating.

Continuous Collisoin Detection (CCD). Rather then trying to reason about when a collision will happen in our descretized setting, we can think about it in a continuous setting. CCD processes all the possible collisions that might occur from \(t_{now}\) to \(t_{later}\) (e.g. \(t\) to \(t+h\)). To do so we can either look forward in time and look for the time when a collision will happen or look backward in time and find a time just before the collision happend. We can pefrorm CCD with a course-to-fine approach to speed it up.

To prevent collisions we can either set a large enough time-step based on CCD or we can warp points to the start of the timestep based on the computed normal.

To compute a \(t\) and \(p\) at the contact we will make the assumption that when \(h \approx 0\), then motion between time-steps can be considered linear, while the error increases with \(\mathcal{O}(h)\). We can “sweep” a triangle over the time-step to get the “swept-volume.” We can then compute the time of collision by finding the intersection of the swept-volume with the other object. Using the forward prediction approach we get candidate positions at the next timestep for one of the triangles as:

\[x_i' = x_0 + h u_i\] for \(i\in \{0,1,2\}\). For the backward formulatoin we get:

\[x_i' = x_i - hu_i.\] In fact for the backward formulation we already have the exact candidates for the previous timestep. We can instaed compute linear velocity as \(u_i = \frac{x_i - x_i'}{h}.\) Using bounding boxes around previous and next timestpe we can see whether there might exist a collision or not.

CCD for \((V,F)\) contact. The idea is to use 3 nodes \(\{x_1,x_2,x_3\}\) from one triangle to get the surface normal \(\hat p_n\) and another node to check whether it is in the plane of \(\hat p_n\). First we get \(\hat p_n = (x_2 - x_1)\times (x_3 - x_1)\). Distance to the origina is \(\hat p_n^\top x_1\).

For a new point \(x_4\) to lie in the triangle we need:

\[\hat p_n ^\top x_4 - d = 0,\] \[((x_2 - x_1)\times (x_3 - x_1))^\top (x_4 - x_1) = 0.\] Now introducing time-dependence and linear motion equations from beofre into the test we get:

\[(((x_2 - x_1) + (u_2 - u_1)t)\times ((x_3 - x_1) + (u_3-u_1)t))^\top ((x_4 - x_1) + (u_4 -u_1)t) = 0\]

and we want to determine the minmial non-negative such \(t< h\) s.t. the above is true. This is a \(P^3\) polynomial so we can find these values using a root-finding algorithms. This gives the point of contact \(p = x_4 + u_4 t\).

CCD for \((E,E)\) contact. We can use the same approach as above, but we need to consider the edges as well. We must check if the edges are parallel:

\[(x_2 - x_1 )\ times (x_4 - x_3) \leq \varepsilon .\] If this is a case we can project vertices on the line through the other edge and check for intersection.

When the two edges are not parallel—possibly touching at only 1 point—then we can reparametrize the edges as line equations:

\[E_1: x_1 + \alpha (x_2 -x_1),\] \[E_2: x_3 + \beta (x_4 - x_3).\]

Then the contact point must also be the closest point between these two lines:

\[a,b, \arg\min_{a,b \in[0,1] }\|x_1 + \alpha (x_2 -x_1) - (x_3 + \beta (x_4 - x_3))\|_2.\]

From preschool we know that we can solve this in the normal equations form:

\[\begin{bmatrix} (x_2 - x_1)^\top (x_2 - x_1) & -(x_2 - x_1)^\top (x_4 - x_3) \\ -(x_2 - x_1)^\top (x_4 - x_3) & (x_4 - x_3)^\top (x_4 - x_3) \end{bmatrix} \begin{bmatrix} \alpha \\ \beta \end{bmatrix} = \begin{bmatrix} (x_2 - x_1)^\top (x_3 -x_1)\\ -(x_4 -x_3)^\top (x_3 -x_1)\end{bmatrix}.\]

The \((\alpha,\beta)\) solutions give the candidate closest point. If \(\alpha,\beta \in [0,1]\) we can simply write the point as:

\[p = (x_1 -x_3) + \alpha (x_2 -x_1) - \beta (x_4 -x_3).\]

If we really want to get sweaty, we can write this using Barycentric coordinates:

\[((1- i - v) x_1(t) + ux_2(t) + vx_3(t)) - x_4(t))) = 0\] where \(t\in[0,1]\) and \(u,v\) are Barycentric coordinates for the traingle.

1.3 Deformable Bodies

1.4 Barrier Methods