Constraints¶
In the Axion physics engine, constraints are the set of mathematical rules that govern how rigid and deformable bodies interact. The engine is a direct implementation of the unified constraint framework presented in "Non-Smooth Newton Methods for Deformable Multi-Body Dynamics" (Macklin et al. 2019). This approach formulates all physical laws—including collision response, joints, and friction—as a single large-scale Differential Variational Inequality (DVI). After time discretization, this DVI becomes a root-finding problem that is solved directly with a non-smooth Newton method, which is the key to the engine's stability, accuracy, and performance.
1. The Unified Constraint Formulation¶
At its core, the framework presented by Macklin et al. 2019 formulates the entire dynamics problem as a single system of non-smooth equations. At each time step, the solver's primary task is to find a set of constraint impulses (forces), denoted by the vector \( \boldsymbol{\lambda} \), that satisfy the dynamics of all interacting bodies simultaneously.
Unilateral and Bilateral Constraints¶
Constraints in Axion are primarily of two types:
-
Unilateral (Inequality) Constraints: These are one-sided conditions, such as the non-penetration rule for contacts. They are modeled using a Nonlinear Complementarity Problem (NCP). For a single contact, this is written as:
\[ 0 \le \lambda_n \perp c_n(q) \ge 0 \quad \quad (1) \]This elegant expression captures two fundamental rules:
- The quantities must be non-negative: The contact impulse \( \lambda_n \) must be repulsive (or zero), and the gap distance \( c_n(q) \) must be non-negative (no penetration).
- They are complementary: If there is a gap (\( c_n(q) > 0 \)), the contact impulse must be zero (\( \lambda_n = 0 \)). Conversely, if there is a contact impulse (\( \lambda_n > 0 \)), there must be no gap (\( c_n(q) = 0 \)).
-
Bilateral (Equality) Constraints: These are conditions that must be met exactly, such as maintaining a specific distance between two points in a joint. They are written as an equation:
\[ \mathbf{g}(q) = \mathbf{0} \quad \quad (2) \]
To solve this mixed system of equalities and inequalities, Axion transforms the complementarity conditions into a set of non-smooth equations using the Fischer-Burmeister function, as detailed in the paper. This allows the entire problem to be solved robustly using a Non-Smooth Newton method.
The Unified Dynamics Equation¶
All constraint forces are aggregated and integrated into the main equations of motion. For the entire system, this can be expressed as:
Where:
- \( \mathbf{M} \) is the system's generalized mass matrix.
- \( \mathbf{u} \) is the vector of generalized velocities.
- \( \mathbf{f}_{\text{ext}} \) represents all external forces (e.g., gravity, control inputs).
- \( \mathbf{J} \) is the constraint Jacobian, a matrix that maps body velocities to constraint-relative velocities.
- \( \boldsymbol{\lambda} \) is the composite vector of all constraint impulses (contact, friction, joint) that we are solving for.
2. Contact Constraints¶
Contact constraints are unilateral constraints that prevent bodies from interpenetrating. The key advantage of the method described by Macklin et al. 2019 is its ability to solve for these constraints without drift or the need for artificial stabilization.
Mathematical Model¶
The primary contact constraint enforces the complementarity condition from Eq. (1). Unlike traditional methods that can accumulate positional errors over time (drift), Axion uses an implicit time-stepping scheme that solves the position-level constraints directly. This completely avoids the need for ad-hoc stabilization techniques like Baumgarte stabilization. The non-smooth Newton solver finds the exact impulses required to prevent penetration at the end of the time step, resulting in a visually stable and robust simulation.
Though the core model handles inelastic impacts, material properties like "bounciness" can be modeled by setting a restitution
coefficient.
Code Representation¶
These constraints are generated by the collision detection system and stored in the ContactInteraction
struct.
@wp.struct
class ContactInteraction:
body_a_idx: int # Index of the first body
body_b_idx: int # Index of the second body
penetration_depth: float # Overlap distance (positive if penetrating)
restitution_coeff: float # Bounciness (0..1)
basis_a: ContactBasis # Contact frame (normal/tangents) for body A
basis_b: ContactBasis # Contact frame for body B
is_active: bool # Whether contact is being processed this step
3. Friction Constraints¶
Friction constraints apply tangential forces that resist sliding motion. The engine uses the smooth, isotropic Coulomb friction model derived from the principle of maximal dissipation, a cornerstone of the Macklin et al. 2019 paper.
Mathematical Model¶
The principle of maximal dissipation states that the friction force \( \boldsymbol{\lambda}_t \) will remove the maximum amount of kinetic energy from the system, subject to the Coulomb constraint that its magnitude is limited by the normal force \( \lambda_n \) and the coefficient of friction \( \mu \):
The Karush-Kuhn-Tucker (KKT) conditions for this model precisely describe the stick-slip behavior:
- Sliding: If there is relative tangential velocity (\( \mathbf{v}_t \neq \mathbf{0} \)), the friction force opposes it at maximum magnitude: \( \boldsymbol{\lambda}_t = -\mu \lambda_n \frac{\mathbf{v}_t}{\|\mathbf{v}_t\|} \).
- Sticking: If there is no relative tangential velocity (\( \mathbf{v}_t = \mathbf{0} \)), the friction force is whatever is necessary to prevent motion, up to the maximum limit: \( \| \boldsymbol{\lambda}_t \| \le \mu \lambda_n \).
The paper shows how to formulate these conditions using an NCP-function and a fixed-point iteration, which recasts the friction model into a symmetric system that fits seamlessly into the non-smooth Newton solver.
Code Implementation¶
The friction forces are computed in the 2D tangent plane defined by the contact normal. This plane is constructed using the ContactBasis
struct, which corresponds to the basis D
in the paper's maximal dissipation formulation.
@wp.struct
class ContactBasis:
normal: wp.spatial_vector # Direction of the contact force
tangent1: wp.spatial_vector # First direction for friction force
tangent2: wp.spatial_vector # Second direction for friction force
4. Joint Constraints¶
Joints connect bodies and restrict their relative motion. In Axion, joints are implemented using the same unified constraint framework as contacts and friction, as described in "Non-Smooth Newton Methods for Deformable Multi-Body Dynamics" (Macklin et al. 2019). The engine employs a constraints-based (or full-coordinate) approach, where each rigid body retains its full 6 degrees of freedom (DOFs), and the solver computes the exact joint impulses required to enforce the desired motion restriction.
Currently, the primary joint type implemented in Axion is the Revolute Joint.
Mathematical Model¶
A revolute joint, or hinge, constrains two bodies to rotate around a single common axis, removing five of the six relative DOFs. These restrictions are modeled as a set of five simultaneous bilateral (equality) constraints.
Specifically, the constraints ensure that:
-
The anchor points on both bodies coincide. This removes all three translational DOFs and can be expressed as a vector equation where the world-space positions of the parent's anchor point \(\mathbf{p}_{\text{parent}}\) and the child's anchor point \(\mathbf{p}_{\text{child}}\) must be equal:
\[ \mathbf{g}_{\text{trans}}(q) = \mathbf{p}_{\text{child}} - \mathbf{p}_{\text{parent}} = \mathbf{0} \] -
The hinge axes on both bodies remain collinear. This removes two rotational DOFs, leaving only the single, free rotation around the designated axis.
The solver finds the joint impulses \(\boldsymbol{\lambda}_j\) required to enforce these five conditions. A key benefit of the implicit formulation used in Axion is that any numerical drift that might cause the joint to separate or misalign is corrected automatically by the non-smooth Newton solver. This provides excellent stability without the need for ad-hoc stabilization terms (like Baumgarte stabilization).
Code Representation¶
The Revolute
joint is the primary articulation model available. It constrains relative motion as follows:
- Joint Type:
Revolute
(Hinge) - Free DOFs: 1 (Rotation around the specified joint axis)
- Constrained DOFs: 5 (3 translational, 2 rotational)
Tuning Constraint Behavior¶
Fine-grained control over the constraint solver is available in the EngineConfig
.