Skip to content
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
109 changes: 61 additions & 48 deletions docs/source/overview/environments.rst

Large diffs are not rendered by default.

Original file line number Diff line number Diff line change
Expand Up @@ -18,6 +18,7 @@
from .humanoid import *
from .humanoid_28 import *
from .kinova import *
from .kuka_allegro import *
from .pick_and_place import *
from .quadcopter import *
from .ridgeback_franka import *
Expand Down
114 changes: 114 additions & 0 deletions source/isaaclab_assets/isaaclab_assets/robots/kuka_allegro.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,114 @@
# Copyright (c) 2022-2025, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md).
# All rights reserved.
#
# SPDX-License-Identifier: BSD-3-Clause

"""Configuration for the Kuka-lbr-iiwa arm robots and Allegro Hand.

The following configurations are available:

* :obj:`KUKA_ALLEGRO_CFG`: Kuka Allegro with implicit actuator model.

Reference:

* https://www.kuka.com/en-us/products/robotics-systems/industrial-robots/lbr-iiwa
* https://www.wonikrobotics.com/robot-hand

"""

import isaaclab.sim as sim_utils
from isaaclab.actuators.actuator_cfg import ImplicitActuatorCfg
from isaaclab.assets.articulation import ArticulationCfg
from isaaclab.utils.assets import ISAACLAB_NUCLEUS_DIR

##
# Configuration
##

KUKA_ALLEGRO_CFG = ArticulationCfg(
spawn=sim_utils.UsdFileCfg(
usd_path=f"{ISAACLAB_NUCLEUS_DIR}/Robots/KukaAllegro/kuka.usd",
activate_contact_sensors=True,
rigid_props=sim_utils.RigidBodyPropertiesCfg(
disable_gravity=True,
retain_accelerations=True,
linear_damping=0.0,
angular_damping=0.0,
max_linear_velocity=1000.0,
max_angular_velocity=1000.0,
max_depenetration_velocity=1000.0,
),
articulation_props=sim_utils.ArticulationRootPropertiesCfg(
enabled_self_collisions=True,
solver_position_iteration_count=32,
solver_velocity_iteration_count=1,
sleep_threshold=0.005,
stabilization_threshold=0.0005,
),
joint_drive_props=sim_utils.JointDrivePropertiesCfg(drive_type="force"),
),
init_state=ArticulationCfg.InitialStateCfg(
pos=(0.0, 0.0, 0.0),
rot=(1.0, 0.0, 0.0, 0.0),
joint_pos={
"iiwa7_joint_(1|2|7)": 0.0,
"iiwa7_joint_3": 0.7854,
"iiwa7_joint_4": 1.5708,
"iiwa7_joint_(5|6)": -1.5708,
"(index|middle|ring)_joint_0": 0.0,
"(index|middle|ring)_joint_1": 0.3,
"(index|middle|ring)_joint_2": 0.3,
"(index|middle|ring)_joint_3": 0.3,
"thumb_joint_0": 1.5,
"thumb_joint_1": 0.60147215,
"thumb_joint_2": 0.33795027,
"thumb_joint_3": 0.60845138,
},
),
actuators={
"kuka_allegro_actuators": ImplicitActuatorCfg(
joint_names_expr=[
"iiwa7_joint_(1|2|3|4|5|6|7)",
"index_joint_(0|1|2|3)",
"middle_joint_(0|1|2|3)",
"ring_joint_(0|1|2|3)",
"thumb_joint_(0|1|2|3)",
],
effort_limit_sim={
"iiwa7_joint_(1|2|3|4|5|6|7)": 300.0,
"index_joint_(0|1|2|3)": 0.5,
"middle_joint_(0|1|2|3)": 0.5,
"ring_joint_(0|1|2|3)": 0.5,
"thumb_joint_(0|1|2|3)": 0.5,
},
stiffness={
"iiwa7_joint_(1|2|3|4)": 300.0,
"iiwa7_joint_5": 100.0,
"iiwa7_joint_6": 50.0,
"iiwa7_joint_7": 25.0,
"index_joint_(0|1|2|3)": 3.0,
"middle_joint_(0|1|2|3)": 3.0,
"ring_joint_(0|1|2|3)": 3.0,
"thumb_joint_(0|1|2|3)": 3.0,
},
damping={
"iiwa7_joint_(1|2|3|4)": 45.0,
"iiwa7_joint_5": 20.0,
"iiwa7_joint_6": 15.0,
"iiwa7_joint_7": 15.0,
"index_joint_(0|1|2|3)": 0.1,
"middle_joint_(0|1|2|3)": 0.1,
"ring_joint_(0|1|2|3)": 0.1,
"thumb_joint_(0|1|2|3)": 0.1,
},
friction={
"iiwa7_joint_(1|2|3|4|5|6|7)": 1.0,
"index_joint_(0|1|2|3)": 0.01,
"middle_joint_(0|1|2|3)": 0.01,
"ring_joint_(0|1|2|3)": 0.01,
"thumb_joint_(0|1|2|3)": 0.01,
},
),
},
soft_joint_pos_limit_factor=1.0,
)
2 changes: 1 addition & 1 deletion source/isaaclab_tasks/config/extension.toml
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
[package]

# Note: Semantic Versioning is used: https://semver.org/
version = "0.10.51"
version = "0.11.0"

# Description
title = "Isaac Lab Environments"
Expand Down
9 changes: 9 additions & 0 deletions source/isaaclab_tasks/docs/CHANGELOG.rst
Original file line number Diff line number Diff line change
@@ -1,6 +1,15 @@
Changelog
---------

0.11.0 (2025-09-07)
~~~~~~~~~~~~~~~~~~~~

Added
^^^^^

* Added dextrous lifting and dextrous reorientation manipulation rl environments.


0.10.51 (2025-09-08)
~~~~~~~~~~~~~~~~~~~~

Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,26 @@
# Copyright (c) 2022-2025, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md).
# All rights reserved.
#
# SPDX-License-Identifier: BSD-3-Clause

"""Dexsuite environments.
Implementation Reference:
Reorient:
@article{petrenko2023dexpbt,
title={Dexpbt: Scaling up dexterous manipulation for hand-arm systems with population based training},
author={Petrenko, Aleksei and Allshire, Arthur and State, Gavriel and Handa, Ankur and Makoviychuk, Viktor},
journal={arXiv preprint arXiv:2305.12127},
year={2023}
}
Lift:
@article{singh2024dextrah,
title={Dextrah-rgb: Visuomotor policies to grasp anything with dexterous hands},
author={Singh, Ritvik and Allshire, Arthur and Handa, Ankur and Ratliff, Nathan and Van Wyk, Karl},
journal={arXiv preprint arXiv:2412.01791},
year={2024}
}
"""
Original file line number Diff line number Diff line change
@@ -0,0 +1,122 @@
# Copyright (c) 2022-2025, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md).
# All rights reserved.
#
# SPDX-License-Identifier: BSD-3-Clause

from isaaclab.managers import CurriculumTermCfg as CurrTerm
from isaaclab.utils import configclass

from . import mdp


@configclass
class CurriculumCfg:
"""Curriculum terms for the MDP."""

# adr stands for automatic/adaptive domain randomization
adr = CurrTerm(
func=mdp.DifficultyScheduler, params={"init_difficulty": 0, "min_difficulty": 0, "max_difficulty": 10}
)

joint_pos_unoise_min_adr = CurrTerm(
func=mdp.modify_term_cfg,
params={
"address": "observations.proprio.joint_pos.noise.n_min",
"modify_fn": mdp.initial_final_interpolate_fn,
"modify_params": {"initial_value": 0.0, "final_value": -0.1, "difficulty_term_str": "adr"},
},
)

joint_pos_unoise_max_adr = CurrTerm(
func=mdp.modify_term_cfg,
params={
"address": "observations.proprio.joint_pos.noise.n_max",
"modify_fn": mdp.initial_final_interpolate_fn,
"modify_params": {"initial_value": 0.0, "final_value": 0.1, "difficulty_term_str": "adr"},
},
)

joint_vel_unoise_min_adr = CurrTerm(
func=mdp.modify_term_cfg,
params={
"address": "observations.proprio.joint_vel.noise.n_min",
"modify_fn": mdp.initial_final_interpolate_fn,
"modify_params": {"initial_value": 0.0, "final_value": -0.2, "difficulty_term_str": "adr"},
},
)

joint_vel_unoise_max_adr = CurrTerm(
func=mdp.modify_term_cfg,
params={
"address": "observations.proprio.joint_vel.noise.n_max",
"modify_fn": mdp.initial_final_interpolate_fn,
"modify_params": {"initial_value": 0.0, "final_value": 0.2, "difficulty_term_str": "adr"},
},
)

hand_tips_pos_unoise_min_adr = CurrTerm(
func=mdp.modify_term_cfg,
params={
"address": "observations.proprio.hand_tips_state_b.noise.n_min",
"modify_fn": mdp.initial_final_interpolate_fn,
"modify_params": {"initial_value": 0.0, "final_value": -0.01, "difficulty_term_str": "adr"},
},
)

hand_tips_pos_unoise_max_adr = CurrTerm(
func=mdp.modify_term_cfg,
params={
"address": "observations.proprio.hand_tips_state_b.noise.n_max",
"modify_fn": mdp.initial_final_interpolate_fn,
"modify_params": {"initial_value": 0.0, "final_value": 0.01, "difficulty_term_str": "adr"},
},
)

object_quat_unoise_min_adr = CurrTerm(
func=mdp.modify_term_cfg,
params={
"address": "observations.policy.object_quat_b.noise.n_min",
"modify_fn": mdp.initial_final_interpolate_fn,
"modify_params": {"initial_value": 0.0, "final_value": -0.03, "difficulty_term_str": "adr"},
},
)

object_quat_unoise_max_adr = CurrTerm(
func=mdp.modify_term_cfg,
params={
"address": "observations.policy.object_quat_b.noise.n_max",
"modify_fn": mdp.initial_final_interpolate_fn,
"modify_params": {"initial_value": 0.0, "final_value": 0.03, "difficulty_term_str": "adr"},
},
)

object_obs_unoise_min_adr = CurrTerm(
func=mdp.modify_term_cfg,
params={
"address": "observations.perception.object_point_cloud.noise.n_min",
"modify_fn": mdp.initial_final_interpolate_fn,
"modify_params": {"initial_value": 0.0, "final_value": -0.01, "difficulty_term_str": "adr"},
},
)

object_obs_unoise_max_adr = CurrTerm(
func=mdp.modify_term_cfg,
params={
"address": "observations.perception.object_point_cloud.noise.n_max",
"modify_fn": mdp.initial_final_interpolate_fn,
"modify_params": {"initial_value": 0.0, "final_value": -0.01, "difficulty_term_str": "adr"},
},
)

gravity_adr = CurrTerm(
func=mdp.modify_term_cfg,
params={
"address": "events.variable_gravity.params.gravity_distribution_params",
"modify_fn": mdp.initial_final_interpolate_fn,
"modify_params": {
"initial_value": ((0.0, 0.0, 0.0), (0.0, 0.0, 0.0)),
"final_value": ((0.0, 0.0, -9.81), (0.0, 0.0, -9.81)),
"difficulty_term_str": "adr",
},
},
)
Original file line number Diff line number Diff line change
@@ -0,0 +1,9 @@
# Copyright (c) 2022-2025, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md).
# All rights reserved.
#
# SPDX-License-Identifier: BSD-3-Clause

"""Configurations for the dexsuite environments."""

# We leave this file empty since we don't want to expose any configs in this package directly.
# We still need this file to import the "config" module in the parent package.
Original file line number Diff line number Diff line change
@@ -0,0 +1,63 @@
# Copyright (c) 2022-2025, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md).
# All rights reserved.
#
# SPDX-License-Identifier: BSD-3-Clause

"""
Dextra Kuka Allegro environments.
"""

import gymnasium as gym

from . import agents

##
# Register Gym environments.
##

# State Observation
gym.register(
id="Isaac-Dexsuite-Kuka-Allegro-Reorient-v0",
entry_point="isaaclab.envs:ManagerBasedRLEnv",
disable_env_checker=True,
kwargs={
"env_cfg_entry_point": f"{__name__}.dexsuite_kuka_allegro_env_cfg:DexsuiteKukaAllegroReorientEnvCfg",
"rl_games_cfg_entry_point": f"{agents.__name__}:rl_games_ppo_cfg.yaml",
"rsl_rl_cfg_entry_point": f"{agents.__name__}.rsl_rl_ppo_cfg:DexsuiteKukaAllegroPPORunnerCfg",
},
)

gym.register(
id="Isaac-Dexsuite-Kuka-Allegro-Reorient-Play-v0",
entry_point="isaaclab.envs:ManagerBasedRLEnv",
disable_env_checker=True,
kwargs={
"env_cfg_entry_point": f"{__name__}.dexsuite_kuka_allegro_env_cfg:DexsuiteKukaAllegroReorientEnvCfg_PLAY",
"rl_games_cfg_entry_point": f"{agents.__name__}:rl_games_ppo_cfg.yaml",
"rsl_rl_cfg_entry_point": f"{agents.__name__}.rsl_rl_ppo_cfg:DexsuiteKukaAllegroPPORunnerCfg",
},
)

# Dexsuite Lift Environments
gym.register(
id="Isaac-Dexsuite-Kuka-Allegro-Lift-v0",
entry_point="isaaclab.envs:ManagerBasedRLEnv",
disable_env_checker=True,
kwargs={
"env_cfg_entry_point": f"{__name__}.dexsuite_kuka_allegro_env_cfg:DexsuiteKukaAllegroLiftEnvCfg",
"rl_games_cfg_entry_point": f"{agents.__name__}:rl_games_ppo_cfg.yaml",
"rsl_rl_cfg_entry_point": f"{agents.__name__}.rsl_rl_ppo_cfg:DexsuiteKukaAllegroPPORunnerCfg",
},
)


gym.register(
id="Isaac-Dexsuite-Kuka-Allegro-Lift-Play-v0",
entry_point="isaaclab.envs:ManagerBasedRLEnv",
disable_env_checker=True,
kwargs={
"env_cfg_entry_point": f"{__name__}.dexsuite_kuka_allegro_env_cfg:DexsuiteKukaAllegroLiftEnvCfg_PLAY",
"rl_games_cfg_entry_point": f"{agents.__name__}:rl_games_ppo_cfg.yaml",
"rsl_rl_cfg_entry_point": f"{agents.__name__}.rsl_rl_ppo_cfg:DexsuiteKukaAllegroPPORunnerCfg",
},
)
Original file line number Diff line number Diff line change
@@ -0,0 +1,4 @@
# Copyright (c) 2022-2025, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md).
# All rights reserved.
#
# SPDX-License-Identifier: BSD-3-Clause
Loading