Skip to content
Open
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
2 changes: 1 addition & 1 deletion docs/pages/concepts/concept_embodiment_design.rst
Original file line number Diff line number Diff line change
Expand Up @@ -102,7 +102,7 @@ Usage Examples
.. code-block:: python

embodiment = asset_registry.get_asset_by_name("gr1_pink")()
teleop_device = device_registry.get_device_by_name("avp_handtracking")()
teleop_device = device_registry.get_device_by_name("openxr")()

environment = IsaacLabArenaEnvironment(
embodiment=embodiment,
Expand Down
2 changes: 1 addition & 1 deletion docs/pages/concepts/concept_teleop_devices_design.rst
Original file line number Diff line number Diff line change
Expand Up @@ -85,4 +85,4 @@ Usage Examples
.. code-block:: bash

# VR hand tracking for humanoid control
python isaaclab_arena/scripts/teleop.py --teleop_device avp_handtracking gr1_open_microwave
python isaaclab_arena/scripts/teleop.py --teleop_device openxr gr1_open_microwave
Original file line number Diff line number Diff line change
Expand Up @@ -69,7 +69,7 @@ Run the recording script:
--num_demos 10 \
--num_success_steps 2 \
gr1_open_microwave \
--teleop_device avp_handtracking
--teleop_device openxr


Step 4: Connect Vision Pro and Record
Expand Down
5 changes: 5 additions & 0 deletions isaaclab_arena/embodiments/embodiment_base.py
Original file line number Diff line number Diff line change
Expand Up @@ -5,6 +5,7 @@

from typing import Any

from isaaclab.devices.retargeter_base import RetargeterCfg
from isaaclab.envs import ManagerBasedRLMimicEnv
from isaaclab.managers.recorder_manager import RecorderManagerBaseCfg

Expand Down Expand Up @@ -86,6 +87,10 @@ def get_xr_cfg(self) -> Any:
def get_camera_cfg(self) -> Any:
return self.camera_config

def get_retargeters(self, sim_device: str | None = None) -> dict[str, list[RetargeterCfg]]:
"""Get the retargeters for the embodiment."""
return {}

def _update_scene_cfg_with_robot_initial_pose(self, scene_config: Any, pose: Pose) -> Any:
if scene_config is None or not hasattr(scene_config, "robot"):
raise RuntimeError("scene_config must be populated with a `robot` before calling `set_robot_initial_pose`.")
Expand Down
16 changes: 16 additions & 0 deletions isaaclab_arena/embodiments/gr1t2/gr1t2.py
Original file line number Diff line number Diff line change
Expand Up @@ -16,6 +16,8 @@
from isaaclab.actuators import ImplicitActuatorCfg
from isaaclab.assets.articulation.articulation_cfg import ArticulationCfg
from isaaclab.devices.openxr import XrCfg
from isaaclab.devices.openxr.retargeters import GR1T2RetargeterCfg
from isaaclab.devices.retargeter_base import RetargeterCfg
from isaaclab.envs import ManagerBasedRLMimicEnv
from isaaclab.envs.mdp.actions import JointPositionActionCfg
from isaaclab.managers import EventTermCfg as EventTerm
Expand Down Expand Up @@ -101,6 +103,20 @@ def __init__(self, enable_cameras: bool = False, initial_pose: Pose | None = Non
anchor_rot=(0.70711, 0.0, 0.0, -0.70711),
)

def get_retargeters(self, sim_device: str | None = None) -> dict[str, list[RetargeterCfg]]:
"""Get the retargeters for the GR1T2 robot."""
retargeters = {
"openxr": [
GR1T2RetargeterCfg(
enable_visualization=True,
num_open_xr_hand_joints=52,
sim_device=sim_device,
hand_joint_names=self.get_action_cfg().upper_body_ik.hand_joint_names,
)
]
}
return retargeters


@register_asset
class GR1T2JointEmbodiment(GR1T2EmbodimentBase):
Expand Down
2 changes: 1 addition & 1 deletion isaaclab_arena/scripts/record_demos.py
Original file line number Diff line number Diff line change
Expand Up @@ -280,7 +280,7 @@ def setup_teleop_device(callbacks: dict[str, Callable]) -> object:
teleop_interface = Se3SpaceMouse(Se3SpaceMouseCfg(pos_sensitivity=0.2, rot_sensitivity=0.5))
else:
omni.log.error(f"Unsupported teleop device: {args_cli.teleop_device}")
omni.log.error("Supported devices: keyboard, spacemouse, avp_handtracking")
omni.log.error("Supported devices: keyboard, spacemouse, openxr")
exit(1)

# Add callbacks to fallback device
Expand Down
2 changes: 1 addition & 1 deletion isaaclab_arena/scripts/teleop.py
Original file line number Diff line number Diff line change
Expand Up @@ -200,7 +200,7 @@ def stop_teleoperation() -> None:
)
else:
omni.log.error(f"Unsupported teleop device: {args_cli.teleop_device}")
omni.log.error("Supported devices: keyboard, spacemouse, gamepad, avp_handtracking")
omni.log.error("Supported devices: keyboard, spacemouse, gamepad, openxr")
env.close()
simulation_app.close()
return
Expand Down
2 changes: 1 addition & 1 deletion isaaclab_arena/teleop_devices/__init__.py
Original file line number Diff line number Diff line change
Expand Up @@ -3,6 +3,6 @@
#
# SPDX-License-Identifier: Apache-2.0

from .avp_handtracking import *
from .keyboard import *
from .openxr import *
from .spacemouse import *
Original file line number Diff line number Diff line change
Expand Up @@ -18,40 +18,27 @@

from isaaclab.devices.device_base import DevicesCfg
from isaaclab.devices.openxr import OpenXRDeviceCfg
from isaaclab.devices.openxr.retargeters import GR1T2RetargeterCfg

from isaaclab_arena.assets.register import register_device
from isaaclab_arena.teleop_devices.teleop_device_base import TeleopDeviceBase


@register_device
class HandTrackingTeleopDevice(TeleopDeviceBase):
class OpenXRTeleopDevice(TeleopDeviceBase):
"""
Teleop device for hand tracking.
Teleop device wrapping the OpenXRDevice.
"""

name = "avp_handtracking"
name = "openxr"

def __init__(
self, sim_device: str | None = None, num_open_xr_hand_joints: int = 52, enable_visualization: bool = True
):
def __init__(self, sim_device: str | None = None):
super().__init__(sim_device=sim_device)
self.num_open_xr_hand_joints = num_open_xr_hand_joints
self.enable_visualization = enable_visualization

def get_teleop_device_cfg(self, embodiment: object | None = None):
return DevicesCfg(
devices={
"avp_handtracking": OpenXRDeviceCfg(
retargeters=[
GR1T2RetargeterCfg(
enable_visualization=self.enable_visualization,
# number of joints in both hands
num_open_xr_hand_joints=self.num_open_xr_hand_joints,
sim_device=self.sim_device,
hand_joint_names=embodiment.get_action_cfg().upper_body_ik.hand_joint_names,
),
],
"openxr": OpenXRDeviceCfg(
retargeters=embodiment.get_retargeters(sim_device=self.sim_device)["openxr"],
sim_device=self.sim_device,
xr_cfg=embodiment.get_xr_cfg(),
),
Expand Down
2 changes: 1 addition & 1 deletion isaaclab_arena/tests/test_device_registry.py
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,7 @@

NUM_STEPS = 2
HEADLESS = True
DEVICE_NAMES = ["avp_handtracking", "spacemouse", "keyboard"]
DEVICE_NAMES = ["openxr", "spacemouse", "keyboard"]


def _test_all_devices_in_registry(simulation_app):
Expand Down