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
1 change: 1 addition & 0 deletions CONTRIBUTORS.md
Original file line number Diff line number Diff line change
Expand Up @@ -72,6 +72,7 @@ Guidelines for modifications:
* HoJin Jeon
* Hongwei Xiong
* Hongyu Li
* Hougant Chen
* Huihua Zhao
* Iretiayo Akinola
* Jack Zeng
Expand Down
8 changes: 4 additions & 4 deletions docs/source/how-to/cloudxr_teleoperation.rst
Original file line number Diff line number Diff line change
Expand Up @@ -721,11 +721,11 @@ Here's an example of setting up hand tracking:

# Create retargeters
position_retargeter = Se3AbsRetargeter(
bound_hand=OpenXRDevice.TrackingTarget.HAND_RIGHT,
bound_hand=DeviceBase.TrackingTarget.HAND_RIGHT,
zero_out_xy_rotation=True,
use_wrist_position=False # Use pinch position (thumb-index midpoint) instead of wrist
)
gripper_retargeter = GripperRetargeter(bound_hand=OpenXRDevice.TrackingTarget.HAND_RIGHT)
gripper_retargeter = GripperRetargeter(bound_hand=DeviceBase.TrackingTarget.HAND_RIGHT)

# Create OpenXR device with hand tracking and both retargeters
device = OpenXRDevice(
Expand Down Expand Up @@ -919,15 +919,15 @@ The retargeting system is designed to be extensible. You can create custom retar
Any: The transformed control commands for the robot.
"""
# Access hand tracking data using TrackingTarget enum
right_hand_data = data[OpenXRDevice.TrackingTarget.HAND_RIGHT]
right_hand_data = data[DeviceBase.TrackingTarget.HAND_RIGHT]

# Extract specific joint positions and orientations
wrist_pose = right_hand_data.get("wrist")
thumb_tip_pose = right_hand_data.get("thumb_tip")
index_tip_pose = right_hand_data.get("index_tip")

# Access head tracking data
head_pose = data[OpenXRDevice.TrackingTarget.HEAD]
head_pose = data[DeviceBase.TrackingTarget.HEAD]

# Process the tracking data and apply your custom logic
# ...
Expand Down
15 changes: 9 additions & 6 deletions scripts/environments/teleoperation/teleop_se3_agent.py
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,11 @@
#
# SPDX-License-Identifier: BSD-3-Clause

"""Script to run a keyboard teleoperation with Isaac Lab manipulation environments."""
"""Script to run teleoperation with Isaac Lab manipulation environments.

Supports multiple input devices (e.g., keyboard, spacemouse, gamepad) and devices
configured within the environment (including OpenXR-based hand tracking or motion
controllers)."""

"""Launch Isaac Sim Simulator first."""

Expand All @@ -13,7 +17,7 @@
from isaaclab.app import AppLauncher

# add argparse arguments
parser = argparse.ArgumentParser(description="Keyboard teleoperation for Isaac Lab environments.")
parser = argparse.ArgumentParser(description="Teleoperation for Isaac Lab environments.")
parser.add_argument("--num_envs", type=int, default=1, help="Number of environments to simulate.")
parser.add_argument(
"--teleop_device",
Expand Down Expand Up @@ -78,7 +82,7 @@

def main() -> None:
"""
Run keyboard teleoperation with Isaac Lab manipulation environment.
Run teleoperation with an Isaac Lab manipulation environment.

Creates the environment, sets up teleoperation interfaces and callbacks,
and runs the main simulation loop until the application is closed.
Expand All @@ -98,8 +102,6 @@ def main() -> None:
env_cfg.terminations.object_reached_goal = DoneTerm(func=mdp.object_reached_goal)

if args_cli.xr:
# External cameras are not supported with XR teleop
# Check for any camera configs and disable them
env_cfg = remove_camera_configs(env_cfg)
env_cfg.sim.render.antialiasing_mode = "DLSS"

Expand Down Expand Up @@ -204,7 +206,7 @@ def stop_teleoperation() -> None:
)
else:
logger.error(f"Unsupported teleop device: {args_cli.teleop_device}")
logger.error("Supported devices: keyboard, spacemouse, gamepad, handtracking")
logger.error("Configure the teleop device in the environment config.")
env.close()
simulation_app.close()
return
Expand Down Expand Up @@ -254,6 +256,7 @@ def stop_teleoperation() -> None:

if should_reset_recording_instance:
env.reset()
teleop_interface.reset()
should_reset_recording_instance = False
print("Environment reset complete")
except Exception as e:
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.48.3"
version = "0.48.4"

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

0.48.4 (2025-11-13)
~~~~~~~~~~~~~~~~~~~

Added
^^^^^

* Added OpenXR motion controller support for the G1 robot locomanipulation environment
``Isaac-PickPlace-Locomanipulation-G1-Abs-v0``. This enables teleoperation using XR motion controllers
in addition to hand tracking.
* Added :class:`OpenXRDeviceMotionController` for motion controller-based teleoperation with headset anchoring control.
* Added motion controller-specific retargeters:
* :class:`G1TriHandControllerUpperBodyRetargeterCfg` for upper body and hand control using motion controllers.
* :class:`G1LowerBodyStandingControllerRetargeterCfg` for lower body control using motion controllers.


0.48.3 (2025-11-13)
~~~~~~~~~~~~~~~~~~~

Expand Down
36 changes: 35 additions & 1 deletion source/isaaclab/isaaclab/devices/device_base.py
Original file line number Diff line number Diff line change
Expand Up @@ -9,6 +9,7 @@
from abc import ABC, abstractmethod
from collections.abc import Callable
from dataclasses import dataclass, field
from enum import Enum
from typing import Any

from isaaclab.devices.retargeter_base import RetargeterBase, RetargeterCfg
Expand Down Expand Up @@ -58,9 +59,13 @@ def __init__(self, retargeters: list[RetargeterBase] | None = None):
"""
# Initialize empty list if None is provided
self._retargeters = retargeters or []
# Aggregate required features across all retargeters
self._required_features = set()
for retargeter in self._retargeters:
self._required_features.update(retargeter.get_requirements())

def __str__(self) -> str:
"""Returns: A string containing the information of joystick."""
"""Returns: A string identifier for the device."""
return f"{self.__class__.__name__}"

"""
Expand Down Expand Up @@ -123,3 +128,32 @@ def advance(self) -> torch.Tensor:
# With multiple retargeters, return a tuple of outputs
# Concatenate retargeted outputs into a single tensor
return torch.cat([retargeter.retarget(raw_data) for retargeter in self._retargeters], dim=-1)

# -----------------------------
# Shared data layout helpers (for retargeters across devices)
# -----------------------------
class TrackingTarget(Enum):
"""Standard tracking targets shared across devices."""

HAND_LEFT = 0
HAND_RIGHT = 1
HEAD = 2
CONTROLLER_LEFT = 3
CONTROLLER_RIGHT = 4

class MotionControllerDataRowIndex(Enum):
"""Rows in the motion-controller 2x7 array."""

POSE = 0
INPUTS = 1

class MotionControllerInputIndex(Enum):
"""Indices in the motion-controller input row."""

THUMBSTICK_X = 0
THUMBSTICK_Y = 1
TRIGGER = 2
SQUEEZE = 3
BUTTON_0 = 4
BUTTON_1 = 5
PADDING = 6
2 changes: 1 addition & 1 deletion source/isaaclab/isaaclab/devices/openxr/__init__.py
Original file line number Diff line number Diff line change
Expand Up @@ -7,4 +7,4 @@

from .manus_vive import ManusVive, ManusViveCfg
from .openxr_device import OpenXRDevice, OpenXRDeviceCfg
from .xr_cfg import XrCfg, remove_camera_configs
from .xr_cfg import XrAnchorRotationMode, XrCfg, remove_camera_configs
15 changes: 3 additions & 12 deletions source/isaaclab/isaaclab/devices/openxr/manus_vive.py
Original file line number Diff line number Diff line change
Expand Up @@ -13,7 +13,6 @@
import numpy as np
from collections.abc import Callable
from dataclasses import dataclass
from enum import Enum

import carb
from isaacsim.core.version import get_version
Expand All @@ -22,7 +21,6 @@
from isaaclab.devices.retargeter_base import RetargeterBase

from ..device_base import DeviceBase, DeviceCfg
from .openxr_device import OpenXRDevice
from .xr_cfg import XrCfg

# For testing purposes, we need to mock the XRCore
Expand Down Expand Up @@ -61,13 +59,6 @@ class ManusVive(DeviceBase):
data is transformed into robot control commands suitable for teleoperation.
"""

class TrackingTarget(Enum):
"""Enum class specifying what to track with Manus+Vive. Consistent with :class:`OpenXRDevice.TrackingTarget`."""

HAND_LEFT = 0
HAND_RIGHT = 1
HEAD = 2

TELEOP_COMMAND_EVENT_TYPE = "teleop_command"

def __init__(self, cfg: ManusViveCfg, retargeters: list[RetargeterBase] | None = None):
Expand Down Expand Up @@ -192,9 +183,9 @@ def _get_raw_data(self) -> dict:
joint_name = HAND_JOINT_MAP[int(index)]
result[hand][joint_name] = np.array(pose["position"] + pose["orientation"], dtype=np.float32)
return {
OpenXRDevice.TrackingTarget.HAND_LEFT: result["left"],
OpenXRDevice.TrackingTarget.HAND_RIGHT: result["right"],
OpenXRDevice.TrackingTarget.HEAD: self._calculate_headpose(),
DeviceBase.TrackingTarget.HAND_LEFT: result["left"],
DeviceBase.TrackingTarget.HAND_RIGHT: result["right"],
DeviceBase.TrackingTarget.HEAD: self._calculate_headpose(),
}

def _calculate_headpose(self) -> np.ndarray:
Expand Down
Loading
Loading