Skip to content

Commit 85dffc5

Browse files
Add cross-backend solver comparison page
New page physical-backends/solver-comparison.rst surfaces the user-visible behavioural differences between PhysX TGS, Newton MJWarp, and Newton Kamino. Most tasks share USD assets across backends, but friction model, contact resolution, restitution gating, constraint stabilization, CCD, and substepping all diverge enough that retuning is expected when porting. The page is organized as side-by-side tables per topic (friction, contact pipeline, restitution, stabilization, convergence, articulation coordinates, substepping, GPU buffers) plus a porting checklist for when moving a task across solvers. Each table cell references the concrete config attribute that controls the behavior, so readers can jump directly to the relevant tuning knob. Featherstone and XPBD Newton solvers exist in source/isaaclab_newton but are not yet wired into any Isaac Lab task; the page calls that out and omits them from the comparison. Linked from the physical-backends hub toctree.
1 parent 7087403 commit 85dffc5

2 files changed

Lines changed: 280 additions & 0 deletions

File tree

docs/source/overview/core-concepts/physical-backends/index.rst

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -17,6 +17,7 @@ backend-specific configuration, installation, and limitations.
1717
physx/index
1818
newton/index
1919
ovphysx/index
20+
solver-comparison
2021

2122

2223
Choosing a Backend
Lines changed: 279 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,279 @@
1+
Solver Comparison
2+
=================
3+
4+
This page summarizes the user-visible behavioural differences between the
5+
solvers shipped with the Isaac Lab physical backends. It's intended as a
6+
porting reference: most tasks reuse the same USD asset across backends, but
7+
contact, friction, and stabilization behave differently enough that retuning
8+
is usually required when moving from one solver to another.
9+
10+
The solvers covered are:
11+
12+
* **PhysX TGS** — default solver for the :doc:`PhysX backend <physx/index>`
13+
(Temporal Gauss-Seidel). PhysX also exposes a Projective Gauss-Seidel
14+
(PGS) variant via :attr:`~isaaclab_physx.physics.PhysxCfg.solver_type`,
15+
which behaves similarly for the purposes of this comparison.
16+
* **Newton MuJoCo-Warp (MJWarp)** — primary :doc:`Newton solver <newton/mjwarp-solver>`,
17+
configured by :class:`~isaaclab_newton.physics.MJWarpSolverCfg`.
18+
* **Newton Kamino** — beta P-ADMM :doc:`Newton solver <newton/kamino-solver>`,
19+
configured by :class:`~isaaclab_newton.physics.KaminoSolverCfg`.
20+
21+
Newton additionally ships ``FeatherstoneSolverCfg`` and ``XPBDSolverCfg``;
22+
neither is wired into an Isaac Lab task at the time of writing and they
23+
are omitted from this comparison.
24+
25+
26+
Friction Model
27+
--------------
28+
29+
.. list-table::
30+
:header-rows: 1
31+
:widths: 25 75
32+
33+
* - Solver
34+
- Friction handling
35+
* - PhysX TGS
36+
- Coulomb friction with **patch-based** anchors. Tangential forces are
37+
merged across nearby contacts via
38+
:attr:`~isaaclab_physx.physics.PhysxCfg.friction_correlation_distance`
39+
and applied above
40+
:attr:`~isaaclab_physx.physics.PhysxCfg.friction_offset_threshold`.
41+
The friction cone is always pyramidal.
42+
* - MJWarp
43+
- MuJoCo's friction model. The friction cone shape is selectable via
44+
:attr:`~isaaclab_newton.physics.MJWarpSolverCfg.cone`
45+
(``"pyramidal"`` or ``"elliptic"``). The tangential-to-normal
46+
impedance ratio is exposed as
47+
:attr:`~isaaclab_newton.physics.MJWarpSolverCfg.impratio`.
48+
* - Kamino
49+
- Per-contact friction resolved inside the P-ADMM solve. Contact
50+
warm-starting is selectable via
51+
:attr:`~isaaclab_newton.physics.KaminoSolverCfg.padmm_contact_warmstart_method`;
52+
the validated presets use ``"geom_pair_net_force"``.
53+
54+
**Porting implication.** Tasks tuned for PhysX's patch friction can feel
55+
"grippier" than MJWarp's per-contact friction at the same friction
56+
coefficient. When moving a manipulation task from PhysX to MJWarp, expect to
57+
raise friction coefficients and consider switching ``cone`` to ``"elliptic"``
58+
for stiffer contact stacks.
59+
60+
61+
Contact Detection and Resolution
62+
--------------------------------
63+
64+
.. list-table::
65+
:header-rows: 1
66+
:widths: 25 75
67+
68+
* - Solver
69+
- Collision pipeline
70+
* - PhysX TGS
71+
- PhysX's built-in broadphase + narrowphase, with optional continuous
72+
collision detection via
73+
:attr:`~isaaclab_physx.physics.PhysxCfg.enable_ccd`. Pre-sized GPU
74+
buffers (``gpu_max_rigid_contact_count`` etc.) cap the number of
75+
contacts per step; oversubscription is a hard error.
76+
* - MJWarp
77+
- Two modes selected by
78+
:attr:`~isaaclab_newton.physics.MJWarpSolverCfg.use_mujoco_contacts`:
79+
MuJoCo's internal contact pipeline (default) or Newton's
80+
:class:`~isaaclab_newton.physics.NewtonCollisionPipelineCfg`. The two
81+
are mutually exclusive. GJK/EPA iteration count is exposed via
82+
:attr:`~isaaclab_newton.physics.MJWarpSolverCfg.ccd_iterations`.
83+
* - Kamino
84+
- Optionally uses Kamino's internal collision detector (``"primitive"``
85+
or ``"unified"``) via
86+
:attr:`~isaaclab_newton.physics.KaminoSolverCfg.use_collision_detector`,
87+
otherwise falls back to Newton's :class:`CollisionPipeline`.
88+
Contact penetration margin is set by
89+
:attr:`~isaaclab_newton.physics.KaminoSolverCfg.constraints_delta`.
90+
91+
**Porting implication.** A task that runs with ``--enable_ccd`` on PhysX
92+
won't get the same protection on MJWarp/Kamino at large ``dt`` — Newton's
93+
CCD is convex GJK/EPA, not the swept-shape CCD PhysX uses. The mitigation
94+
on Newton is shorter ``dt`` or higher
95+
:attr:`~isaaclab_newton.physics.NewtonCfg.num_substeps`.
96+
97+
98+
Restitution and Bounce
99+
----------------------
100+
101+
.. list-table::
102+
:header-rows: 1
103+
:widths: 25 75
104+
105+
* - Solver
106+
- Restitution
107+
* - PhysX TGS
108+
- Restitution coefficient is per-material on the USD shape. A global
109+
velocity threshold
110+
:attr:`~isaaclab_physx.physics.PhysxCfg.bounce_threshold_velocity`
111+
suppresses restitution below ~0.5 m/s by default.
112+
* - MJWarp
113+
- Restitution follows the MJCF model translated from USD. There is no
114+
bounce-threshold gate — small-velocity contacts can still bounce
115+
unless you reduce the per-material restitution.
116+
* - Kamino
117+
- Restitution is contained in the contact constraint set; behaviour is
118+
similar to MJWarp.
119+
120+
**Porting implication.** Tasks that rely on PhysX's bounce-threshold to
121+
suppress jitter (e.g. footstep contact on flat ground) may show contact
122+
chatter on Newton until restitution coefficients are reduced.
123+
124+
125+
Constraint Stabilization
126+
------------------------
127+
128+
.. list-table::
129+
:header-rows: 1
130+
:widths: 25 75
131+
132+
* - Solver
133+
- Stabilization
134+
* - PhysX TGS
135+
- Implicit, via the TGS solver. An optional extra pass is enabled by
136+
:attr:`~isaaclab_physx.physics.PhysxCfg.enable_stabilization` (note:
137+
corrupts contact-sensor force magnitudes).
138+
* - MJWarp
139+
- Implicit, set by the MuJoCo solver's ``solref``/``solimp`` per
140+
constraint. No top-level toggle.
141+
* - Kamino
142+
- Explicit Baumgarte stabilization with separate gains for joint
143+
bilaterals (:attr:`~isaaclab_newton.physics.KaminoSolverCfg.constraints_alpha`),
144+
joint-limit unilaterals
145+
(:attr:`~isaaclab_newton.physics.KaminoSolverCfg.constraints_beta`),
146+
and contact unilaterals
147+
(:attr:`~isaaclab_newton.physics.KaminoSolverCfg.constraints_gamma`).
148+
149+
150+
Solver Convergence
151+
------------------
152+
153+
.. list-table::
154+
:header-rows: 1
155+
:widths: 25 75
156+
157+
* - Solver
158+
- Iteration model
159+
* - PhysX TGS
160+
- Two iteration counts, per actor: position
161+
(``min/max_position_iteration_count``) and velocity
162+
(``min/max_velocity_iteration_count``). The solver takes the largest
163+
actor's count clamped to the scene range. No global convergence
164+
tolerance.
165+
* - MJWarp
166+
- :attr:`~isaaclab_newton.physics.MJWarpSolverCfg.iterations` outer
167+
Newton/CG iterations and
168+
:attr:`~isaaclab_newton.physics.MJWarpSolverCfg.ls_iterations` line
169+
searches per outer iteration. Convergence gate:
170+
:attr:`~isaaclab_newton.physics.MJWarpSolverCfg.tolerance` (default
171+
``1e-6``).
172+
:attr:`~isaaclab_newton.physics.MJWarpSolverCfg.ls_parallel` switches
173+
line search to parallel execution at a small accuracy cost.
174+
* - Kamino
175+
- P-ADMM with separate
176+
:attr:`~isaaclab_newton.physics.KaminoSolverCfg.padmm_primal_tolerance`,
177+
:attr:`~isaaclab_newton.physics.KaminoSolverCfg.padmm_dual_tolerance`,
178+
and
179+
:attr:`~isaaclab_newton.physics.KaminoSolverCfg.padmm_compl_tolerance`
180+
gates, capped at
181+
:attr:`~isaaclab_newton.physics.KaminoSolverCfg.padmm_max_iterations`.
182+
Acceleration and warm-starting are tunable.
183+
184+
185+
Articulation Coordinates
186+
------------------------
187+
188+
.. list-table::
189+
:header-rows: 1
190+
:widths: 25 75
191+
192+
* - Solver
193+
- Coordinate representation
194+
* - PhysX TGS
195+
- **Reduced-coordinate** articulations (joint-space, Featherstone-like).
196+
Joint state is the canonical truth; body transforms are derived via
197+
forward kinematics.
198+
* - MJWarp
199+
- Reduced-coordinate, computed by the MuJoCo solver.
200+
* - Kamino
201+
- **Maximal-coordinate**: each body has its own free-body state,
202+
constraints are enforced via Baumgarte stabilization. Resets go
203+
through a dedicated FK pass (:attr:`~isaaclab_newton.physics.KaminoSolverCfg.use_fk_solver`)
204+
so maximal body poses match the reduced joint state after a state
205+
write.
206+
207+
**Porting implication.** Kamino is more sensitive to inconsistent reset
208+
state — joint positions and body poses must agree, which Isaac Lab's asset
209+
write paths handle but custom reset code can break.
210+
211+
212+
Substepping and Timestep
213+
------------------------
214+
215+
.. list-table::
216+
:header-rows: 1
217+
:widths: 25 75
218+
219+
* - Solver
220+
- Substep model
221+
* - PhysX TGS
222+
- PhysX runs at the simulation ``dt``. No external substep counter;
223+
internal substepping is per-actor.
224+
* - MJWarp
225+
- Top-level :attr:`~isaaclab_newton.physics.NewtonCfg.num_substeps`
226+
controls how many solver substeps run per Isaac Lab step. Effective
227+
solver ``dt`` is ``SimulationCfg.dt / num_substeps``.
228+
* - Kamino
229+
- Same :attr:`~isaaclab_newton.physics.NewtonCfg.num_substeps` knob.
230+
Validated Kamino task presets typically use 1–2 substeps; expect to
231+
raise this for contact-heavy tasks.
232+
233+
234+
GPU Buffers and Throughput
235+
--------------------------
236+
237+
.. list-table::
238+
:header-rows: 1
239+
:widths: 25 75
240+
241+
* - Solver
242+
- Memory model
243+
* - PhysX TGS
244+
- Static GPU buffers sized at construction. Undersized buffers cause
245+
crashes or dropped contacts at scale. See the
246+
:doc:`PhysX configuration page <physx/configuration>` for the
247+
``gpu_*`` knobs.
248+
* - MJWarp
249+
- Pre-allocated per-environment limits:
250+
:attr:`~isaaclab_newton.physics.MJWarpSolverCfg.njmax`
251+
(constraint rows) and
252+
:attr:`~isaaclab_newton.physics.MJWarpSolverCfg.nconmax` (contact
253+
points). The remainder of state lives in dynamically-sized Warp
254+
arrays.
255+
* - Kamino
256+
- Inherits MJWarp's pre-allocation pattern via Newton, plus its own
257+
contact-pair allocator
258+
(:attr:`~isaaclab_newton.physics.KaminoSolverCfg.collision_detector_max_contacts_per_pair`)
259+
when using the internal collision detector.
260+
261+
262+
Porting Checklist
263+
-----------------
264+
265+
When moving a task between solvers:
266+
267+
1. **Re-validate contact behavior.** Run the task at the smallest
268+
``num_envs`` with a visualizer; watch for new penetration or jitter
269+
before scaling up.
270+
2. **Retune friction.** PhysX patch friction and MJWarp per-contact friction
271+
are not interchangeable at the same coefficient.
272+
3. **Retune restitution.** MJWarp/Kamino have no bounce-threshold gate;
273+
reduce per-material restitution to suppress jitter.
274+
4. **Choose substeps.** PhysX → Newton typically needs at least 1–2
275+
substeps for contact-heavy tasks; manipulation tasks may need more.
276+
5. **Watch for CCD differences.** Tasks that relied on PhysX swept CCD
277+
should either reduce ``dt`` or raise ``num_substeps`` on Newton.
278+
6. **For Kamino specifically**, also validate reset behaviour and consider
279+
Baumgarte gains if you see drift on joint or contact constraints.

0 commit comments

Comments
 (0)