Skip to content
Open
Show file tree
Hide file tree
Changes from 16 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
1 change: 1 addition & 0 deletions CONTRIBUTORS.md
Original file line number Diff line number Diff line change
Expand Up @@ -85,6 +85,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.
16 changes: 16 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
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
170 changes: 170 additions & 0 deletions source/isaaclab_assets/isaaclab_assets/robots/openarm.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,170 @@
# 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.
Reference: https://github.com/enactic/openarm_isaac_lab
Please `git clone https://github.com/enactic/openarm_isaac_lab` and `export PYTHONPATH=$PYTHONPATH:~/openarm_isaac_lab` to use these configurations.
"""

from source.openarm.openarm.tasks.manager_based.openarm_manipulation import OPENARM_ROOT_DIR
Copy link
Contributor

Choose a reason for hiding this comment

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

logic: Importing from external repository creates fragile dependency - users must manually clone and configure PYTHONPATH. Consider error handling if import fails. Should there be a fallback or error handling if the external repository is not available?


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

OPENARM_BI_CFG = ArticulationCfg(
spawn=sim_utils.UsdFileCfg(
usd_path=f"{OPENARM_ROOT_DIR}/usds/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_joint1": 0.0,
"openarm_left_joint2": 0.0,
"openarm_left_joint3": 0.0,
"openarm_left_joint4": 0.0,
"openarm_left_joint5": 0.0,
"openarm_left_joint6": 0.0,
"openarm_left_joint7": 0.0,
"openarm_right_joint1": 0.0,
"openarm_right_joint2": 0.0,
"openarm_right_joint3": 0.0,
"openarm_right_joint4": 0.0,
"openarm_right_joint5": 0.0,
"openarm_right_joint6": 0.0,
"openarm_right_joint7": 0.0,
"openarm_left_finger_joint.*": 0.0,
"openarm_right_finger_joint.*": 0.0,
},
),
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(
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"{OPENARM_ROOT_DIR}/usds/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 +156 to +157
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.
"""
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.11.9"
version = "0.11.10"

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

0.11.10 (2025-11-26)
~~~~~~~~~~~~~~~~~~~

Added
^^^^^

* Added reaching task environments for OpenArm unimanual robot:
* :class:`OpenArmReachEnvCfg`; Gym ID ``Isaac-Reach-OpenArm-v0``.
* :class:`OpenArmReachEnvCfg_PLAY`; Gym ID ``OpenArmReachEnvCfg_PLAY``.
Copy link
Contributor

Choose a reason for hiding this comment

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

syntax: Gym ID should be Isaac-Reach-OpenArm-Play-v0 not OpenArmReachEnvCfg_PLAY to match the pattern used in other PLAY environments

Suggested change
* :class:`OpenArmReachEnvCfg_PLAY`; Gym ID ``OpenArmReachEnvCfg_PLAY``.
* :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.9 (2025-11-10)
~~~~~~~~~~~~~~~~~~~

Expand Down
Loading