Solver Comparison#
This page summarizes the user-visible behavioural differences between the solvers shipped with the Isaac Lab physical backends. It’s intended as a porting reference: most tasks reuse the same USD asset across backends, but contact, friction, and stabilization behave differently enough that retuning is usually required when moving from one solver to another.
The solvers covered are:
PhysX TGS — default solver for the PhysX backend (Temporal Gauss-Seidel). PhysX also exposes a Projective Gauss-Seidel (PGS) variant via
solver_type, which behaves similarly for the purposes of this comparison.Newton MuJoCo-Warp (MJWarp) — primary Newton solver, configured by
MJWarpSolverCfg.Newton Kamino — beta P-ADMM Newton solver, configured by
KaminoSolverCfg.
Newton additionally ships FeatherstoneSolverCfg and XPBDSolverCfg;
neither is wired into an Isaac Lab task at the time of writing and they
are omitted from this comparison.
Friction Model#
Solver |
Friction handling |
|---|---|
PhysX TGS |
Coulomb friction with patch-based anchors. Tangential forces are
merged across nearby contacts via
|
MJWarp |
MuJoCo’s friction model. The friction cone shape is selectable via
|
Kamino |
Per-contact friction resolved inside the P-ADMM solve. Contact
warm-starting is selectable via
|
Porting implication. Tasks tuned for PhysX’s patch friction can feel
“grippier” than MJWarp’s per-contact friction at the same friction
coefficient. When moving a manipulation task from PhysX to MJWarp, expect to
raise friction coefficients and consider switching cone to "elliptic"
for stiffer contact stacks.
Contact Detection and Resolution#
Solver |
Collision pipeline |
|---|---|
PhysX TGS |
PhysX’s built-in broadphase + narrowphase, with optional continuous
collision detection via
|
MJWarp |
Two modes selected by
|
Kamino |
Optionally uses Kamino’s internal collision detector ( |
Porting implication. A task that runs with --enable_ccd on PhysX
won’t get the same protection on MJWarp/Kamino at large dt — Newton’s
CCD is convex GJK/EPA, not the swept-shape CCD PhysX uses. The mitigation
on Newton is shorter dt or higher
num_substeps.
Restitution and Bounce#
Solver |
Restitution |
|---|---|
PhysX TGS |
Restitution coefficient is per-material on the USD shape. A global
velocity threshold
|
MJWarp |
Restitution follows the MJCF model translated from USD. There is no bounce-threshold gate — small-velocity contacts can still bounce unless you reduce the per-material restitution. |
Kamino |
Restitution is contained in the contact constraint set; behaviour is similar to MJWarp. |
Porting implication. Tasks that rely on PhysX’s bounce-threshold to suppress jitter (e.g. footstep contact on flat ground) may show contact chatter on Newton until restitution coefficients are reduced.
Constraint Stabilization#
Solver |
Stabilization |
|---|---|
PhysX TGS |
Implicit, via the TGS solver. An optional extra pass is enabled by
|
MJWarp |
Implicit, set by the MuJoCo solver’s |
Kamino |
Explicit Baumgarte stabilization with separate gains for joint
bilaterals ( |
Solver Convergence#
Solver |
Iteration model |
|---|---|
PhysX TGS |
Two iteration counts, per actor: position
( |
MJWarp |
|
Kamino |
P-ADMM with separate
|
Articulation Coordinates#
Solver |
Coordinate representation |
|---|---|
PhysX TGS |
Reduced-coordinate articulations (joint-space, Featherstone-like). Joint state is the canonical truth; body transforms are derived via forward kinematics. |
MJWarp |
Reduced-coordinate, computed by the MuJoCo solver. |
Kamino |
Maximal-coordinate: each body has its own free-body state,
constraints are enforced via Baumgarte stabilization. Resets go
through a dedicated FK pass ( |
Porting implication. Kamino is more sensitive to inconsistent reset state — joint positions and body poses must agree, which Isaac Lab’s asset write paths handle but custom reset code can break.
Substepping and Timestep#
Solver |
Substep model |
|---|---|
PhysX TGS |
PhysX runs at the simulation |
MJWarp |
Top-level |
Kamino |
Same |
GPU Buffers and Throughput#
Solver |
Memory model |
|---|---|
PhysX TGS |
Static GPU buffers sized at construction. Undersized buffers cause
crashes or dropped contacts at scale. See the
PhysX configuration page for the
|
MJWarp |
Pre-allocated per-environment limits:
|
Kamino |
Inherits MJWarp’s pre-allocation pattern via Newton, plus its own
contact-pair allocator
( |
Porting Checklist#
When moving a task between solvers:
Re-validate contact behavior. Run the task at the smallest
num_envswith a visualizer; watch for new penetration or jitter before scaling up.Retune friction. PhysX patch friction and MJWarp per-contact friction are not interchangeable at the same coefficient.
Retune restitution. MJWarp/Kamino have no bounce-threshold gate; reduce per-material restitution to suppress jitter.
Choose substeps. PhysX → Newton typically needs at least 1–2 substeps for contact-heavy tasks; manipulation tasks may need more.
Watch for CCD differences. Tasks that relied on PhysX swept CCD should either reduce
dtor raisenum_substepson Newton.For Kamino specifically, also validate reset behaviour and consider Baumgarte gains if you see drift on joint or contact constraints.