Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
35 commits
Select commit Hold shift + click to select a range
1fdc9c5
added openarm asset
JinnnK Nov 25, 2025
a980b11
updated a license
JinnnK Nov 25, 2025
ac2161b
added reach task with openarm bimanual
JinnnK Nov 25, 2025
158faa2
updated reach task with openarm bimanual
JinnnK Nov 25, 2025
182ac16
added lift a cube task with openarm unimanual
JinnnK Nov 25, 2025
00a8aaf
added reach and cabinet task with openarm unimanual
JinnnK Nov 25, 2025
dd63da6
Fixed bug
JinnnK Nov 26, 2025
b647491
Fixed bugs
JinnnK Nov 26, 2025
94d6aab
Updated changelog
JinnnK Nov 26, 2025
66e1743
updated init
JinnnK Nov 26, 2025
0d51e76
updated license
JinnnK Nov 26, 2025
8c45882
updated contributors
JinnnK Nov 26, 2025
a9ab009
updated extension.toml
JinnnK Nov 26, 2025
7681c6b
updated environments.rst and added image files
JinnnK Nov 26, 2025
4349142
run pre-commit checks and modified codes
JinnnK Nov 26, 2025
eb559cc
removed unnecessary lines
JinnnK Nov 26, 2025
53c4155
Updated Comprehensive Environment List in the Documentation
JinnnK Nov 26, 2025
41354da
modified changelog
JinnnK Nov 26, 2025
41341df
updated joint names
JinnnK Dec 11, 2025
c1379ca
updated joint names in asset
JinnnK Dec 11, 2025
ed0ddb2
updated joint names
JinnnK Dec 11, 2025
6f6efe6
removed the low-performing policies
JinnnK Dec 11, 2025
3634e4a
updated docs
JinnnK Dec 11, 2025
d7ff33a
updated joint names
JinnnK Dec 11, 2025
18e44c9
updated feedback
JinnnK Dec 12, 2025
9c789e3
Directory update for lift_openarm_env_cfg.py
JinnnK Dec 12, 2025
80bb6be
Add motor specification references
JinnnK Dec 12, 2025
c1e884a
Add comment explaining environment modifications
JinnnK Dec 12, 2025
1770886
Add comment explaining environment modifications of reach tasks
JinnnK Dec 12, 2025
57aa239
Merge branch 'main' into feature/add_openarm_env
ooctipus Dec 12, 2025
6ec29cc
Change asset path
JinnnK Dec 16, 2025
baf699a
Merge branch 'main' into feature/add_openarm_env
AntoineRichard Dec 16, 2025
65762bb
updated docs
JinnnK Dec 17, 2025
0f1391d
updated pre-commit
JinnnK Dec 17, 2025
8cd7c41
Merge branch 'main' into feature/add_openarm_env
kellyguo11 Dec 17, 2025
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
1 change: 1 addition & 0 deletions CONTRIBUTORS.md
Original file line number Diff line number Diff line change
Expand Up @@ -88,6 +88,7 @@ Guidelines for modifications:
* Jinghuan Shang
* Jingzhou Liu
* Jinqi Wei
* Jinyeob Kim
* Johnson Sun
* Kaixi Bao
* Kris Wilson
Expand Down
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.
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.
32 changes: 32 additions & 0 deletions docs/source/overview/environments.rst
Original file line number Diff line number Diff line change
Expand Up @@ -163,6 +163,14 @@ for the lift-cube environment:
+-------------------------+------------------------------+-----------------------------------------------------------------------------+
| |agibot_place_toy| | |agibot_place_toy-link| | Pick up and place an object in a box with a Agibot A2D humanoid robot |
+-------------------------+------------------------------+-----------------------------------------------------------------------------+
| |reach_openarm_bi| | |reach_openarm_bi-link| | Move the end-effector to sampled target poses with the OpenArm robot |
+-------------------------+------------------------------+-----------------------------------------------------------------------------+
| |reach_openarm_uni| | |reach_openarm_uni-link| | Move the end-effector to a sampled target pose with the OpenArm robot |
+-------------------------+------------------------------+-----------------------------------------------------------------------------+
| |lift_openarm_uni| | |lift_openarm_uni-link| | Pick a cube and bring it to a sampled target position with the OpenArm robot|
+-------------------------+------------------------------+-----------------------------------------------------------------------------+
| |cabi_openarm_uni| | |cabi_openarm_uni-link| | Grasp the handle of a cabinet's drawer and open it with the OpenArm robot |
+-------------------------+------------------------------+-----------------------------------------------------------------------------+

.. |reach-franka| image:: ../_static/tasks/manipulation/franka_reach.jpg
.. |reach-ur10| image:: ../_static/tasks/manipulation/ur10_reach.jpg
Expand All @@ -183,6 +191,10 @@ for the lift-cube environment:
.. |agibot_place_toy| image:: ../_static/tasks/manipulation/agibot_place_toy.jpg
.. |kuka-allegro-lift| image:: ../_static/tasks/manipulation/kuka_allegro_lift.jpg
.. |kuka-allegro-reorient| image:: ../_static/tasks/manipulation/kuka_allegro_reorient.jpg
.. |reach_openarm_bi| image:: ../_static/tasks/manipulation/openarm_bi_reach.jpg
.. |reach_openarm_uni| image:: ../_static/tasks/manipulation/openarm_uni_reach.jpg
.. |lift_openarm_uni| image:: ../_static/tasks/manipulation/openarm_uni_lift.jpg
.. |cabi_openarm_uni| image:: ../_static/tasks/manipulation/openarm_uni_open_drawer.jpg

.. |reach-franka-link| replace:: `Isaac-Reach-Franka-v0 <https://github.com/isaac-sim/IsaacLab/blob/main/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/franka/joint_pos_env_cfg.py>`__
.. |reach-ur10-link| replace:: `Isaac-Reach-UR10-v0 <https://github.com/isaac-sim/IsaacLab/blob/main/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/ur_10/joint_pos_env_cfg.py>`__
Expand Down Expand Up @@ -212,6 +224,10 @@ for the lift-cube environment:
.. |cube-shadow-vis-link| replace:: `Isaac-Repose-Cube-Shadow-Vision-Direct-v0 <https://github.com/isaac-sim/IsaacLab/blob/main/source/isaaclab_tasks/isaaclab_tasks/direct/shadow_hand/shadow_hand_vision_env.py>`__
.. |agibot_place_mug-link| replace:: `Isaac-Place-Mug-Agibot-Left-Arm-RmpFlow-v0 <https://github.com/isaac-sim/IsaacLab/blob/main/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/place/config/agibot/place_upright_mug_rmp_rel_env_cfg.py>`__
.. |agibot_place_toy-link| replace:: `Isaac-Place-Toy2Box-Agibot-Right-Arm-RmpFlow-v0 <https://github.com/isaac-sim/IsaacLab/blob/main/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/place/config/agibot/place_toy2box_rmp_rel_env_cfg.py>`__
.. |reach_openarm_bi-link| replace:: `Isaac-Reach-OpenArm-Bi-v0 <https://github.com/isaac-sim/IsaacLab/blob/main/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/openarm/bimanual/joint_pos_env_cfg.py>`__
.. |reach_openarm_uni-link| replace:: `Isaac-Reach-OpenArm-v0 <https://github.com/isaac-sim/IsaacLab/blob/main/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/openarm/unimanual/joint_pos_env_cfg.py>`__
.. |lift_openarm_uni-link| replace:: `Isaac-Lift-Cube-OpenArm-v0 <https://github.com/isaac-sim/IsaacLab/blob/main/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/lift/config/openarm/joint_pos_env_cfg.py>`__
.. |cabi_openarm_uni-link| replace:: `Isaac-Open-Drawer-OpenArm-v0 <https://github.com/isaac-sim/IsaacLab/blob/main/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/cabinet/config/openarm/joint_pos_env_cfg.py>`__


Contact-rich Manipulation
Expand Down Expand Up @@ -1135,3 +1151,19 @@ inferencing, including reading from an already trained checkpoint and disabling
- Isaac-Velocity-Rough-Unitree-Go2-Play-v0
- Manager Based
- **rsl_rl** (PPO), **skrl** (PPO)
* - Isaac-Reach-OpenArm-Bi-v0
- Isaac-Reach-OpenArm-Bi-Play-v0
- Manager Based
- **rsl_rl** (PPO), **rl_games** (PPO)
* - Isaac-Reach-OpenArm-v0
- Isaac-Reach-OpenArm-Play-v0
- Manager Based
- **rsl_rl** (PPO), **skrl** (PPO), **rl_games** (PPO)
* - Isaac-Lift-Cube-OpenArm-v0
- Isaac-Lift-Cube-OpenArm-Play-v0
- Manager Based
- **rsl_rl** (PPO), **rl_games** (PPO)
* - Isaac-Open-Drawer-OpenArm-v0
- Isaac-Open-Drawer-OpenArm-Play-v0
- Manager Based
- **rsl_rl** (PPO), **rl_games** (PPO)
2 changes: 1 addition & 1 deletion source/isaaclab_assets/config/extension.toml
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
[package]
# Semantic Versioning is used: https://semver.org/
version = "0.2.3"
version = "0.2.4"

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

0.2.4 (2025-11-26)
~~~~~~~~~~~~~~~~~~

Added
^^^^^

* Configuration for OpenArm robots used for manipulation tasks.

0.2.3 (2025-08-11)
~~~~~~~~~~~~~~~~~~

Expand Down
173 changes: 173 additions & 0 deletions source/isaaclab_assets/isaaclab_assets/robots/openarm.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,173 @@
# 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 of OpenArm robots.

The following configurations are available:

* :obj:`OPENARM_BI_CFG`: OpenArm robot with two arms.
* :obj:`OPENARM_BI_HIGH_PD_CFG`: OpenArm robot with two arms and stiffer PD control.
* :obj:`OPENARM_UNI_CFG`: OpenArm robot with one arm.
* :obj:`OPENARM_UNI_HIGH_PD_CFG`: OpenArm robot with one arm and stiffer PD control.

References:
OpenArm repositories:
* https://github.com/enactic/openarm
* https://github.com/enactic/openarm_isaac_lab

Motor spec sheets:
* Joint 1–2 (DM-J8009P-2EC):
https://cdn.shopify.com/s/files/1/0673/6848/5000/files/DM-J8009P-2EC_User_Manual.pdf?v=1755481750
* Joint 3–4 (DM-J4340P-2EC / DM-J4340-2EC):
https://cdn.shopify.com/s/files/1/0673/6848/5000/files/DM-J4340-2EC_User_Manual.pdf?v=1756883905
* Joint 5–8 (DM-J4310-2EC V1.1):
https://files.seeedstudio.com/products/Damiao/DM-J4310-en.pdf
"""

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

OPENARM_BI_CFG = ArticulationCfg(
spawn=sim_utils.UsdFileCfg(
usd_path=f"{ISAAC_NUCLEUS_DIR}/Robots/OpenArm/openarm_bimanual/openarm_bimanual.usd",
rigid_props=sim_utils.RigidBodyPropertiesCfg(
disable_gravity=False,
max_depenetration_velocity=5.0,
),
articulation_props=sim_utils.ArticulationRootPropertiesCfg(
enabled_self_collisions=False,
solver_position_iteration_count=8,
solver_velocity_iteration_count=0,
),
),
init_state=ArticulationCfg.InitialStateCfg(
joint_pos={
"openarm_left_joint.*": 0.0,
"openarm_right_joint.*": 0.0,
"openarm_left_finger_joint.*": 0.0,
"openarm_right_finger_joint.*": 0.0,
},
),
# spec sheet for reference
# DM-J8009P-2EC (Joint 1, 2):
# https://cdn.shopify.com/s/files/1/0673/6848/5000/files/DM-J8009P-2EC_User_Manual.pdf?v=1755481750
# DM-J4340P-2EC, DM-J4340-2EC (Joint 3, 4):
# https://cdn.shopify.com/s/files/1/0673/6848/5000/files/DM-J4340-2EC_User_Manual.pdf?v=1756883905
# DM-J4310-2EC V1.1 (Joint 5, 6, 7, 8):
# https://files.seeedstudio.com/products/Damiao/DM-J4310-en.pdf
actuators={
Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Suggested change
actuators={
# spec sheet for reference
# DM-J8009P-2EC (Joint 1, 2):
# https://cdn.shopify.com/s/files/1/0673/6848/5000/files/DM-J8009P-2EC_User_Manual.pdf?v=1755481750
# DM-J4340P-2EC, DM-J4340-2EC (Joint 3, 4):
# https://cdn.shopify.com/s/files/1/0673/6848/5000/files/DM-J4340-2EC_User_Manual.pdf?v=1756883905
# DM-J4310-2EC V1.1 (Joint 5, 6, 7, 8):
# https://files.seeedstudio.com/products/Damiao/DM-J4310-en.pdf
actuators={

"openarm_arm": ImplicitActuatorCfg(
joint_names_expr=[
"openarm_left_joint[1-7]",
"openarm_right_joint[1-7]",
],
velocity_limit_sim={
"openarm_left_joint[1-2]": 2.175,
"openarm_right_joint[1-2]": 2.175,
"openarm_left_joint[3-4]": 2.175,
"openarm_right_joint[3-4]": 2.175,
"openarm_left_joint[5-7]": 2.61,
"openarm_right_joint[5-7]": 2.61,
},
effort_limit_sim={
"openarm_left_joint[1-2]": 40.0,
"openarm_right_joint[1-2]": 40.0,
"openarm_left_joint[3-4]": 27.0,
"openarm_right_joint[3-4]": 27.0,
"openarm_left_joint[5-7]": 7.0,
"openarm_right_joint[5-7]": 7.0,
},
stiffness=80.0,
damping=4.0,
),
"openarm_gripper": ImplicitActuatorCfg(
Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

If these value are taken from actuator spec, please attach the spec link here so other people can verify and validate as well : ))

Copy link
Contributor Author

@JinnnK JinnnK Dec 11, 2025

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Copy link
Collaborator

@ooctipus ooctipus Dec 11, 2025

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

rated rpm in DM-J8009P-2EC (Joint 1, 2): https://cdn.shopify.com/s/files/1/0673/6848/5000/files/DM-J8009P-2EC_User_Manual.pdf?v=1755481750 seems like 100 rpm, convert that to rad/s is 10.472 rad/s ? or is that not working very well with training.

While it is nice to match real hardware, It is not necessary to match exactly for all practical reasons, if you think this change is necessary for sim, we are also happy with current value, thanks!

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Yes, that’s correct! We are aware that the current specification does not fully match the real motor’s rated performance. However, for both training stability in simulation and safety during sim-to-real deployment, we intentionally set the velocity limits lower than the actual hardware capabilities.

With this configuration, we have already completed sim-to-real testing and confirmed that the system performs reliably.

Going forward, we plan to conduct additional experiments to identify a safe value that is closer to the real hardware, and we will update the configuration accordingly. We will also submit a PR once that work is completed. Thank you!

Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

sounds great!!

joint_names_expr=[
"openarm_left_finger_joint.*",
"openarm_right_finger_joint.*",
],
velocity_limit_sim=0.2,
effort_limit_sim=333.33,
stiffness=2e3,
damping=1e2,
),
},
soft_joint_pos_limit_factor=1.0,
)
"""Configuration of OpenArm Bimanual robot."""

OPENARM_UNI_CFG = ArticulationCfg(
spawn=sim_utils.UsdFileCfg(
usd_path=f"{ISAAC_NUCLEUS_DIR}/Robots/OpenArm/openarm_unimanual/openarm_unimanual.usd",
rigid_props=sim_utils.RigidBodyPropertiesCfg(
disable_gravity=False,
max_depenetration_velocity=5.0,
),
articulation_props=sim_utils.ArticulationRootPropertiesCfg(
enabled_self_collisions=False,
solver_position_iteration_count=8,
solver_velocity_iteration_count=0,
),
),
init_state=ArticulationCfg.InitialStateCfg(
joint_pos={
"openarm_joint1": 1.57,
"openarm_joint2": 0.0,
"openarm_joint3": -1.57,
"openarm_joint4": 1.57,
"openarm_joint5": 0.0,
"openarm_joint6": 0.0,
"openarm_joint7": 0.0,
"openarm_finger_joint.*": 0.044,
},
),
actuators={
"openarm_arm": ImplicitActuatorCfg(
joint_names_expr=["openarm_joint[1-7]"],
velocity_limit_sim={
"openarm_joint[1-2]": 2.175,
"openarm_joint[3-4]": 2.175,
"openarm_joint[5-7]": 2.61,
},
effort_limit_sim={
"openarm_joint[1-2]": 40.0,
"openarm_joint[3-4]": 27.0,
"openarm_joint[5-7]": 7.0,
},
stiffness=80.0,
damping=4.0,
),
"openarm_gripper": ImplicitActuatorCfg(
joint_names_expr=["openarm_finger_joint.*"],
velocity_limit_sim=0.2,
effort_limit_sim=333.33,
stiffness=2e3,
damping=1e2,
),
},
soft_joint_pos_limit_factor=1.0,
)
"""Configuration of OpenArm Unimanual robot."""

OPENARM_BI_HIGH_PD_CFG = OPENARM_BI_CFG.copy()
OPENARM_BI_HIGH_PD_CFG.spawn.rigid_props.disable_gravity = True
OPENARM_BI_HIGH_PD_CFG.actuators["openarm_arm"].stiffness = 400.0
OPENARM_BI_HIGH_PD_CFG.actuators["openarm_arm"].damping = 80.0
OPENARM_BI_HIGH_PD_CFG.actuators["openarm_gripper"].stiffness = 2e3
OPENARM_BI_HIGH_PD_CFG.actuators["openarm_gripper"].damping = 1e2
Comment on lines +159 to +160
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

style: High PD configuration sets same stiffness/damping values as base config for gripper actuators, making these lines redundant.

Suggested change
OPENARM_BI_HIGH_PD_CFG.actuators["openarm_gripper"].stiffness = 2e3
OPENARM_BI_HIGH_PD_CFG.actuators["openarm_gripper"].damping = 1e2
# Remove redundant lines since gripper values are already the same in base config

"""Configuration of OpenArm Bimanual robot with stiffer PD control.

This configuration is useful for task-space control using differential IK.
"""

OPENARM_UNI_HIGH_PD_CFG = OPENARM_UNI_CFG.copy()
OPENARM_UNI_HIGH_PD_CFG.spawn.rigid_props.disable_gravity = True
OPENARM_UNI_HIGH_PD_CFG.actuators["openarm_arm"].stiffness = 400.0
OPENARM_UNI_HIGH_PD_CFG.actuators["openarm_arm"].damping = 80.0
"""Configuration of OpenArm Unimanual robot with stiffer PD control.

This configuration is useful for task-space control using differential IK.
"""
20 changes: 20 additions & 0 deletions source/isaaclab_tasks/docs/CHANGELOG.rst
Original file line number Diff line number Diff line change
@@ -1,6 +1,26 @@
Changelog
---------

0.11.11 (2025-12-16)
~~~~~~~~~~~~~~~~~~~~

Added
^^^^^

* Added reaching task environments for OpenArm unimanual robot:
* :class:`OpenArmReachEnvCfg`; Gym ID ``Isaac-Reach-OpenArm-v0``.
* :class:`OpenArmReachEnvCfg_PLAY`; Gym ID ``Isaac-Reach-OpenArm-Play-v0``.
* Added lifting a cube task environments for OpenArm unimanual robot:
* :class:`OpenArmCubeLiftEnvCfg`; Gym ID ``Isaac-Lift-Cube-OpenArm-v0``.
* :class:`OpenArmCubeLiftEnvCfg_PLAY`; Gym ID ``Isaac-Lift-Cube-OpenArm-Play-v0``.
* Added opening a drawer task environments for OpenArm unimanual robot:
* :class:`OpenArmCabinetEnvCfg`; Gym ID ``Isaac-Open-Drawer-OpenArm-v0``.
* :class:`OpenArmCabinetEnvCfg_PLAY`; Gym ID ``Isaac-Open-Drawer-OpenArm-Play-v0``.
* Added reaching task environments for OpenArm bimanual robot:
* :class:`OpenArmReachEnvCfg`; Gym ID ``Isaac-Reach-OpenArm-Bi-v0``.
* :class:`OpenArmReachEnvCfg_PLAY`; Gym ID ``Isaac-Reach-OpenArm-Bi-Play-v0``.
Comment on lines +20 to +21
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

logic: Class name appears to be duplicated from line 11 - should these be distinct bimanual class names? Are the bimanual environments using different class names than the unimanual ones?



0.11.10 (2025-12-13)
~~~~~~~~~~~~~~~~~~~~

Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,38 @@
# 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

import gymnasium as gym

from . import agents

##
# Register Gym environments.
##

##
# Joint Position Control
##

gym.register(
id="Isaac-Open-Drawer-OpenArm-v0",
entry_point="isaaclab.envs:ManagerBasedRLEnv",
kwargs={
"env_cfg_entry_point": f"{__name__}.joint_pos_env_cfg:OpenArmCabinetEnvCfg",
"rsl_rl_cfg_entry_point": f"{agents.__name__}.rsl_rl_ppo_cfg:OpenArmCabinetPPORunnerCfg",
"rl_games_cfg_entry_point": f"{agents.__name__}:rl_games_ppo_cfg.yaml",
},
disable_env_checker=True,
)

gym.register(
id="Isaac-Open-Drawer-OpenArm-Play-v0",
entry_point="isaaclab.envs:ManagerBasedRLEnv",
kwargs={
"env_cfg_entry_point": f"{__name__}.joint_pos_env_cfg:OpenArmCabinetEnvCfg_PLAY",
"rsl_rl_cfg_entry_point": f"{agents.__name__}.rsl_rl_ppo_cfg:OpenArmCabinetPPORunnerCfg",
"rl_games_cfg_entry_point": f"{agents.__name__}:rl_games_ppo_cfg.yaml",
},
disable_env_checker=True,
)
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
Loading