Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
41 commits
Select commit Hold shift + click to select a range
3e175ac
Add surface gripper in manager-based workflow
rebeccazhang0707 Jul 31, 2025
8b37298
pre-commit format check
rebeccazhang0707 Jul 31, 2025
b4dc6be
adapt to official Sim usd assets with gripper variants, and remove re…
rebeccazhang0707 Aug 14, 2025
c069116
fix bugs in SurfaceGripperAction apply_actions(), dimension alignment
rebeccazhang0707 Aug 18, 2025
20e8ec2
add galbot_stack_cube tasks and mimic tasks:
rebeccazhang0707 Aug 18, 2025
8bab66b
- use "reset" events to modify the robot initial_states, and convert …
rebeccazhang0707 Aug 19, 2025
01cf7df
Merge branch 'reb/surface_gripper' into reb/galbot_stack_cube
rebeccazhang0707 Aug 19, 2025
eb0d96a
after ./isaaclab.sh -f
rebeccazhang0707 Aug 19, 2025
d4918ab
add AbsBinaryJointPositionAction
rebeccazhang0707 Aug 19, 2025
8a4a6ca
pre-commit format check
rebeccazhang0707 Aug 19, 2025
0f6ab6b
fixes surface_gripper operations in get_state() and reset_to() of Int…
rebeccazhang0707 Aug 19, 2025
07dbceb
smaller pos_sensitivity for keyboard teleop
rebeccazhang0707 Aug 19, 2025
a0419f9
Merge branch 'reb/surface_gripper' into reb/galbot_stack_cube
rebeccazhang0707 Aug 19, 2025
6edd402
decrease the cube_scale to default, otherwise, the cube_stacked() ter…
rebeccazhang0707 Aug 19, 2025
da9717a
Merge branch 'reb/surface_gripper' into reb/galbot_stack_cube
rebeccazhang0707 Aug 19, 2025
9ae55e2
Merge branch 'main' into reb/surface_gripper
rebeccazhang0707 Aug 19, 2025
e01d12a
Revert "decrease the cube_scale to default, otherwise, the cube_stack…
rebeccazhang0707 Aug 19, 2025
a7da1ba
fix bug of surface_gripper checking in obs and terminations:
rebeccazhang0707 Aug 19, 2025
37e3ac2
remove randomize_galbot_joint_by_gaussion_offset event, which is not …
rebeccazhang0707 Aug 19, 2025
a1398fd
refactor SurfaceGripperBinaryAction class
rebeccazhang0707 Aug 20, 2025
d1cf8c0
revise the return_key options in get cube_poses and ee_frame_pose
rebeccazhang0707 Aug 20, 2025
bbb2593
revert the original UR10_CFG
rebeccazhang0707 Aug 20, 2025
76c00f9
Adds Agibot place_toy2box and place_upright_mug tasks and mimic tasks:
rebeccazhang0707 Aug 20, 2025
15b6e01
Merge branch 'main' into reb/surface_gripper
kellyguo11 Aug 26, 2025
b834e0f
- UR10_LONG/SHORT_SUCTION_CFG inherits UR10_CFG and overrides some va…
rebeccazhang0707 Aug 27, 2025
253a326
update original surface_gripper scripts
rebeccazhang0707 Aug 27, 2025
5e8e37f
format check
rebeccazhang0707 Aug 27, 2025
2333183
update docs
rebeccazhang0707 Aug 29, 2025
fedd3e0
Merge branch 'main' into reb/galbot_stack_cube
kellyguo11 Aug 29, 2025
6f54f48
fixs ArticulaitonCfg to use default gains setup from USD in galbot.py
rebeccazhang0707 Sep 1, 2025
972e90e
update the usd_path with variants
rebeccazhang0707 Sep 1, 2025
e38ee2a
update usd_path in AssetCfg
rebeccazhang0707 Sep 1, 2025
ac16701
- update init_pose of robot in AssetCfg instead of using events
rebeccazhang0707 Sep 2, 2025
c088583
add to environments in the docs
rebeccazhang0707 Sep 2, 2025
11c7e3d
move rmpflow configs to cloud
rebeccazhang0707 Sep 2, 2025
f819cad
move the rmpflow configs to cloud
rebeccazhang0707 Sep 2, 2025
ef47ccf
adds to environments in docs
rebeccazhang0707 Sep 2, 2025
50b4602
Merge branch 'reb/surface_gripper' into reb/galbot_stack_cube
rebeccazhang0707 Sep 2, 2025
cff65a0
Merge branch 'reb/galbot_stack_cube' into reb/agibot_place_tasks
rebeccazhang0707 Sep 2, 2025
22d0c1e
add retrieve_file_path for RmpFlowAssets Cfg files
rebeccazhang0707 Sep 2, 2025
cebf1fd
Merge branch 'reb/galbot_stack_cube' into reb/agibot_place_tasks
rebeccazhang0707 Sep 2, 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
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.
23 changes: 22 additions & 1 deletion docs/source/overview/environments.rst
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,7 @@
Available Environments
======================

The following lists comprises of all the RL tasks implementations that are available in Isaac Lab.
The following lists comprises of all the RL or IL tasks implementations that are available in Isaac Lab.
While we try to keep this list up-to-date, you can always get the latest list of environments by
running the following command:

Expand Down Expand Up @@ -113,6 +113,10 @@ for the lift-cube environment:
| | | Blueprint env used for the NVIDIA Isaac GR00T blueprint for synthetic |
| | |stack-cube-bp-link| | manipulation motion generation |
+--------------------+-------------------------+-----------------------------------------------------------------------------+
| |surface-gripper| | |long-suction-link| | Stack three cubes (bottom to top: blue, red, green) |
| | | with the UR10 arm and long surface gripper |
| | |short-suction-link| | or short surface gripper. |
+--------------------+-------------------------+-----------------------------------------------------------------------------+
| |cabi-franka| | |cabi-franka-link| | Grasp the handle of a cabinet's drawer and open it with the Franka robot |
| | | |
| | |franka-direct-link| | |
Expand All @@ -135,6 +139,13 @@ for the lift-cube environment:
| |gr1_pp_waist| | |gr1_pp_waist-link| | Pick up and place an object in a basket with a GR-1 humanoid robot |
| | | with waist degrees-of-freedom enables that provides a wider reach space. |
+--------------------+-------------------------+-----------------------------------------------------------------------------+
| |galbot_stack| | |galbot_stack-link| | Stack three cubes (bottom to top: blue, red, green) with the left arm of |
| | | a Galbot humanoid robot |
+--------------------+-------------------------+-----------------------------------------------------------------------------+
| |agibot_place_mug| | |agibot_place_mug-link| | Pick up and place a mug upright with a Agibot A2D humanoid robot |
+--------------------+-------------------------+-----------------------------------------------------------------------------+
| |agibot_place_toy| | |agibot_place_toy-link| | Pick up and place an object in a box with a Agibot A2D humanoid robot |
+--------------------+-------------------------+-----------------------------------------------------------------------------+

.. |reach-franka| image:: ../_static/tasks/manipulation/franka_reach.jpg
.. |reach-ur10| image:: ../_static/tasks/manipulation/ur10_reach.jpg
Expand All @@ -145,6 +156,10 @@ for the lift-cube environment:
.. |stack-cube| image:: ../_static/tasks/manipulation/franka_stack.jpg
.. |gr1_pick_place| image:: ../_static/tasks/manipulation/gr-1_pick_place.jpg
.. |gr1_pp_waist| image:: ../_static/tasks/manipulation/gr-1_pick_place_waist.jpg
.. |surface-gripper| image:: ../_static/tasks/manipulation/ur10_stack_surface_gripper.jpg
.. |galbot_stack| image:: ../_static/tasks/manipulation/galbot_stack_cube.jpg
.. |agibot_place_mug| image:: ../_static/tasks/manipulation/agibot_place_mug.jpg
.. |agibot_place_toy| image:: ../_static/tasks/manipulation/agibot_place_toy.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 All @@ -159,12 +174,18 @@ for the lift-cube environment:
.. |stack-cube-bp-link| replace:: `Isaac-Stack-Cube-Franka-IK-Rel-Blueprint-v0 <https://github.com/isaac-sim/IsaacLab/blob/main/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/stack/config/franka/stack_ik_rel_blueprint_env_cfg.py>`__
.. |gr1_pick_place-link| replace:: `Isaac-PickPlace-GR1T2-Abs-v0 <https://github.com/isaac-sim/IsaacLab/blob/main/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/pick_place/pickplace_gr1t2_env_cfg.py>`__
.. |gr1_pp_waist-link| replace:: `Isaac-PickPlace-GR1T2-WaistEnabled-Abs-v0 <https://github.com/isaac-sim/IsaacLab/blob/main/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/pick_place/pickplace_gr1t2_waist_enabled_env_cfg.py>`__
.. |galbot_stack-link| replace:: `Isaac-Stack-Cube-Galbot-Left-Arm-Gripper-RmpFlow-v0 <https://github.com/isaac-sim/IsaacLab/blob/main/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/stack/config/galbot/stack_rmp_rel_env_cfg.py>`__
.. |long-suction-link| replace:: `Isaac-Stack-Cube-UR10-Long-Suction-IK-Rel-v0 <https://github.com/isaac-sim/IsaacLab/blob/main/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/stack/config/ur10_gripper/stack_ik_rel_env_cfg.py>`__
.. |short-suction-link| replace:: `Isaac-Stack-Cube-UR10-Short-Suction-IK-Rel-v0 <https://github.com/isaac-sim/IsaacLab/blob/main/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/stack/config/ur10_gripper/stack_ik_rel_env_cfg.py>`__

.. |cube-shadow-link| replace:: `Isaac-Repose-Cube-Shadow-Direct-v0 <https://github.com/isaac-sim/IsaacLab/blob/main/source/isaaclab_tasks/isaaclab_tasks/direct/shadow_hand/shadow_hand_env_cfg.py>`__
.. |cube-shadow-ff-link| replace:: `Isaac-Repose-Cube-Shadow-OpenAI-FF-Direct-v0 <https://github.com/isaac-sim/IsaacLab/blob/main/source/isaaclab_tasks/isaaclab_tasks/direct/shadow_hand/shadow_hand_env_cfg.py>`__
.. |cube-shadow-lstm-link| replace:: `Isaac-Repose-Cube-Shadow-OpenAI-LSTM-Direct-v0 <https://github.com/isaac-sim/IsaacLab/blob/main/source/isaaclab_tasks/isaaclab_tasks/direct/shadow_hand/shadow_hand_env_cfg.py>`__
.. |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>`__

Contact-rich Manipulation
~~~~~~~~~~~~~~~~~~~~~~~~~

Expand Down
2 changes: 1 addition & 1 deletion scripts/demos/pick_and_place.py
Original file line number Diff line number Diff line change
Expand Up @@ -87,7 +87,7 @@ class PickAndPlaceEnvCfg(DirectRLEnvCfg):

# Surface Gripper, the prim_expr need to point to a unique surface gripper per environment.
gripper = SurfaceGripperCfg(
prim_expr="/World/envs/env_.*/Robot/picker_head/SurfaceGripper",
prim_path="/World/envs/env_.*/Robot/picker_head/SurfaceGripper",
max_grip_distance=0.1,
shear_force_limit=500.0,
coaxial_force_limit=500.0,
Expand Down
2 changes: 1 addition & 1 deletion scripts/tutorials/01_assets/run_surface_gripper.py
Original file line number Diff line number Diff line change
Expand Up @@ -72,7 +72,7 @@ def design_scene():
# Surface Gripper: Next we define the surface gripper config
surface_gripper_cfg = SurfaceGripperCfg()
# We need to tell the View which prim to use for the surface gripper
surface_gripper_cfg.prim_expr = "/World/Origin.*/Robot/picker_head/SurfaceGripper"
surface_gripper_cfg.prim_path = "/World/Origin.*/Robot/picker_head/SurfaceGripper"
# We can then set different parameters for the surface gripper, note that if these parameters are not set,
# the View will try to read them from the prim.
surface_gripper_cfg.max_grip_distance = 0.1 # [m] (Maximum distance at which the gripper can grasp an object)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -9,6 +9,7 @@
import warnings
from typing import TYPE_CHECKING

import omni.log
from isaacsim.core.utils.extensions import enable_extension
from isaacsim.core.version import get_version

Expand All @@ -18,7 +19,7 @@
if TYPE_CHECKING:
from isaacsim.robot.surface_gripper import GripperView

from .surface_gripper_cfg import SurfaceGripperCfg
from .surface_gripper_cfg import SurfaceGripperCfg


class SurfaceGripper(AssetBase):
Expand Down Expand Up @@ -246,7 +247,7 @@ def _initialize_impl(self) -> None:

Raises:
ValueError: If the simulation backend is not CPU.
RuntimeError: If the Simulation Context is not initialized.
RuntimeError: If the Simulation Context is not initialized or if gripper prims are not found.

Note:
The SurfaceGripper is only supported on CPU for now. Please set the simulation backend to run on CPU.
Expand All @@ -262,8 +263,35 @@ def _initialize_impl(self) -> None:
"SurfaceGripper is only supported on CPU for now. Please set the simulation backend to run on CPU. Use"
" `--device cpu` to run the simulation on CPU."
)

# obtain the first prim in the regex expression (all others are assumed to be a copy of this)
template_prim = sim_utils.find_first_matching_prim(self._cfg.prim_path)
if template_prim is None:
raise RuntimeError(f"Failed to find prim for expression: '{self._cfg.prim_path}'.")
template_prim_path = template_prim.GetPath().pathString

# find surface gripper prims
gripper_prims = sim_utils.get_all_matching_child_prims(
template_prim_path, predicate=lambda prim: prim.GetTypeName() == "IsaacSurfaceGripper"
)
if len(gripper_prims) == 0:
raise RuntimeError(
f"Failed to find a surface gripper when resolving '{self._cfg.prim_path}'."
" Please ensure that the prim has type 'IsaacSurfaceGripper'."
)
if len(gripper_prims) > 1:
raise RuntimeError(
f"Failed to find a single surface gripper when resolving '{self._cfg.prim_path}'."
f" Found multiple '{gripper_prims}' under '{template_prim_path}'."
" Please ensure that there is only one surface gripper in the prim path tree."
)

# resolve gripper prim back into regex expression
gripper_prim_path = gripper_prims[0].GetPath().pathString
gripper_prim_path_expr = self._cfg.prim_path + gripper_prim_path[len(template_prim_path) :]

# Count number of environments
self._prim_expr = self._cfg.prim_expr
self._prim_expr = gripper_prim_path_expr
env_prim_path_expr = self._prim_expr.rsplit("/", 1)[0]
self._parent_prims = sim_utils.find_matching_prims(env_prim_path_expr)
self._num_envs = len(self._parent_prims)
Expand All @@ -287,6 +315,10 @@ def _initialize_impl(self) -> None:
retry_interval=self._retry_interval.clone(),
)

# log information about the surface gripper
omni.log.info(f"Surface gripper initialized at: {self._cfg.prim_path} with root '{gripper_prim_path_expr}'.")
omni.log.info(f"Number of instances: {self._num_envs}")

# Reset grippers
self.reset()

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -7,12 +7,15 @@

from isaaclab.utils import configclass

from ..asset_base_cfg import AssetBaseCfg
from .surface_gripper import SurfaceGripper


@configclass
class SurfaceGripperCfg:
class SurfaceGripperCfg(AssetBaseCfg):
"""Configuration parameters for a surface gripper actuator."""

prim_expr: str = MISSING
prim_path: str = MISSING
"""The expression to find the grippers in the stage."""

max_grip_distance: float | None = None
Expand All @@ -26,3 +29,5 @@ class SurfaceGripperCfg:

retry_interval: float | None = None
"""The amount of time the gripper will spend trying to grasp an object."""

class_type: type = SurfaceGripper
61 changes: 61 additions & 0 deletions source/isaaclab/isaaclab/controllers/config/rmp_flow.py
Original file line number Diff line number Diff line change
Expand Up @@ -9,6 +9,13 @@

from isaaclab.controllers.rmp_flow import RmpFlowControllerCfg

# from isaaclab.utils.assets import ISAACLAB_NUCLEUS_DIR

# FIXME: temp uploaded to nucleus folder, remove this line in public release and use above ISAACLAB_NUCLEUS_DIR
ISAACLAB_NUCLEUS_DIR = "https://isaac-dev.ov.nvidia.com/omni/web3/omniverse://isaac-dev.ov.nvidia.com/Isaac/IsaacLab"

ISAACLAB_NUCLEUS_RMPFLOW_DIR = os.path.join(ISAACLAB_NUCLEUS_DIR, "Controllers", "RmpFlowAssets")

# Note: RMP-Flow config files for supported robots are stored in the motion_generation extension
_RMP_CONFIG_DIR = os.path.join(
get_extension_path_from_name("isaacsim.robot_motion.motion_generation"), "motion_policy_configs"
Expand All @@ -35,3 +42,57 @@
evaluations_per_frame=5,
)
"""Configuration of RMPFlow for UR10 arm (default from `isaacsim.robot_motion.motion_generation`)."""

GALBOT_LEFT_ARM_RMPFLOW_CFG = RmpFlowControllerCfg(
config_file=os.path.join(
ISAACLAB_NUCLEUS_RMPFLOW_DIR,
"galbot_one_charlie",
"rmpflow",
"galbot_one_charlie_left_arm_rmpflow_config.yaml",
),
urdf_file=os.path.join(ISAACLAB_NUCLEUS_RMPFLOW_DIR, "galbot_one_charlie", "galbot_one_charlie.urdf"),
collision_file=os.path.join(
ISAACLAB_NUCLEUS_RMPFLOW_DIR, "galbot_one_charlie", "rmpflow", "galbot_one_charlie_left_arm_gripper.yaml"
),
frame_name="left_gripper_tcp_link",
evaluations_per_frame=5,
ignore_robot_state_updates=True,
)

GALBOT_RIGHT_ARM_RMPFLOW_CFG = RmpFlowControllerCfg(
config_file=os.path.join(
ISAACLAB_NUCLEUS_RMPFLOW_DIR,
"galbot_one_charlie",
"rmpflow",
"galbot_one_charlie_right_arm_rmpflow_config.yaml",
),
urdf_file=os.path.join(ISAACLAB_NUCLEUS_RMPFLOW_DIR, "galbot_one_charlie", "galbot_one_charlie.urdf"),
collision_file=os.path.join(
ISAACLAB_NUCLEUS_RMPFLOW_DIR, "galbot_one_charlie", "rmpflow", "galbot_one_charlie_right_arm_suction.yaml"
),
frame_name="right_suction_cup_tcp_link",
evaluations_per_frame=5,
ignore_robot_state_updates=True,
)

"""Configuration of RMPFlow for Galbot humanoid."""

AGIBOT_LEFT_ARM_RMPFLOW_CFG = RmpFlowControllerCfg(
config_file=os.path.join(ISAACLAB_NUCLEUS_RMPFLOW_DIR, "agibot", "rmpflow", "agibot_left_arm_rmpflow_config.yaml"),
urdf_file=os.path.join(ISAACLAB_NUCLEUS_RMPFLOW_DIR, "agibot", "agibot.urdf"),
collision_file=os.path.join(ISAACLAB_NUCLEUS_RMPFLOW_DIR, "agibot", "rmpflow", "agibot_left_arm_gripper.yaml"),
frame_name="gripper_center",
evaluations_per_frame=5,
ignore_robot_state_updates=True,
)

AGIBOT_RIGHT_ARM_RMPFLOW_CFG = RmpFlowControllerCfg(
config_file=os.path.join(ISAACLAB_NUCLEUS_RMPFLOW_DIR, "agibot", "rmpflow", "agibot_right_arm_rmpflow_config.yaml"),
urdf_file=os.path.join(ISAACLAB_NUCLEUS_RMPFLOW_DIR, "agibot", "agibot.urdf"),
collision_file=os.path.join(ISAACLAB_NUCLEUS_RMPFLOW_DIR, "agibot", "rmpflow", "agibot_right_arm_gripper.yaml"),
frame_name="right_gripper_center",
evaluations_per_frame=5,
ignore_robot_state_updates=True,
)

"""Configuration of RMPFlow for Agibot humanoid."""
13 changes: 10 additions & 3 deletions source/isaaclab/isaaclab/controllers/rmp_flow.py
Original file line number Diff line number Diff line change
Expand Up @@ -20,6 +20,7 @@
from isaacsim.robot_motion.motion_generation.lula.motion_policies import RmpFlow, RmpFlowSmoothed

from isaaclab.utils import configclass
from isaaclab.utils.assets import retrieve_file_path


@configclass
Expand Down Expand Up @@ -95,11 +96,17 @@ def initialize(self, prim_paths_expr: str):
# add robot reference
robot = SingleArticulation(prim_path)
robot.initialize()
# download files if they are not local

local_urdf_file = retrieve_file_path(self.cfg.urdf_file, force_download=True)
local_collision_file = retrieve_file_path(self.cfg.collision_file, force_download=True)
local_config_file = retrieve_file_path(self.cfg.config_file, force_download=True)

# add controller
rmpflow = controller_cls(
robot_description_path=self.cfg.collision_file,
urdf_path=self.cfg.urdf_file,
rmpflow_config_path=self.cfg.config_file,
robot_description_path=local_collision_file,
urdf_path=local_urdf_file,
rmpflow_config_path=local_config_file,
end_effector_frame_name=self.cfg.frame_name,
maximum_substep_size=physics_dt / self.cfg.evaluations_per_frame,
ignore_robot_state_updates=self.cfg.ignore_robot_state_updates,
Expand Down
Loading
Loading