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
9 changes: 3 additions & 6 deletions docs/source/how-to/cloudxr_teleoperation.rst
Original file line number Diff line number Diff line change
Expand Up @@ -935,18 +935,15 @@ The retargeting system is designed to be extensible. You can create custom retar
# Return control commands in appropriate format
return torch.tensor([0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.0]) # Example output

3. Register your retargeter with the factory by adding it to the ``RETARGETER_MAP``:
3. Register your retargeter by setting ``retargeter_type`` on the config class:

.. code-block:: python

# Import your retargeter at the top of your module
from my_package.retargeters import MyCustomRetargeter, MyCustomRetargeterCfg

# Add your retargeter to the factory
from isaaclab.devices.teleop_device_factory import RETARGETER_MAP

# Register your retargeter type with its constructor
RETARGETER_MAP[MyCustomRetargeterCfg] = MyCustomRetargeter
# Link the config to the implementation for factory construction
MyCustomRetargeterCfg.retargeter_type = MyCustomRetargeter

4. Now you can use your custom retargeter in teleop device configurations:

Expand Down
2 changes: 1 addition & 1 deletion source/isaaclab/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.47.4"
version = "0.47.5"

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

0.47.5 (2025-10-30)
~~~~~~~~~~~~~~~~~~~

Changed
^^^^^^^

* Moved retargeter and device declaration out of factory and into the devices/retargeters themselves.


0.47.4 (2025-10-30)
~~~~~~~~~~~~~~~~~~~

Expand Down
6 changes: 6 additions & 0 deletions source/isaaclab/isaaclab/devices/device_base.py
Original file line number Diff line number Diff line change
Expand Up @@ -18,8 +18,14 @@
class DeviceCfg:
"""Configuration for teleoperation devices."""

# Whether teleoperation should start active by default
teleoperation_active_default: bool = True
# Torch device string to place output tensors on
sim_device: str = "cpu"
# Retargeters that transform device data into robot commands
retargeters: list[RetargeterCfg] = field(default_factory=list)
# Concrete device class to construct for this config. Set by each device module.
device_type: type["DeviceBase"] | None = None


@dataclass
Expand Down
23 changes: 13 additions & 10 deletions source/isaaclab/isaaclab/devices/gamepad/se2_gamepad.py
Original file line number Diff line number Diff line change
Expand Up @@ -5,6 +5,8 @@

"""Gamepad controller for SE(2) control."""

from __future__ import annotations

import numpy as np
import torch
import weakref
Expand All @@ -18,16 +20,6 @@
from ..device_base import DeviceBase, DeviceCfg


@dataclass
class Se2GamepadCfg(DeviceCfg):
"""Configuration for SE2 gamepad devices."""

v_x_sensitivity: float = 1.0
v_y_sensitivity: float = 1.0
omega_z_sensitivity: float = 1.0
dead_zone: float = 0.01


class Se2Gamepad(DeviceBase):
r"""A gamepad controller for sending SE(2) commands as velocity commands.

Expand Down Expand Up @@ -209,3 +201,14 @@ def _resolve_command_buffer(self, raw_command: np.ndarray) -> np.ndarray:
command[command_sign] *= -1

return command


@dataclass
class Se2GamepadCfg(DeviceCfg):
"""Configuration for SE2 gamepad devices."""

v_x_sensitivity: float = 1.0
v_y_sensitivity: float = 1.0
omega_z_sensitivity: float = 1.0
dead_zone: float = 0.01
device_type: type[DeviceBase] = Se2Gamepad
24 changes: 13 additions & 11 deletions source/isaaclab/isaaclab/devices/gamepad/se3_gamepad.py
Original file line number Diff line number Diff line change
Expand Up @@ -5,6 +5,8 @@

"""Gamepad controller for SE(3) control."""

from __future__ import annotations

import numpy as np
import torch
import weakref
Expand All @@ -18,17 +20,6 @@
from ..device_base import DeviceBase, DeviceCfg


@dataclass
class Se3GamepadCfg(DeviceCfg):
"""Configuration for SE3 gamepad devices."""

gripper_term: bool = True
dead_zone: float = 0.01 # For gamepad devices
pos_sensitivity: float = 1.0
rot_sensitivity: float = 1.6
retargeters: None = None


class Se3Gamepad(DeviceBase):
"""A gamepad controller for sending SE(3) commands as delta poses and binary command (open/close).

Expand Down Expand Up @@ -264,3 +255,14 @@ def _resolve_command_buffer(self, raw_command: np.ndarray) -> np.ndarray:
delta_command[delta_command_sign] *= -1

return delta_command


@dataclass
class Se3GamepadCfg(DeviceCfg):
"""Configuration for SE3 gamepad devices."""

gripper_term: bool = True
dead_zone: float = 0.01 # For gamepad devices
pos_sensitivity: float = 1.0
rot_sensitivity: float = 1.6
device_type: type[DeviceBase] = Se3Gamepad
21 changes: 12 additions & 9 deletions source/isaaclab/isaaclab/devices/keyboard/se2_keyboard.py
Original file line number Diff line number Diff line change
Expand Up @@ -5,6 +5,8 @@

"""Keyboard controller for SE(2) control."""

from __future__ import annotations

import numpy as np
import torch
import weakref
Expand All @@ -17,15 +19,6 @@
from ..device_base import DeviceBase, DeviceCfg


@dataclass
class Se2KeyboardCfg(DeviceCfg):
"""Configuration for SE2 keyboard devices."""

v_x_sensitivity: float = 0.8
v_y_sensitivity: float = 0.4
omega_z_sensitivity: float = 1.0


class Se2Keyboard(DeviceBase):
r"""A keyboard controller for sending SE(2) commands as velocity commands.

Expand Down Expand Up @@ -178,3 +171,13 @@ def _create_key_bindings(self):
"NUMPAD_9": np.asarray([0.0, 0.0, -1.0]) * self.omega_z_sensitivity,
"X": np.asarray([0.0, 0.0, -1.0]) * self.omega_z_sensitivity,
}


@dataclass
class Se2KeyboardCfg(DeviceCfg):
"""Configuration for SE2 keyboard devices."""

v_x_sensitivity: float = 0.8
v_y_sensitivity: float = 0.4
omega_z_sensitivity: float = 1.0
device_type: type[DeviceBase] = Se2Keyboard
23 changes: 13 additions & 10 deletions source/isaaclab/isaaclab/devices/keyboard/se3_keyboard.py
Original file line number Diff line number Diff line change
Expand Up @@ -5,6 +5,8 @@

"""Keyboard controller for SE(3) control."""

from __future__ import annotations

import numpy as np
import torch
import weakref
Expand All @@ -18,16 +20,6 @@
from ..device_base import DeviceBase, DeviceCfg


@dataclass
class Se3KeyboardCfg(DeviceCfg):
"""Configuration for SE3 keyboard devices."""

gripper_term: bool = True
pos_sensitivity: float = 0.4
rot_sensitivity: float = 0.8
retargeters: None = None


class Se3Keyboard(DeviceBase):
"""A keyboard controller for sending SE(3) commands as delta poses and binary command (open/close).

Expand Down Expand Up @@ -206,3 +198,14 @@ def _create_key_bindings(self):
"C": np.asarray([0.0, 0.0, 1.0]) * self.rot_sensitivity,
"V": np.asarray([0.0, 0.0, -1.0]) * self.rot_sensitivity,
}


@dataclass
class Se3KeyboardCfg(DeviceCfg):
"""Configuration for SE3 keyboard devices."""

gripper_term: bool = True
pos_sensitivity: float = 0.4
rot_sensitivity: float = 0.8
retargeters: None = None
device_type: type[DeviceBase] = Se3Keyboard
17 changes: 10 additions & 7 deletions source/isaaclab/isaaclab/devices/openxr/manus_vive.py
Original file line number Diff line number Diff line change
Expand Up @@ -7,6 +7,8 @@
Manus and Vive for teleoperation and interaction.
"""

from __future__ import annotations

import contextlib
import numpy as np
from collections.abc import Callable
Expand Down Expand Up @@ -34,13 +36,6 @@
from .manus_vive_utils import HAND_JOINT_MAP, ManusViveIntegration


@dataclass
class ManusViveCfg(DeviceCfg):
"""Configuration for Manus and Vive."""

xr_cfg: XrCfg | None = None


class ManusVive(DeviceBase):
"""Manus gloves and Vive trackers for teleoperation and interaction.

Expand Down Expand Up @@ -246,3 +241,11 @@ def _on_teleop_command(self, event: carb.events.IEvent):
elif "reset" in msg:
if "RESET" in self._additional_callbacks:
self._additional_callbacks["RESET"]()


@dataclass
class ManusViveCfg(DeviceCfg):
"""Configuration for Manus and Vive."""

xr_cfg: XrCfg | None = None
device_type: type[DeviceBase] = ManusVive
18 changes: 11 additions & 7 deletions source/isaaclab/isaaclab/devices/openxr/openxr_device.py
Original file line number Diff line number Diff line change
Expand Up @@ -5,6 +5,8 @@

"""OpenXR-powered device for teleoperation and interaction."""

from __future__ import annotations

import contextlib
import numpy as np
from collections.abc import Callable
Expand All @@ -26,14 +28,8 @@

with contextlib.suppress(ModuleNotFoundError):
from omni.kit.xr.core import XRCore, XRPoseValidityFlags
from isaacsim.core.prims import SingleXFormPrim


@dataclass
class OpenXRDeviceCfg(DeviceCfg):
"""Configuration for OpenXR devices."""

xr_cfg: XrCfg | None = None
from isaacsim.core.prims import SingleXFormPrim


class OpenXRDevice(DeviceBase):
Expand Down Expand Up @@ -303,3 +299,11 @@ def _on_teleop_command(self, event: carb.events.IEvent):
elif "reset" in msg:
if "RESET" in self._additional_callbacks:
self._additional_callbacks["RESET"]()


@dataclass
class OpenXRDeviceCfg(DeviceCfg):
"""Configuration for OpenXR devices."""

xr_cfg: XrCfg | None = None
device_type: type[DeviceBase] = OpenXRDevice

This file was deleted.

Original file line number Diff line number Diff line change
Expand Up @@ -3,6 +3,8 @@
#
# SPDX-License-Identifier: BSD-3-Clause

from __future__ import annotations

import contextlib
import numpy as np
import torch
Expand All @@ -19,15 +21,6 @@
from .gr1_t2_dex_retargeting_utils import GR1TR2DexRetargeting


@dataclass
class GR1T2RetargeterCfg(RetargeterCfg):
"""Configuration for the GR1T2 retargeter."""

enable_visualization: bool = False
num_open_xr_hand_joints: int = 100
hand_joint_names: list[str] | None = None # List of robot hand joint names


class GR1T2Retargeter(RetargeterBase):
"""Retargets OpenXR hand tracking data to GR1T2 hand end-effector commands.

Expand Down Expand Up @@ -156,3 +149,13 @@ def _retarget_abs(self, wrist: np.ndarray) -> np.ndarray:
usd_right_roll_link_in_world_quat = PoseUtils.quat_from_matrix(usd_right_roll_link_in_world_mat)

return np.concatenate([usd_right_roll_link_in_world_pos, usd_right_roll_link_in_world_quat])


@dataclass
class GR1T2RetargeterCfg(RetargeterCfg):
"""Configuration for the GR1T2 retargeter."""

enable_visualization: bool = False
num_open_xr_hand_joints: int = 100
hand_joint_names: list[str] | None = None # List of robot hand joint names
retargeter_type: type[RetargeterBase] = GR1T2Retargeter
Loading
Loading