Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension


Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
@@ -0,0 +1,5 @@
Changed
^^^^^^^

* Changed Newton-related dependencies to use MuJoCo 3.8, MuJoCo Warp 3.8.0.2,
Warp 1.13 or newer, and the packaged Newton 1.2.0 release candidate.
4 changes: 2 additions & 2 deletions source/isaaclab/setup.py
Original file line number Diff line number Diff line change
Expand Up @@ -31,11 +31,11 @@
"trimesh",
"pyglet>=2.1.6,<3",
"mujoco==3.8.0",
"mujoco-warp==3.8.0.1",
"mujoco-warp==3.8.0.2",
# image processing
"transformers==4.57.6",
"einops", # needed for transformers, doesn't always auto-install
"warp-lang==1.13.0",
"warp-lang>=1.13.0",
"matplotlib>=3.10.3", # minimum version for Python 3.12 support
# make sure this is consistent with isaac sim version
"pillow==12.1.1",
Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,5 @@
Changed
^^^^^^^

* Changed Newton integration to use the packaged Newton 1.2.0 release candidate
and updated transform conversion calls for Warp 1.13 compatibility.
4 changes: 2 additions & 2 deletions source/isaaclab_newton/setup.py
Original file line number Diff line number Diff line change
Expand Up @@ -39,9 +39,9 @@ def run(self):
"all": [
"prettytable==3.3.0",
"mujoco==3.8.0",
"mujoco-warp==3.8.0.1",
"mujoco-warp==3.8.0.2",
"PyOpenGL-accelerate==3.1.10",
"newton @ git+https://github.com/newton-physics/newton.git@v1.2.0rc2",
"newton==1.2.0rc3",
],
}

Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,5 @@
Fixed
^^^^^

* Fixed Newton transform synchronization for Warp 1.13 compatibility in the
RTX renderer.
Original file line number Diff line number Diff line change
@@ -0,0 +1,5 @@
Changed
^^^^^^^

* Changed the Newton extra to depend on the packaged Newton 1.2.0 release
candidate instead of a Git commit.
2 changes: 1 addition & 1 deletion source/isaaclab_physx/setup.py
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,7 @@

EXTRAS_REQUIRE = {
"newton": [
"newton @ git+https://github.com/newton-physics/newton.git@v1.2.0rc2",
"newton==1.2.0rc3",
],
}

Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,5 @@
Added
^^^^^

* Added Newton MJWarp physics preset support and mesh-based heterogeneous
object spawning for Dexsuite manipulation environments.
Original file line number Diff line number Diff line change
Expand Up @@ -3,9 +3,6 @@
#
# SPDX-License-Identifier: BSD-3-Clause

from isaaclab_newton.physics import MJWarpSolverCfg, NewtonCfg
from isaaclab_physx.physics import PhysxCfg

from isaaclab.assets import ArticulationCfg
from isaaclab.managers import RewardTermCfg as RewTerm
from isaaclab.managers import SceneEntityCfg
Expand All @@ -31,34 +28,6 @@
FINGER_SENSORS = [f"{name}_object_s" for name in FINGERTIP_LIST if name != "thumb_link_3"]


@configclass
class KukaAllegroPhysicsCfg(PresetCfg):
default = PhysxCfg(
bounce_threshold_velocity=0.01,
gpu_max_rigid_patch_count=4 * 5 * 2**15,
gpu_found_lost_pairs_capacity=2**26,
)
newton_mjwarp = NewtonCfg(
solver_cfg=MJWarpSolverCfg(
solver="newton",
integrator="implicitfast",
njmax=300,
nconmax=70,
impratio=10.0,
cone="elliptic",
update_data_interval=2,
iterations=100,
ls_iterations=15,
ls_parallel=False,
use_mujoco_contacts=True,
ccd_iterations=5000,
),
num_substeps=2,
debug_mode=False,
)
physx = default


@configclass
class KukaAllegroSceneCfg(PresetCfg):
@configclass
Expand Down Expand Up @@ -132,28 +101,15 @@ class KukaAllegroObservationCfg(PresetCfg):
default = state


@configclass
class KukaAllegroEventCfg(PresetCfg):
@configclass
class KukaAllegroPhysxEventCfg(dexsuite.StartupEventCfg, dexsuite.EventCfg):
pass

default = KukaAllegroPhysxEventCfg()
newton_mjwarp = dexsuite.EventCfg()
physx = default


@configclass
class KukaAllegroMixinCfg:
scene: KukaAllegroSceneCfg = KukaAllegroSceneCfg()
rewards: KukaAllegroReorientRewardCfg = KukaAllegroReorientRewardCfg()
observations: KukaAllegroObservationCfg = KukaAllegroObservationCfg()
events: KukaAllegroEventCfg = KukaAllegroEventCfg()
actions: KukaAllegroRelJointPosActionCfg = KukaAllegroRelJointPosActionCfg()

def __post_init__(self):
super().__post_init__()
self.sim.physics = KukaAllegroPhysicsCfg()


@configclass
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -5,6 +5,7 @@

from dataclasses import MISSING

from isaaclab_newton.physics import MJWarpSolverCfg, NewtonCfg, NewtonCollisionPipelineCfg, NewtonShapeCfg
from isaaclab_physx.physics import PhysxCfg

import isaaclab.sim as sim_utils
Expand All @@ -18,7 +19,7 @@
from isaaclab.managers import TerminationTermCfg as DoneTerm
from isaaclab.markers import VisualizationMarkersCfg
from isaaclab.scene import InteractiveSceneCfg
from isaaclab.sim import CapsuleCfg, ConeCfg, CuboidCfg, RigidBodyMaterialCfg, SphereCfg
from isaaclab.sim import MeshCapsuleCfg, MeshConeCfg, MeshCuboidCfg, MeshSphereCfg, RigidBodyMaterialCfg
from isaaclab.utils import configclass
from isaaclab.utils.assets import ISAAC_NUCLEUS_DIR
from isaaclab.utils.noise import UniformNoiseCfg as Unoise
Expand All @@ -37,26 +38,32 @@
)


OBJECT_PHYSICS = {
"physics_material": RigidBodyMaterialCfg(static_friction=0.5),
"collision_props": sim_utils.CollisionPropertiesCfg(contact_offset=0.002),
}


@configclass
class ObjectCfg(PresetCfg):
shapes = sim_utils.MultiAssetSpawnerCfg(
assets_cfg=[
CuboidCfg(size=(0.05, 0.1, 0.1), physics_material=RigidBodyMaterialCfg(static_friction=0.5)),
CuboidCfg(size=(0.05, 0.05, 0.1), physics_material=RigidBodyMaterialCfg(static_friction=0.5)),
CuboidCfg(size=(0.025, 0.1, 0.1), physics_material=RigidBodyMaterialCfg(static_friction=0.5)),
CuboidCfg(size=(0.025, 0.05, 0.1), physics_material=RigidBodyMaterialCfg(static_friction=0.5)),
CuboidCfg(size=(0.025, 0.025, 0.1), physics_material=RigidBodyMaterialCfg(static_friction=0.5)),
CuboidCfg(size=(0.01, 0.1, 0.1), physics_material=RigidBodyMaterialCfg(static_friction=0.5)),
SphereCfg(radius=0.05, physics_material=RigidBodyMaterialCfg(static_friction=0.5)),
SphereCfg(radius=0.025, physics_material=RigidBodyMaterialCfg(static_friction=0.5)),
CapsuleCfg(radius=0.04, height=0.025, physics_material=RigidBodyMaterialCfg(static_friction=0.5)),
CapsuleCfg(radius=0.04, height=0.01, physics_material=RigidBodyMaterialCfg(static_friction=0.5)),
CapsuleCfg(radius=0.04, height=0.1, physics_material=RigidBodyMaterialCfg(static_friction=0.5)),
CapsuleCfg(radius=0.025, height=0.1, physics_material=RigidBodyMaterialCfg(static_friction=0.5)),
CapsuleCfg(radius=0.025, height=0.2, physics_material=RigidBodyMaterialCfg(static_friction=0.5)),
CapsuleCfg(radius=0.01, height=0.2, physics_material=RigidBodyMaterialCfg(static_friction=0.5)),
ConeCfg(radius=0.05, height=0.1, physics_material=RigidBodyMaterialCfg(static_friction=0.5)),
ConeCfg(radius=0.025, height=0.1, physics_material=RigidBodyMaterialCfg(static_friction=0.5)),
MeshCuboidCfg(size=(0.05, 0.1, 0.1), **OBJECT_PHYSICS),
MeshCuboidCfg(size=(0.05, 0.05, 0.1), **OBJECT_PHYSICS),
MeshCuboidCfg(size=(0.025, 0.1, 0.1), **OBJECT_PHYSICS),
MeshCuboidCfg(size=(0.025, 0.05, 0.1), **OBJECT_PHYSICS),
MeshCuboidCfg(size=(0.025, 0.025, 0.1), **OBJECT_PHYSICS),
MeshCuboidCfg(size=(0.01, 0.1, 0.1), **OBJECT_PHYSICS),
MeshSphereCfg(radius=0.05, **OBJECT_PHYSICS),
MeshSphereCfg(radius=0.025, **OBJECT_PHYSICS),
MeshCapsuleCfg(radius=0.04, height=0.025, **OBJECT_PHYSICS),
MeshCapsuleCfg(radius=0.04, height=0.01, **OBJECT_PHYSICS),
MeshCapsuleCfg(radius=0.04, height=0.1, **OBJECT_PHYSICS),
MeshCapsuleCfg(radius=0.025, height=0.1, **OBJECT_PHYSICS),
MeshCapsuleCfg(radius=0.025, height=0.2, **OBJECT_PHYSICS),
MeshCapsuleCfg(radius=0.01, height=0.2, **OBJECT_PHYSICS),
MeshConeCfg(radius=0.05, height=0.1, **OBJECT_PHYSICS),
MeshConeCfg(radius=0.025, height=0.1, **OBJECT_PHYSICS),
],
rigid_props=sim_utils.RigidBodyPropertiesCfg(
solver_position_iteration_count=16,
Expand All @@ -77,7 +84,6 @@ class ObjectCfg(PresetCfg):
collision_props=sim_utils.CollisionPropertiesCfg(),
mass_props=sim_utils.MassPropertiesCfg(mass=0.2),
)
newton_mjwarp = cube # newton does not support multi-asset spawning yet
default = shapes


Expand Down Expand Up @@ -218,8 +224,8 @@ def __post_init__(self):


@configclass
class StartupEventCfg:
"""Startup-mode domain randomization (PhysX only — Newton does not support startup events)."""
class EventCfg:
"""Reset-mode events (shared by all physics backends)."""

robot_physics_material = EventTerm(
func=mdp.randomize_rigid_body_material,
Expand All @@ -245,6 +251,17 @@ class StartupEventCfg:
},
)

object_physics_inertia = EventTerm(
func=mdp.randomize_rigid_body_inertia,
mode="startup",
params={
"asset_cfg": SceneEntityCfg("object"),
"inertia_distribution_params": [0.01, 0.01],
"operation": "add",
"diagonal_only": True,
},
)

joint_stiffness_and_damping = EventTerm(
func=mdp.randomize_actuator_gains,
mode="startup",
Expand Down Expand Up @@ -276,11 +293,6 @@ class StartupEventCfg:
},
)


@configclass
class EventCfg:
"""Reset-mode events (shared by all physics backends)."""

# Gravity scheduling is a deliberate curriculum trick — starting with no
# gravity (easy) and gradually introducing full gravity (hard) makes learning
# smoother and removes the need for a separate "Lift" reward.
Expand Down Expand Up @@ -409,6 +421,36 @@ class TerminationsCfg:
abnormal_robot = DoneTerm(func=mdp.abnormal_robot_state)


@configclass
class PhysicsCfg(PresetCfg):
default = PhysxCfg(
bounce_threshold_velocity=0.01,
gpu_max_rigid_patch_count=4 * 5 * 2**15,
gpu_found_lost_pairs_capacity=2**26,
)
newton_mjwarp = NewtonCfg(
solver_cfg=MJWarpSolverCfg(
solver="newton",
integrator="implicitfast",
njmax=300,
nconmax=200,
impratio=10.0,
cone="elliptic",
update_data_interval=2,
iterations=100,
ls_iterations=15,
ls_parallel=False,
use_mujoco_contacts=False,
ccd_iterations=35,
),
collision_cfg=NewtonCollisionPipelineCfg(),
default_shape_cfg=NewtonShapeCfg(),
num_substeps=2,
debug_mode=False,
)
physx = default


@configclass
class DexsuiteReorientEnvCfg(ManagerBasedEnvCfg):
"""Dexsuite reorientation task definition, also the base definition for derivative Lift task and evaluation task"""
Expand All @@ -423,19 +465,11 @@ class DexsuiteReorientEnvCfg(ManagerBasedEnvCfg):
# MDP settings
rewards: RewardsCfg = RewardsCfg()
terminations: TerminationsCfg = TerminationsCfg()
events: EventCfg = MISSING # type: ignore
events: EventCfg = EventCfg()
curriculum: CurriculumCfg | None = CurriculumCfg()

def validate_config(self):
"""Check for invalid preset combinations after resolution."""
is_newton = not isinstance(self.sim.physics, PhysxCfg)
is_multi_asset = isinstance(self.scene.object.spawn, sim_utils.MultiAssetSpawnerCfg)

if is_newton and is_multi_asset:
raise ValueError(
"Newton physics does not support multi-asset spawning."
" Use a single-geometry object preset (e.g. presets=cube) instead of 'shapes'."
)

warp_supported = {"rgb", "depth", "distance_to_image_plane"}
for cam_attr in ("base_camera", "wrist_camera"):
Expand Down Expand Up @@ -466,11 +500,7 @@ def __post_init__(self):
# simulation settings
self.sim.dt = 1 / 120
self.sim.render_interval = self.decimation
self.sim.physics = PhysxCfg(
bounce_threshold_velocity=0.01,
gpu_max_rigid_patch_count=4 * 5 * 2**15,
gpu_found_lost_pairs_capacity=2**26,
)
self.sim.physics = PhysicsCfg()


class DexsuiteLiftEnvCfg(DexsuiteReorientEnvCfg):
Expand Down
6 changes: 3 additions & 3 deletions source/isaaclab_visualizers/setup.py
Original file line number Diff line number Diff line change
Expand Up @@ -17,16 +17,16 @@
"kit": [],
"newton": [
"warp-lang",
"newton @ git+https://github.com/newton-physics/newton.git@v1.2.0rc2",
"newton==1.2.0rc3",
"PyOpenGL-accelerate",
"imgui-bundle>=1.92.5",
],
"rerun": [
"newton @ git+https://github.com/newton-physics/newton.git@v1.2.0rc2",
"newton==1.2.0rc3",
"rerun-sdk>=0.29.0",
],
"viser": [
"newton @ git+https://github.com/newton-physics/newton.git@v1.2.0rc2",
"newton==1.2.0rc3",
"viser>=1.0.16",
],
}
Expand Down
4 changes: 2 additions & 2 deletions tools/wheel_builder/res/python_packages.toml
Original file line number Diff line number Diff line change
Expand Up @@ -85,8 +85,8 @@ pyproject.optional-dependencies.all = [
{ "newton" = [
"warp-lang==1.13.0",
"mujoco==3.8.0",
"mujoco-warp==3.8.0.1",
"newton @ git+https://github.com/newton-physics/newton.git@v1.2.0rc2",
"mujoco-warp==3.8.0.2",
"newton==1.2.0rc3",
"PyOpenGL-accelerate==3.1.10"
] },
# ================================================================================
Expand Down
Loading