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
32 changes: 27 additions & 5 deletions docs/source/how-to/cloudxr_teleoperation.rst
Original file line number Diff line number Diff line change
Expand Up @@ -419,6 +419,20 @@ Requires Isaac Sim 5.1 or later.

Run the teleoperation example with Manus + Vive tracking:

.. dropdown:: Installation instructions
:open:

The Manus integration is provided through the Isaac Sim teleoperation input plugin framework.
Install the plugin by following the build and installation steps in `isaac-teleop-device-plugins <https://github.com/isaac-sim/isaac-teleop-device-plugins>`_.

In the same terminal from which you will launch Isaac Lab, set:

.. code-block:: bash

export ISAACSIM_HANDTRACKER_LIB=<path to isaac-teleop-device-plugins>/build-manus-default/lib/libIsaacSimManusHandTracking.so

Once the plugin is installed, run the teleoperation example:

.. code-block:: bash

./isaaclab.sh -p scripts/environments/teleoperation/teleop_se3_agent.py \
Expand All @@ -427,20 +441,28 @@ Run the teleoperation example with Manus + Vive tracking:
--xr \
--enable_pinocchio

Begin the session with your palms facing up.
This is necessary for calibrating Vive tracker poses using Apple Vision Pro wrist poses from a few initial frames,
as the Vive trackers attached to the back of the hands occlude the optical hand tracking.
The recommended workflow, is to start Isaac Lab, click **Start AR**, and then put on the Manus gloves, vive trackers, and
headset. Once you are ready to begin the session, use voice commands to launch the Isaac XR teleop sample client and
connect to Isaac Lab.

Isaac Lab automatically calibrates the Vive trackers using wrist pose data from the Apple Vision Pro during the initial
frames of the session. If calibration fails, for example, if the red dots do not accurately follow the teleoperator's
hands, restart Isaac Lab and begin with your hands in a palm-up position to improve calibration reliability.

For optimal performance, position the lighthouse above the hands, tilted slightly downward.
One lighthouse is sufficient if both hands are visible.
Ensure the lighthouse remains stable; a stand is recommended to prevent wobbling.

Ensure that while the task is being teleoperated, the hands remain stable and visible to the lighthouse at all times.
See: `Installing the Base Stations <https://www.vive.com/us/support/vive/category_howto/installing-the-base-stations.html>`_
and `Tips for Setting Up the Base Stations <https://www.vive.com/us/support/vive/category_howto/tips-for-setting-up-the-base-stations.html>`_

.. note::

To avoid resource contention and crashes, ensure Manus and Vive devices are connected to different USB controllers/buses.
Use ``lsusb -t`` to identify different buses and connect devices accordingly.

Vive trackers are automatically calculated to map to the left and right wrist joints.
Vive trackers are automatically calculated to map to the left and right wrist joints obtained from a stable
OpenXR hand tracking wrist pose.
This auto-mapping calculation supports up to 2 Vive trackers;
if more than 2 Vive trackers are detected, it uses the first two trackers detected for calibration, which may not be correct.

Expand Down
7 changes: 7 additions & 0 deletions source/isaaclab/isaaclab/devices/openxr/manus_vive.py
Original file line number Diff line number Diff line change
Expand Up @@ -98,6 +98,8 @@ def __init__(self, cfg: ManusViveCfg, retargeters: list[RetargeterBase] | None =
)
)
self._manus_vive = ManusViveIntegration()
# Only start calibration on the first START selection
self._calibration_started = False

# Initialize dictionaries instead of arrays
default_pose = np.array([0, 0, 0, 1, 0, 0, 0], dtype=np.float32)
Expand Down Expand Up @@ -240,9 +242,14 @@ def _on_teleop_command(self, event: carb.events.IEvent):
if "start" in msg:
if "START" in self._additional_callbacks:
self._additional_callbacks["START"]()
# Begin calibration only the first time START is selected
if not self._calibration_started:
self._manus_vive.enable_calibration(reset=True)
self._calibration_started = True
elif "stop" in msg:
if "STOP" in self._additional_callbacks:
self._additional_callbacks["STOP"]()
elif "reset" in msg:
if "RESET" in self._additional_callbacks:
self._additional_callbacks["RESET"]()
self._manus_vive.enable_calibration(reset=True)
93 changes: 91 additions & 2 deletions source/isaaclab/isaaclab/devices/openxr/manus_vive_utils.py
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,7 @@
# SPDX-License-Identifier: BSD-3-Clause

import contextlib
from typing import Optional
import numpy as np
from time import time

Expand All @@ -18,6 +19,9 @@

from pxr import Gf

import isaaclab.sim as sim_utils
from isaaclab.markers import VisualizationMarkers, VisualizationMarkersCfg

# Mapping from Manus joint index (0-24) to joint name. Palm (25) is calculated from middle metacarpal and proximal.
HAND_JOINT_MAP = {
# Wrist
Expand Down Expand Up @@ -68,6 +72,8 @@ def __init__(self):
self.default_pose = {"position": [0, 0, 0], "orientation": [1, 0, 0, 0]}
# 90-degree ccw rotation on Y-axis and 90-degree ccw rotation on Z-axis
self.rot_adjust = Gf.Matrix3d().SetRotate(Gf.Quatd(0.5, Gf.Vec3d(-0.5, 0.5, 0.5)))
# Calibration gating: do not start until explicitly enabled by device "START"
self._calibration_enabled = False
self.scene_T_lighthouse_static = None
self._vive_left_id = None
self._vive_right_id = None
Expand All @@ -78,6 +84,65 @@ def __init__(self):
self._pairB_trans_errs = []
self._pairB_rot_errs = []

# Visualization for OpenXR wrist samples during calibration
self._viz_markers: Optional[VisualizationMarkers] = None
self._viz_positions = [] # list[list[float]] of sampled OpenXR wrist translations
self._viz_max_points = 500

def _ensure_viz_markers(self):
if self._viz_markers is None:
marker_cfg = VisualizationMarkersCfg(
prim_path="/Visuals/openxr_calibration_markers",
markers={
"xr_sample": sim_utils.SphereCfg(
radius=0.0075,
visual_material=sim_utils.PreviewSurfaceCfg(diffuse_color=(0.0, 1.0, 0.0)),
)
},
)
self._viz_markers = VisualizationMarkers(marker_cfg)
self._viz_markers.set_visibility(True)

def _update_viz_markers(self, L: Gf.Matrix4d | None, R: Gf.Matrix4d | None):
if not self._calibration_enabled or self.scene_T_lighthouse_static is not None:
return
self._ensure_viz_markers()
markers = self._viz_markers
if markers is None:
return
# Append current frame OpenXR wrist translations (in stage frame as provided by XR)
if L is not None:
t = L.ExtractTranslation()
self._viz_positions.append([float(t[0]), float(t[1]), float(t[2])])
if R is not None:
t = R.ExtractTranslation()
self._viz_positions.append([float(t[0]), float(t[1]), float(t[2])])
# Truncate to max points for performance
if len(self._viz_positions) > self._viz_max_points:
self._viz_positions = self._viz_positions[-self._viz_max_points :]
# Update markers in the viewport
import numpy as _np

translations = _np.asarray(self._viz_positions, dtype=_np.float32)
# When empty, pass explicit empty indices to allow clearing
if translations.shape[0] == 0:
markers.visualize(translations=_np.zeros((0, 3), dtype=_np.float32), marker_indices=[])
else:
markers.visualize(translations=translations)

def _reset_viz_markers(self):
self._viz_positions = []
markers = self._viz_markers
if markers is not None:
markers.set_visibility(True)
import numpy as _np

markers.visualize(translations=_np.zeros((0, 3), dtype=_np.float32), marker_indices=[])

def _hide_viz_markers(self):
if self._viz_markers is not None:
self._viz_markers.set_visibility(False)

def get_all_device_data(self) -> dict:
"""Get all tracked device data in scene coordinates.

Expand Down Expand Up @@ -141,11 +206,30 @@ def update_vive(self):
self.device_status["vive_trackers"]["last_data_time"] = time()
try:
# Initialize coordinate transformation from first Vive wrist position
if self.scene_T_lighthouse_static is None:
if self.scene_T_lighthouse_static is None and self._calibration_enabled:
self._initialize_coordinate_transformation()
except Exception as e:
omni.log.error(f"Vive tracker update failed: {e}")

def enable_calibration(self, reset: bool = True):
"""Enable the wrist calibration process, optionally resetting accumulated samples.

Args:
reset: When True, clears previous calibration state and samples before enabling.
"""
self._calibration_enabled = True
if reset:
self.scene_T_lighthouse_static = None
self._vive_left_id = None
self._vive_right_id = None
self._pairA_candidates.clear()
self._pairB_candidates.clear()
self._pairA_trans_errs.clear()
self._pairA_rot_errs.clear()
self._pairB_trans_errs.clear()
self._pairB_rot_errs.clear()
self._reset_viz_markers()

def _initialize_coordinate_transformation(self):
"""
Initialize the scene to lighthouse coordinate transformation.
Expand All @@ -169,6 +253,9 @@ def _initialize_coordinate_transformation(self):
gloves.append("right")
R = get_openxr_wrist_matrix("right")

# Update visualization with current OpenXR wrist samples
self._update_viz_markers(L, R)

M0, M1, vives = None, None, []
if wm0_id is not None:
vives.append(wm0_id)
Expand Down Expand Up @@ -243,6 +330,8 @@ def _initialize_coordinate_transformation(self):
f"Wrist calibration computed. Resolved mapping: {self._vive_left_id}->Left,"
f" {self._vive_right_id}->Right"
)
# Hide visualization markers once calibration completes
self._hide_viz_markers()

except Exception as e:
omni.log.error(f"Failed to initialize coordinate transformation: {e}")
Expand Down Expand Up @@ -437,7 +526,7 @@ def get_openxr_wrist_matrix(hand: str) -> Gf.Matrix4d:
return None


def get_vive_wrist_ids(vive_data: dict) -> tuple[str, str]:
def get_vive_wrist_ids(vive_data: dict) -> tuple[str | None, str | None]:
"""Get the Vive wrist tracker IDs if available.

Args:
Expand Down
Loading