Commit 5ecd53bd authored by rwiltz's avatar rwiltz Committed by Kelly Guo

Adds support for head pose for Open XR device (#340)

Small refactor to add headpose to the openxr device

<!-- As a practice, it is recommended to open an issue to have
discussions on the proposed pull request.
This makes it easier for the community to keep track of what is being
developed or added, and if a given feature
is demanded by more than one party. -->

<!-- As you go through the list, delete the ones that are not
applicable. -->

- Bug fix (non-breaking change which fixes an issue)
- New feature (non-breaking change which adds functionality)

Please attach before and after screenshots of the change if applicable.

<!--
Example:

| Before | After |
| ------ | ----- |
| _gif/png before_ | _gif/png after_ |

To upload images to a PR -- simply drag and drop an image while in edit
mode and it should upload the image directly. You can then paste that
source into the above before/after sections.
-->

- [x] I have run the [`pre-commit` checks](https://pre-commit.com/) with
`./isaaclab.sh --format`
- [x] I have made corresponding changes to the documentation
- [x] My changes generate no new warnings
- [x] I have added tests that prove my fix is effective or that my
feature works
- [x] I have updated the changelog and the corresponding version in the
extension's `config/extension.toml` file
- [x] I have added my name to the `CONTRIBUTORS.md` or my name already
exists there

<!--
As you go through the checklist above, you can mark something as done by
putting an x character in it

For example,
- [x] I have done this task
- [ ] I have not done this task
-->

---------
Signed-off-by: 's avatarKelly Guo <kellyguo123@hotmail.com>
Co-authored-by: 's avatarKelly Guo <kellyg@nvidia.com>
parent c84bb924
...@@ -529,15 +529,15 @@ Here's an example of setting up hand tracking: ...@@ -529,15 +529,15 @@ Here's an example of setting up hand tracking:
# Create retargeters # Create retargeters
position_retargeter = Se3AbsRetargeter( position_retargeter = Se3AbsRetargeter(
bound_hand=OpenXRDevice.TrackingTarget.HAND_RIGHT,
zero_out_xy_rotation=True, zero_out_xy_rotation=True,
use_wrist_position=False # Use pinch position (thumb-index midpoint) instead of wrist use_wrist_position=False # Use pinch position (thumb-index midpoint) instead of wrist
) )
gripper_retargeter = GripperRetargeter() gripper_retargeter = GripperRetargeter(bound_hand=OpenXRDevice.TrackingTarget.HAND_RIGHT)
# Create OpenXR device with hand tracking and both retargeters # Create OpenXR device with hand tracking and both retargeters
device = OpenXRDevice( device = OpenXRDevice(
env_cfg.xr, env_cfg.xr,
hand=OpenXRDevice.Hand.RIGHT,
retargeters=[position_retargeter, gripper_retargeter], retargeters=[position_retargeter, gripper_retargeter],
) )
...@@ -565,9 +565,21 @@ processes the incoming tracking data: ...@@ -565,9 +565,21 @@ processes the incoming tracking data:
.. code-block:: python .. code-block:: python
from isaaclab.devices.retargeter_base import RetargeterBase from isaaclab.devices.retargeter_base import RetargeterBase
from isaaclab.devices import OpenXRDevice
class MyCustomRetargeter(RetargeterBase): class MyCustomRetargeter(RetargeterBase):
def retarget(self, data: dict[str, np.ndarray]) -> Any: def retarget(self, data: dict)-> Any:
# Access hand tracking data using TrackingTarget enum
right_hand_data = data[OpenXRDevice.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]
# Process the tracking data # Process the tracking data
# Return control commands in appropriate format # Return control commands in appropriate format
... ...
......
...@@ -205,7 +205,6 @@ def main(): ...@@ -205,7 +205,6 @@ def main():
# Create hand tracking device with retargeter # Create hand tracking device with retargeter
teleop_interface = OpenXRDevice( teleop_interface = OpenXRDevice(
env_cfg.xr, env_cfg.xr,
hand=OpenXRDevice.Hand.BOTH,
retargeters=[gr1t2_retargeter], retargeters=[gr1t2_retargeter],
) )
teleop_interface.add_callback("RESET", reset_recording_instance) teleop_interface.add_callback("RESET", reset_recording_instance)
...@@ -218,16 +217,19 @@ def main(): ...@@ -218,16 +217,19 @@ def main():
elif "handtracking" in args_cli.teleop_device.lower(): elif "handtracking" in args_cli.teleop_device.lower():
# Create EE retargeter with desired configuration # Create EE retargeter with desired configuration
if "_abs" in args_cli.teleop_device.lower(): if "_abs" in args_cli.teleop_device.lower():
retargeter_device = Se3AbsRetargeter(zero_out_xy_rotation=True) retargeter_device = Se3AbsRetargeter(
bound_hand=OpenXRDevice.TrackingTarget.HAND_RIGHT, zero_out_xy_rotation=True
)
else: else:
retargeter_device = Se3RelRetargeter(zero_out_xy_rotation=True) retargeter_device = Se3RelRetargeter(
bound_hand=OpenXRDevice.TrackingTarget.HAND_RIGHT, zero_out_xy_rotation=True
)
grip_retargeter = GripperRetargeter() grip_retargeter = GripperRetargeter(bound_hand=OpenXRDevice.TrackingTarget.HAND_RIGHT)
# Create hand tracking device with retargeter (in a list) # Create hand tracking device with retargeter (in a list)
teleop_interface = OpenXRDevice( teleop_interface = OpenXRDevice(
env_cfg.xr, env_cfg.xr,
hand=OpenXRDevice.Hand.RIGHT,
retargeters=[retargeter_device, grip_retargeter], retargeters=[retargeter_device, grip_retargeter],
) )
teleop_interface.add_callback("RESET", reset_recording_instance) teleop_interface.add_callback("RESET", reset_recording_instance)
......
...@@ -301,7 +301,6 @@ def main(): ...@@ -301,7 +301,6 @@ def main():
# Create hand tracking device with retargeter # Create hand tracking device with retargeter
device = OpenXRDevice( device = OpenXRDevice(
env_cfg.xr, env_cfg.xr,
hand=OpenXRDevice.Hand.BOTH,
retargeters=[gr1t2_retargeter], retargeters=[gr1t2_retargeter],
) )
device.add_callback("RESET", reset_recording_instance) device.add_callback("RESET", reset_recording_instance)
...@@ -313,16 +312,19 @@ def main(): ...@@ -313,16 +312,19 @@ def main():
elif "handtracking" in device_name: elif "handtracking" in device_name:
# Create Franka retargeter with desired configuration # Create Franka retargeter with desired configuration
if "_abs" in device_name: if "_abs" in device_name:
retargeter_device = Se3AbsRetargeter(zero_out_xy_rotation=True) retargeter_device = Se3AbsRetargeter(
bound_hand=OpenXRDevice.TrackingTarget.HAND_RIGHT, zero_out_xy_rotation=True
)
else: else:
retargeter_device = Se3RelRetargeter(zero_out_xy_rotation=True) retargeter_device = Se3RelRetargeter(
bound_hand=OpenXRDevice.TrackingTarget.HAND_RIGHT, zero_out_xy_rotation=True
)
grip_retargeter = GripperRetargeter() grip_retargeter = GripperRetargeter(bound_hand=OpenXRDevice.TrackingTarget.HAND_RIGHT)
# Create hand tracking device with retargeter (in a list) # Create hand tracking device with retargeter (in a list)
device = OpenXRDevice( device = OpenXRDevice(
env_cfg.xr, env_cfg.xr,
hand=OpenXRDevice.Hand.RIGHT,
retargeters=[retargeter_device, grip_retargeter], retargeters=[retargeter_device, grip_retargeter],
) )
device.add_callback("RESET", reset_recording_instance) device.add_callback("RESET", reset_recording_instance)
......
[package] [package]
# Note: Semantic Versioning is used: https://semver.org/ # Note: Semantic Versioning is used: https://semver.org/
version = "0.36.15" version = "0.36.16"
# Description # Description
title = "Isaac Lab framework for Robot Learning" title = "Isaac Lab framework for Robot Learning"
......
Changelog Changelog
--------- ---------
0.36.15 (2025-04-09) 0.36.16 (2025-04-09)
~~~~~~~~~~~~~~~~~~~~ ~~~~~~~~~~~~~~~~~~~~
Changed Changed
...@@ -12,7 +12,7 @@ Changed ...@@ -12,7 +12,7 @@ Changed
the cuda device, which results in NCCL errors on distributed setups. the cuda device, which results in NCCL errors on distributed setups.
0.36.14 (2025-04-01) 0.36.15 (2025-04-01)
~~~~~~~~~~~~~~~~~~~~ ~~~~~~~~~~~~~~~~~~~~
Fixed Fixed
...@@ -21,7 +21,7 @@ Fixed ...@@ -21,7 +21,7 @@ Fixed
* Added check in RecorderManager to ensure that the success indicator is only set if the termination manager is present. * Added check in RecorderManager to ensure that the success indicator is only set if the termination manager is present.
0.36.13 (2025-03-24) 0.36.14 (2025-03-24)
~~~~~~~~~~~~~~~~~~~~ ~~~~~~~~~~~~~~~~~~~~
Changed Changed
...@@ -31,6 +31,15 @@ Changed ...@@ -31,6 +31,15 @@ Changed
the default settings will be used from the experience files and the double definition is removed. the default settings will be used from the experience files and the double definition is removed.
0.36.13 (2025-03-24)
~~~~~~~~~~~~~~~~~~~~
Added
^^^^^
* Added headpose support to OpenXRDevice.
0.36.12 (2025-03-19) 0.36.12 (2025-03-19)
~~~~~~~~~~~~~~~~~~~~ ~~~~~~~~~~~~~~~~~~~~
......
...@@ -44,44 +44,41 @@ class OpenXRDevice(DeviceBase): ...@@ -44,44 +44,41 @@ class OpenXRDevice(DeviceBase):
* "STOP": Pause hand tracking data flow * "STOP": Pause hand tracking data flow
* "RESET": Reset the tracking and signal simulation reset * "RESET": Reset the tracking and signal simulation reset
The device can track either the left hand, right hand, or both hands simultaneously based on The device can track the left hand, right hand, head position, or any combination of these
the Hand enum value passed to the constructor. When retargeters are provided, the raw joint based on the TrackingTarget enum values. When retargeters are provided, the raw tracking
poses are transformed into robot control commands suitable for teleoperation. data is transformed into robot control commands suitable for teleoperation.
""" """
class Hand(Enum): class TrackingTarget(Enum):
"""Enum class specifying which hand(s) to track with OpenXR. """Enum class specifying what to track with OpenXR.
Attributes: Attributes:
LEFT: Track only the left hand HAND_LEFT: Track the left hand (index 0 in _get_raw_data output)
RIGHT: Track only the right hand HAND_RIGHT: Track the right hand (index 1 in _get_raw_data output)
BOTH: Track both hands simultaneously HEAD: Track the head/headset position (index 2 in _get_raw_data output)
""" """
LEFT = 0 HAND_LEFT = 0
RIGHT = 1 HAND_RIGHT = 1
BOTH = 2 HEAD = 2
TELEOP_COMMAND_EVENT_TYPE = "teleop_command" TELEOP_COMMAND_EVENT_TYPE = "teleop_command"
def __init__( def __init__(
self, self,
xr_cfg: XrCfg | None, xr_cfg: XrCfg | None,
hand: Hand,
retargeters: list[RetargeterBase] | None = None, retargeters: list[RetargeterBase] | None = None,
): ):
"""Initialize the hand tracking device. """Initialize the OpenXR device.
Args: Args:
xr_cfg: Configuration object for OpenXR settings. If None, default settings are used. xr_cfg: Configuration object for OpenXR settings. If None, default settings are used.
hand: Which hand(s) to track (LEFT, RIGHT, or BOTH) retargeters: List of retargeters to transform tracking data into robot commands.
retargeters: List of retargeters to transform hand tracking data into robot commands. If None or empty list, raw tracking data will be returned.
If None or empty list, raw joint poses will be returned.
""" """
super().__init__(retargeters) super().__init__(retargeters)
self._openxr = OpenXR() self._openxr = OpenXR()
self._xr_cfg = xr_cfg or XrCfg() self._xr_cfg = xr_cfg or XrCfg()
self._hand = hand
self._additional_callbacks = dict() self._additional_callbacks = dict()
self._vc_subscription = ( self._vc_subscription = (
XRCore.get_singleton() XRCore.get_singleton()
...@@ -92,6 +89,7 @@ class OpenXRDevice(DeviceBase): ...@@ -92,6 +89,7 @@ class OpenXRDevice(DeviceBase):
) )
self._previous_joint_poses_left = np.full((26, 7), [0, 0, 0, 1, 0, 0, 0], dtype=np.float32) self._previous_joint_poses_left = np.full((26, 7), [0, 0, 0, 1, 0, 0, 0], dtype=np.float32)
self._previous_joint_poses_right = np.full((26, 7), [0, 0, 0, 1, 0, 0, 0], dtype=np.float32) self._previous_joint_poses_right = np.full((26, 7), [0, 0, 0, 1, 0, 0, 0], dtype=np.float32)
self._previous_headpose = np.array([0, 0, 0, 1, 0, 0, 0], dtype=np.float32)
# Specify the placement of the simulation when viewed in an XR device using a prim. # Specify the placement of the simulation when viewed in an XR device using a prim.
xr_anchor = SingleXFormPrim("/XRAnchor", position=self._xr_cfg.anchor_pos, orientation=self._xr_cfg.anchor_rot) xr_anchor = SingleXFormPrim("/XRAnchor", position=self._xr_cfg.anchor_pos, orientation=self._xr_cfg.anchor_rot)
...@@ -118,10 +116,8 @@ class OpenXRDevice(DeviceBase): ...@@ -118,10 +116,8 @@ class OpenXRDevice(DeviceBase):
Returns: Returns:
Formatted string with device information Formatted string with device information
""" """
hand_str = "Both Hands" if self._hand == self.Hand.BOTH else f"{self._hand.name.title()} Hand"
msg = f"OpenXR Hand Tracking Device: {self.__class__.__name__}\n" msg = f"OpenXR Hand Tracking Device: {self.__class__.__name__}\n"
msg += f"\tTracking: {hand_str}\n"
msg += f"\tAnchor Position: {self._xr_cfg.anchor_pos}\n" msg += f"\tAnchor Position: {self._xr_cfg.anchor_pos}\n"
msg += f"\tAnchor Rotation: {self._xr_cfg.anchor_rot}\n" msg += f"\tAnchor Rotation: {self._xr_cfg.anchor_rot}\n"
...@@ -162,6 +158,7 @@ class OpenXRDevice(DeviceBase): ...@@ -162,6 +158,7 @@ class OpenXRDevice(DeviceBase):
def reset(self): def reset(self):
self._previous_joint_poses_left = np.full((26, 7), [0, 0, 0, 1, 0, 0, 0], dtype=np.float32) self._previous_joint_poses_left = np.full((26, 7), [0, 0, 0, 1, 0, 0, 0], dtype=np.float32)
self._previous_joint_poses_right = np.full((26, 7), [0, 0, 0, 1, 0, 0, 0], dtype=np.float32) self._previous_joint_poses_right = np.full((26, 7), [0, 0, 0, 1, 0, 0, 0], dtype=np.float32)
self._previous_headpose = np.array([0, 0, 0, 1, 0, 0, 0], dtype=np.float32)
def add_callback(self, key: str, func: Callable): def add_callback(self, key: str, func: Callable):
"""Add additional functions to bind to client messages. """Add additional functions to bind to client messages.
...@@ -174,27 +171,27 @@ class OpenXRDevice(DeviceBase): ...@@ -174,27 +171,27 @@ class OpenXRDevice(DeviceBase):
self._additional_callbacks[key] = func self._additional_callbacks[key] = func
def _get_raw_data(self) -> Any: def _get_raw_data(self) -> Any:
"""Get the latest hand tracking data. """Get the latest tracking data from the OpenXR runtime.
Returns: Returns:
Dictionary of joint poses Dictionary containing tracking data for:
- Left hand joint poses (26 joints with position and orientation)
- Right hand joint poses (26 joints with position and orientation)
- Head pose (position and orientation)
Each pose is represented as a 7-element array: [x, y, z, qw, qx, qy, qz]
where the first 3 elements are position and the last 4 are quaternion orientation.
""" """
if self._hand == self.Hand.LEFT:
hand_joints = self._openxr.locate_hand_joints(OpenXRSpec.XrHandEXT.XR_HAND_LEFT_EXT)
return self._calculate_joint_poses(hand_joints, self._previous_joint_poses_left)
elif self._hand == self.Hand.RIGHT:
hand_joints = self._openxr.locate_hand_joints(OpenXRSpec.XrHandEXT.XR_HAND_RIGHT_EXT)
return self._calculate_joint_poses(hand_joints, self._previous_joint_poses_right)
else:
return { return {
self.Hand.LEFT: self._calculate_joint_poses( self.TrackingTarget.HAND_LEFT: self._calculate_joint_poses(
self._openxr.locate_hand_joints(OpenXRSpec.XrHandEXT.XR_HAND_LEFT_EXT), self._openxr.locate_hand_joints(OpenXRSpec.XrHandEXT.XR_HAND_LEFT_EXT),
self._previous_joint_poses_left, self._previous_joint_poses_left,
), ),
self.Hand.RIGHT: self._calculate_joint_poses( self.TrackingTarget.HAND_RIGHT: self._calculate_joint_poses(
self._openxr.locate_hand_joints(OpenXRSpec.XrHandEXT.XR_HAND_RIGHT_EXT), self._openxr.locate_hand_joints(OpenXRSpec.XrHandEXT.XR_HAND_RIGHT_EXT),
self._previous_joint_poses_right, self._previous_joint_poses_right,
), ),
self.TrackingTarget.HEAD: self._calculate_headpose(),
} }
""" """
...@@ -221,6 +218,33 @@ class OpenXRDevice(DeviceBase): ...@@ -221,6 +218,33 @@ class OpenXRDevice(DeviceBase):
return self._joints_to_dict(previous_joint_poses) return self._joints_to_dict(previous_joint_poses)
def _calculate_headpose(self) -> np.ndarray:
"""Calculate the head pose from OpenXR.
Returns:
numpy.ndarray: 7-element array containing head position (xyz) and orientation (wxyz)
"""
head_device = XRCore.get_singleton().get_input_device("displayDevice")
if head_device:
hmd = head_device.get_virtual_world_pose("")
position = hmd.ExtractTranslation()
quat = hmd.ExtractRotationQuat()
quati = quat.GetImaginary()
quatw = quat.GetReal()
# Store in w, x, y, z order to match our convention
self._previous_headpose = np.array([
position[0],
position[1],
position[2],
quatw,
quati[0],
quati[1],
quati[2],
])
return self._previous_headpose
def _joints_to_dict(self, joint_data: np.ndarray) -> dict[str, np.ndarray]: def _joints_to_dict(self, joint_data: np.ndarray) -> dict[str, np.ndarray]:
"""Convert joint array to dictionary using standard joint names. """Convert joint array to dictionary using standard joint names.
......
...@@ -60,11 +60,11 @@ class GR1T2Retargeter(RetargeterBase): ...@@ -60,11 +60,11 @@ class GR1T2Retargeter(RetargeterBase):
) )
self._markers = VisualizationMarkers(marker_cfg) self._markers = VisualizationMarkers(marker_cfg)
def retarget(self, joint_poses: dict[str, np.ndarray]) -> tuple[np.ndarray, np.ndarray, np.ndarray]: def retarget(self, data: dict) -> tuple[np.ndarray, np.ndarray, np.ndarray]:
"""Convert hand joint poses to robot end-effector commands. """Convert hand joint poses to robot end-effector commands.
Args: Args:
joint_poses: Dictionary containing hand joint poses data: Dictionary mapping tracking targets to joint data dictionaries.
Returns: Returns:
tuple containing: tuple containing:
...@@ -74,8 +74,8 @@ class GR1T2Retargeter(RetargeterBase): ...@@ -74,8 +74,8 @@ class GR1T2Retargeter(RetargeterBase):
""" """
# Access the left and right hand data using the enum key # Access the left and right hand data using the enum key
left_hand_poses = joint_poses[OpenXRDevice.Hand.LEFT] left_hand_poses = data[OpenXRDevice.TrackingTarget.HAND_LEFT]
right_hand_poses = joint_poses[OpenXRDevice.Hand.RIGHT] right_hand_poses = data[OpenXRDevice.TrackingTarget.HAND_RIGHT]
left_wrist = left_hand_poses.get("wrist") left_wrist = left_hand_poses.get("wrist")
right_wrist = right_hand_poses.get("wrist") right_wrist = right_hand_poses.get("wrist")
......
...@@ -6,6 +6,7 @@ ...@@ -6,6 +6,7 @@
import numpy as np import numpy as np
from typing import Final from typing import Final
from isaaclab.devices import OpenXRDevice
from isaaclab.devices.retargeter_base import RetargeterBase from isaaclab.devices.retargeter_base import RetargeterBase
...@@ -27,24 +28,33 @@ class GripperRetargeter(RetargeterBase): ...@@ -27,24 +28,33 @@ class GripperRetargeter(RetargeterBase):
def __init__( def __init__(
self, self,
bound_hand: OpenXRDevice.TrackingTarget,
): ):
"""Initialize the gripper retargeter.""" """Initialize the gripper retargeter."""
# Store the hand to track
if bound_hand not in [OpenXRDevice.TrackingTarget.HAND_LEFT, OpenXRDevice.TrackingTarget.HAND_RIGHT]:
raise ValueError(
"bound_hand must be either OpenXRDevice.TrackingTarget.HAND_LEFT or"
" OpenXRDevice.TrackingTarget.HAND_RIGHT"
)
self.bound_hand = bound_hand
# Initialize gripper state # Initialize gripper state
self._previous_gripper_command = False self._previous_gripper_command = False
def retarget(self, data: dict[str, np.ndarray]) -> bool: def retarget(self, data: dict) -> bool:
"""Convert hand joint poses to gripper command. """Convert hand joint poses to gripper command.
Args: Args:
data: Dictionary mapping joint names to their pose data, data: Dictionary mapping tracking targets to joint data dictionaries.
joint names are defined in isaaclab.devices.openxr.common.HAND_JOINT_NAMES The joint names are defined in isaaclab.devices.openxr.common.HAND_JOINT_NAMES
Returns: Returns:
bool: Gripper command where True = close gripper, False = open gripper bool: Gripper command where True = close gripper, False = open gripper
""" """
# Extract key joint poses # Extract key joint poses
thumb_tip = data.get("thumb_tip") hand_data = data[self.bound_hand]
index_tip = data.get("index_tip") thumb_tip = hand_data["thumb_tip"]
index_tip = hand_data["index_tip"]
# Calculate gripper command with hysteresis # Calculate gripper command with hysteresis
gripper_command = self._calculate_gripper_command(thumb_tip[:3], index_tip[:3]) gripper_command = self._calculate_gripper_command(thumb_tip[:3], index_tip[:3])
......
...@@ -6,6 +6,7 @@ ...@@ -6,6 +6,7 @@
import numpy as np import numpy as np
from scipy.spatial.transform import Rotation, Slerp from scipy.spatial.transform import Rotation, Slerp
from isaaclab.devices import OpenXRDevice
from isaaclab.devices.retargeter_base import RetargeterBase from isaaclab.devices.retargeter_base import RetargeterBase
from isaaclab.markers import VisualizationMarkers from isaaclab.markers import VisualizationMarkers
from isaaclab.markers.config import FRAME_MARKER_CFG from isaaclab.markers.config import FRAME_MARKER_CFG
...@@ -26,6 +27,7 @@ class Se3AbsRetargeter(RetargeterBase): ...@@ -26,6 +27,7 @@ class Se3AbsRetargeter(RetargeterBase):
def __init__( def __init__(
self, self,
bound_hand: OpenXRDevice.TrackingTarget,
zero_out_xy_rotation: bool = False, zero_out_xy_rotation: bool = False,
use_wrist_rotation: bool = False, use_wrist_rotation: bool = False,
use_wrist_position: bool = False, use_wrist_position: bool = False,
...@@ -34,11 +36,19 @@ class Se3AbsRetargeter(RetargeterBase): ...@@ -34,11 +36,19 @@ class Se3AbsRetargeter(RetargeterBase):
"""Initialize the retargeter. """Initialize the retargeter.
Args: Args:
bound_hand: The hand to track (OpenXRDevice.TrackingTarget.HAND_LEFT or OpenXRDevice.TrackingTarget.HAND_RIGHT)
zero_out_xy_rotation: If True, zero out rotation around x and y axes zero_out_xy_rotation: If True, zero out rotation around x and y axes
use_wrist_rotation: If True, use wrist rotation instead of finger average use_wrist_rotation: If True, use wrist rotation instead of finger average
use_wrist_position: If True, use wrist position instead of pinch position use_wrist_position: If True, use wrist position instead of pinch position
enable_visualization: If True, visualize the target pose in the scene enable_visualization: If True, visualize the target pose in the scene
""" """
if bound_hand not in [OpenXRDevice.TrackingTarget.HAND_LEFT, OpenXRDevice.TrackingTarget.HAND_RIGHT]:
raise ValueError(
"bound_hand must be either OpenXRDevice.TrackingTarget.HAND_LEFT or"
" OpenXRDevice.TrackingTarget.HAND_RIGHT"
)
self.bound_hand = bound_hand
self._zero_out_xy_rotation = zero_out_xy_rotation self._zero_out_xy_rotation = zero_out_xy_rotation
self._use_wrist_rotation = use_wrist_rotation self._use_wrist_rotation = use_wrist_rotation
self._use_wrist_position = use_wrist_position self._use_wrist_position = use_wrist_position
...@@ -53,21 +63,22 @@ class Se3AbsRetargeter(RetargeterBase): ...@@ -53,21 +63,22 @@ class Se3AbsRetargeter(RetargeterBase):
self._visualization_pos = np.zeros(3) self._visualization_pos = np.zeros(3)
self._visualization_rot = np.array([1.0, 0.0, 0.0, 0.0]) self._visualization_rot = np.array([1.0, 0.0, 0.0, 0.0])
def retarget(self, data: dict[str, np.ndarray]) -> np.ndarray: def retarget(self, data: dict) -> np.ndarray:
"""Convert hand joint poses to robot end-effector command. """Convert hand joint poses to robot end-effector command.
Args: Args:
data: Dictionary mapping joint names to their pose data, data: Dictionary mapping tracking targets to joint data dictionaries.
joint names are defined in isaaclab.devices.openxr.common.HAND_JOINT_NAMES The joint names are defined in isaaclab.devices.openxr.common.HAND_JOINT_NAMES
Returns: Returns:
np.ndarray: 7D array containing position (xyz) and orientation (quaternion) np.ndarray: 7D array containing position (xyz) and orientation (quaternion)
for the robot end-effector for the robot end-effector
""" """
# Extract key joint poses # Extract key joint poses from the bound hand
thumb_tip = data.get("thumb_tip") hand_data = data[self.bound_hand]
index_tip = data.get("index_tip") thumb_tip = hand_data.get("thumb_tip")
wrist = data.get("wrist") index_tip = hand_data.get("index_tip")
wrist = hand_data.get("wrist")
ee_command = self._retarget_abs(thumb_tip, index_tip, wrist) ee_command = self._retarget_abs(thumb_tip, index_tip, wrist)
......
...@@ -6,6 +6,7 @@ ...@@ -6,6 +6,7 @@
import numpy as np import numpy as np
from scipy.spatial.transform import Rotation from scipy.spatial.transform import Rotation
from isaaclab.devices import OpenXRDevice
from isaaclab.devices.retargeter_base import RetargeterBase from isaaclab.devices.retargeter_base import RetargeterBase
from isaaclab.markers import VisualizationMarkers from isaaclab.markers import VisualizationMarkers
from isaaclab.markers.config import FRAME_MARKER_CFG from isaaclab.markers.config import FRAME_MARKER_CFG
...@@ -27,6 +28,7 @@ class Se3RelRetargeter(RetargeterBase): ...@@ -27,6 +28,7 @@ class Se3RelRetargeter(RetargeterBase):
def __init__( def __init__(
self, self,
bound_hand: OpenXRDevice.TrackingTarget,
zero_out_xy_rotation: bool = False, zero_out_xy_rotation: bool = False,
use_wrist_rotation: bool = False, use_wrist_rotation: bool = False,
use_wrist_position: bool = True, use_wrist_position: bool = True,
...@@ -39,6 +41,7 @@ class Se3RelRetargeter(RetargeterBase): ...@@ -39,6 +41,7 @@ class Se3RelRetargeter(RetargeterBase):
"""Initialize the relative motion retargeter. """Initialize the relative motion retargeter.
Args: Args:
bound_hand: The hand to track (OpenXRDevice.TrackingTarget.HAND_LEFT or OpenXRDevice.TrackingTarget.HAND_RIGHT)
zero_out_xy_rotation: If True, ignore rotations around x and y axes, allowing only z-axis rotation zero_out_xy_rotation: If True, ignore rotations around x and y axes, allowing only z-axis rotation
use_wrist_rotation: If True, use wrist rotation for control instead of averaging finger orientations use_wrist_rotation: If True, use wrist rotation for control instead of averaging finger orientations
use_wrist_position: If True, use wrist position instead of pinch position (midpoint between fingers) use_wrist_position: If True, use wrist position instead of pinch position (midpoint between fingers)
...@@ -48,6 +51,14 @@ class Se3RelRetargeter(RetargeterBase): ...@@ -48,6 +51,14 @@ class Se3RelRetargeter(RetargeterBase):
alpha_rot: Rotation smoothing parameter (0-1); higher values track more closely to input, lower values smooth more alpha_rot: Rotation smoothing parameter (0-1); higher values track more closely to input, lower values smooth more
enable_visualization: If True, show a visual marker representing the target end-effector pose enable_visualization: If True, show a visual marker representing the target end-effector pose
""" """
# Store the hand to track
if bound_hand not in [OpenXRDevice.TrackingTarget.HAND_LEFT, OpenXRDevice.TrackingTarget.HAND_RIGHT]:
raise ValueError(
"bound_hand must be either OpenXRDevice.TrackingTarget.HAND_LEFT or"
" OpenXRDevice.TrackingTarget.HAND_RIGHT"
)
self.bound_hand = bound_hand
self._zero_out_xy_rotation = zero_out_xy_rotation self._zero_out_xy_rotation = zero_out_xy_rotation
self._use_wrist_rotation = use_wrist_rotation self._use_wrist_rotation = use_wrist_rotation
self._use_wrist_position = use_wrist_position self._use_wrist_position = use_wrist_position
...@@ -78,21 +89,22 @@ class Se3RelRetargeter(RetargeterBase): ...@@ -78,21 +89,22 @@ class Se3RelRetargeter(RetargeterBase):
self._previous_index_tip = np.array([0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0], dtype=np.float32) self._previous_index_tip = np.array([0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0], dtype=np.float32)
self._previous_wrist = np.array([0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0], dtype=np.float32) self._previous_wrist = np.array([0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0], dtype=np.float32)
def retarget(self, data: dict[str, np.ndarray]) -> np.ndarray: def retarget(self, data: dict) -> np.ndarray:
"""Convert hand joint poses to robot end-effector command. """Convert hand joint poses to robot end-effector command.
Args: Args:
data: Dictionary mapping joint names to their pose data, data: Dictionary mapping tracking targets to joint data dictionaries.
joint names are defined in isaaclab.devices.openxr.common.HAND_JOINT_NAMES The joint names are defined in isaaclab.devices.openxr.common.HAND_JOINT_NAMES
Returns: Returns:
np.ndarray: 6D array containing position (xyz) and rotation vector (rx,ry,rz) np.ndarray: 6D array containing position (xyz) and rotation vector (rx,ry,rz)
for the robot end-effector for the robot end-effector
""" """
# Extract key joint poses # Extract key joint poses from the bound hand
thumb_tip = data.get("thumb_tip") hand_data = data[self.bound_hand]
index_tip = data.get("index_tip") thumb_tip = hand_data.get("thumb_tip")
wrist = data.get("wrist") index_tip = hand_data.get("index_tip")
wrist = hand_data.get("wrist")
delta_thumb_tip = self._calculate_delta_pose(thumb_tip, self._previous_thumb_tip) delta_thumb_tip = self._calculate_delta_pose(thumb_tip, self._previous_thumb_tip)
delta_index_tip = self._calculate_delta_pose(index_tip, self._previous_index_tip) delta_index_tip = self._calculate_delta_pose(index_tip, self._previous_index_tip)
......
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment