Using the Kamino Solver#
Kamino is a Newton solver, not a separate Isaac Lab physics backend. In Isaac Lab,
Kamino is enabled by selecting a NewtonCfg whose
solver_cfg is KaminoSolverCfg.
This is usually exposed as a newton_kamino physics preset on the task configuration.
Kamino support is currently beta. A task that works with PhysX or with Newton’s MuJoCo-Warp solver may still need task-specific asset, collision, reset, and solver tuning before it works well with Kamino.
Start from a Supported Newton Task#
Before adding Kamino, first make sure the task runs with the Newton backend:
./isaaclab.sh -p scripts/environments/zero_agent.py --task Isaac-Cartpole-Direct-v0 --num_envs 128 --viz newton presets=newton_mjwarp
Then run the same task with the Kamino preset if it is available:
./isaaclab.sh -p scripts/environments/zero_agent.py --task Isaac-Cartpole-Direct-v0 --num_envs 128 --viz newton presets=newton_kamino
At the time of writing, the newton_kamino preset is defined for
Isaac-Cartpole-Direct-v0, Isaac-Ant-Direct-v0, Isaac-Cartpole-v0,
and Isaac-Ant-v0. Passing presets=newton_kamino to another task does not
automatically enable Kamino; the task must define and validate its own newton_kamino
preset.
Add a Kamino Physics Preset#
Tasks that support multiple physics options usually store SimulationCfg.physics
as a PresetCfg. First import the Newton
solver config types used by the presets:
from isaaclab_newton.physics import KaminoSolverCfg, MJWarpSolverCfg, NewtonCfg
Then add a newton_kamino entry beside the existing default, physx, and
newton_mjwarp entries:
class CartpolePhysicsCfg(PresetCfg):
default: PhysxCfg = PhysxCfg()
physx: PhysxCfg = PhysxCfg()
newton_mjwarp: NewtonCfg = NewtonCfg(
solver_cfg=MJWarpSolverCfg(
njmax=5,
nconmax=3,
cone="pyramidal",
impratio=1,
integrator="implicitfast",
),
num_substeps=1,
debug_mode=False,
use_cuda_graph=True,
)
newton_kamino: NewtonCfg = NewtonCfg(
solver_cfg=KaminoSolverCfg(
integrator="moreau",
use_collision_detector=True,
sparse_jacobian=True,
constraints_alpha=0.1,
padmm_max_iterations=100,
padmm_primal_tolerance=1e-4,
padmm_dual_tolerance=1e-4,
padmm_compl_tolerance=1e-4,
padmm_rho_0=0.05,
padmm_eta=1e-5,
padmm_use_acceleration=True,
padmm_warmstart_mode="containers",
padmm_contact_warmstart_method="geom_pair_net_force",
padmm_use_graph_conditionals=False,
collision_detector_pipeline="unified",
collision_detector_max_contacts_per_pair=8,
),
num_substeps=1,
debug_mode=False,
use_cuda_graph=True,
)
ovphysx: OvPhysxCfg = OvPhysxCfg()
The important pieces are:
Add a
newton_kaminopreset whose value isNewtonCfg.Set
solver_cfg=KaminoSolverCfg(...)inside that Newton config.Keep the preset at the same config path used by the task’s
SimulationCfg, for exampleenv.sim.physics.
You can select the preset globally:
./isaaclab.sh -p scripts/reinforcement_learning/rsl_rl/train.py --task=Isaac-Cartpole-v0 presets=newton_kamino
or select the physics field directly:
./isaaclab.sh -p scripts/reinforcement_learning/rsl_rl/train.py --task=Isaac-Cartpole-v0 env.sim.physics=newton_kamino
Use the direct path override when only one task field should use the Kamino preset.
Use presets=newton_kamino when you want every matching preset field in the task config
to resolve to newton_kamino.
Isaac Lab training scripts accept these Hydra overrides after the regular command
line flags; no separator is needed for the examples above.
Check Task and Asset Compatibility#
Kamino uses the Newton model built from the task assets. When adding Kamino to a new task, validate the following before tuning solver parameters:
The task must already be compatible with the Newton backend. If
presets=newton_mjwarpfails during model construction, fix the asset or task configuration first.The assets should use Newton-supported rigid bodies, articulations, and collision geometry. PhysX-only features, unsupported schemas, or missing collision shapes can prevent Newton model creation or produce unusable contacts.
Reset logic should write consistent root and joint state through Isaac Lab asset APIs. Kamino uses a forward-kinematics reset path after state writes so maximal coordinate body poses match the reduced joint state.
Sensor, renderer, and visualizer presets remain separate from the solver preset. Kamino can share the Newton-compatible sensors and renderers used by the task, but each sensor and renderer combination still needs its own validation.
Contact-heavy tasks usually need their own collision mode, substep count, and P-ADMM iteration/tolerance settings. Start from the validated Cartpole or Ant preset that most closely resembles the task.
For a small articulated system with simple contacts, the Cartpole preset uses Kamino’s internal collision detector. For Ant, the preset uses Newton’s collision pipeline and two substeps. These choices are task-specific; treat them as starting points rather than universal defaults.
Kamino Solver Parameters#
The following fields are specific to KaminoSolverCfg.
They are grouped by the part of the solver they affect.
Core Integration#
Parameter |
Description |
|---|---|
|
Default: |
|
Default: |
|
Default: |
|
Default: |
Collision Handling#
Parameter |
Description |
|---|---|
|
Default: |
|
Default: |
|
Default: |
|
Default: |
Constraint Stabilization#
Parameter |
Description |
|---|---|
|
Default: |
|
Default: |
|
Default: |
P-ADMM Solver Controls#
Parameter |
Description |
|---|---|
|
Default: |
|
Default: |
|
Default: |
|
Default: |
|
Default: |
|
Default: |
|
Default: |
|
Default: |
|
Default: |
|
Default: |
Sparsity, Dynamics, and Debugging#
Parameter |
Description |
|---|---|
|
Default: |
|
Default: |
|
Default: |
|
Default: |
|
Default: |
Tuning Workflow#
Use the following sequence when bringing up a new Kamino task:
Run the task with
presets=newton_mjwarpand fix Newton model construction or task compatibility issues first.Add a
newton_kaminopreset with conservative values copied from the closest validated task.Run a small smoke test with a low environment count and a visualizer.
Increase
num_envsand profile only after the task is stable.Tune
num_substeps,padmm_max_iterations, and the P-ADMM tolerances together. Raising iteration count without checking tolerances can hide a poorly scaled constraint setup.Enable
collect_solver_infoorcompute_solution_metricsonly while debugging convergence. Disable them for training and benchmarks.