Skip to content

Conversation

@rwiltz
Copy link
Contributor

@rwiltz rwiltz commented Nov 5, 2025

Description

This MR does the following:

  • Introduces Quest retargeters for G1 env loco-manipulation tasks. This enables lower body control via the quest controller joysticks, and upper body control via controller tracking.
  • Refactors the retargeters to not depend on OpenXRDevice, instead move enums into DeviceBase and allow retargeters to be used across devices.
  • Adds XrAnchor "pinning" to a specific robot prim so that the XR view follows the robot in the scene.

Fixes # (issue)

Type of change

  • New feature (non-breaking change which adds functionality)
  • Breaking change (existing functionality will not work without user modification)
  • Documentation update

Screenshots

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

Checklist

  • I have read and understood the contribution guidelines
  • I have run the pre-commit checks with ./isaaclab.sh --format
  • I have made corresponding changes to the documentation
  • My changes generate no new warnings
  • I have added tests that prove my fix is effective or that my feature works
  • I have updated the changelog and the corresponding version in the extension's config/extension.toml file
  • I have added my name to the CONTRIBUTORS.md or my name already exists there

@github-actions github-actions bot added documentation Improvements or additions to documentation isaac-mimic Related to Isaac Mimic team isaac-lab Related to Isaac Lab team labels Nov 5, 2025
@rwiltz rwiltz marked this pull request as ready for review November 5, 2025 21:49
@rwiltz rwiltz requested a review from hougantc-nvda November 5, 2025 21:49
Copy link
Contributor

@greptile-apps greptile-apps bot left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Greptile Overview

Greptile Summary

This PR introduces Quest controller support for G1 loco-manipulation tasks and refactors the retargeter architecture for device independence.

Key Changes:

  • Architecture Refactoring: Moved tracking enums (TrackingTarget, MotionControllerDataRowIndex, MotionControllerInputIndex) from OpenXRDevice to DeviceBase, enabling retargeters to work across different device types
  • Feature Discovery System: Added Requirement enum and GetRequirments() method to RetargeterBase, allowing devices to query which data features each retargeter needs (hand tracking, head tracking, motion controllers)
  • XR Anchor Pinning: New XrAnchorSynchronizer class enables the XR anchor to dynamically follow a robot prim (e.g., pelvis) with configurable rotation modes (FIXED, FOLLOW_PRIM, FOLLOW_PRIM_SMOOTHED, CUSTOM)
  • Quest Controller Integration: Two new retargeters for G1:
    • G1LowerBodyStandingMotionControllerRetargeter: Maps thumbstick inputs to locomotion commands (x/y movement, yaw rotation, hip height)
    • G1TriHandUpperBodyMotionControllerRetargeter: Maps trigger/squeeze/buttons to hand joint commands for manipulation
  • Breaking Change: All existing retargeters updated to use DeviceBase.TrackingTarget instead of OpenXRDevice.TrackingTarget

Issues Found:

  • Method name typo: GetRequirments() should be GetRequirements() (marked as intentional but is still a spelling error that should be corrected across all 10 files)

Confidence Score: 4/5

  • Safe to merge with one systematic typo correction needed
  • The refactoring is well-architected and properly decouples retargeters from OpenXR-specific dependencies. The XR anchor synchronizer implementation is solid with proper error handling. The only issue is a systematic method name typo (GetRequirments vs GetRequirements) that needs correction across all implementations. All existing retargeters have been updated consistently, tests have been updated, and the breaking changes are well-documented.
  • All files using GetRequirments() need the typo corrected to GetRequirements() before merge (10 files total)

Important Files Changed

File Analysis

Filename Score Overview
source/isaaclab/isaaclab/devices/device_base.py 4/5 Added shared enums (TrackingTarget, MotionControllerDataRowIndex, MotionControllerInputIndex) to support cross-device retargeting and feature aggregation system
source/isaaclab/isaaclab/devices/retargeter_base.py 3/5 Added Requirement enum and GetRequirments() method for feature discovery - typo in method name should be corrected to GetRequirements()
source/isaaclab/isaaclab/devices/openxr/openxr_device.py 4/5 Refactored to use DeviceBase enums, added motion controller support, integrated XrAnchorSynchronizer for dynamic anchor tracking
source/isaaclab/isaaclab/devices/openxr/xr_anchor_utils.py 4/5 New XrAnchorSynchronizer class enables XR anchor to follow robot prim with configurable rotation modes and smoothing
source/isaaclab/isaaclab/devices/openxr/xr_cfg.py 5/5 Added XrAnchorRotationMode enum and new config fields for dynamic anchor positioning (anchor_prim_path, anchor_rotation_mode, smoothing parameters)
source/isaaclab/isaaclab/devices/openxr/retargeters/humanoid/unitree/g1_motion_controller_locomotion.py 4/5 New retargeter maps Quest controller thumbsticks to G1 locomotion commands (movement and hip height adjustment)
source/isaaclab/isaaclab/devices/openxr/retargeters/humanoid/unitree/trihand/g1_upper_body_motion_ctrl_retargeter.py 4/5 New retargeter maps Quest controller inputs (trigger, squeeze, buttons) to G1 hand joints for manipulation

Sequence Diagram

sequenceDiagram
    participant User
    participant Env as Environment
    participant Device as OpenXRDevice
    participant Retargeter1 as G1UpperBodyRetargeter
    participant Retargeter2 as G1LowerBodyRetargeter
    participant XRCore as XRCore/Hardware
    participant Anchor as XrAnchorSynchronizer
    participant Robot as G1 Robot

    User->>Env: Initialize environment
    Env->>Device: Create OpenXRDevice(cfg, retargeters)
    Device->>Retargeter1: Query GetRequirments()
    Retargeter1-->>Device: [HAND_TRACKING]
    Device->>Retargeter2: Query GetRequirments()
    Retargeter2-->>Device: [MOTION_CONTROLLER]
    Device->>Device: Aggregate required features
    Device->>Anchor: Initialize XrAnchorSynchronizer
    Anchor->>Robot: Track pelvis prim
    
    loop Every Simulation Step
        User->>Env: env.step()
        Env->>Device: advance()
        Device->>Device: _get_raw_data()
        Device->>XRCore: get_input_device("/user/hand/left")
        XRCore-->>Device: Hand tracking data
        Device->>XRCore: get_input_device("/user/hand/right")
        XRCore-->>Device: Controller + inputs data
        Device->>Device: Package data with TrackingTarget keys
        
        Device->>Retargeter1: retarget(raw_data)
        Retargeter1->>Retargeter1: Extract HAND_LEFT/RIGHT from data
        Retargeter1->>Retargeter1: Calculate wrist poses
        Retargeter1->>Retargeter1: Retarget hand joints
        Retargeter1-->>Device: tensor[wrist_poses + hand_joints]
        
        Device->>Retargeter2: retarget(raw_data)
        Retargeter2->>Retargeter2: Extract CONTROLLER_LEFT/RIGHT
        Retargeter2->>Retargeter2: Map thumbsticks to locomotion
        Retargeter2-->>Device: tensor[x, y, yaw, hip_height]
        
        Device->>Device: torch.cat([ret1_output, ret2_output])
        Device-->>Env: Combined command tensor
        
        Env->>Robot: Apply upper body IK
        Env->>Robot: Apply lower body joint positions
        
        Anchor->>Robot: Query pelvis world pose
        Robot-->>Anchor: Position + Rotation
        Anchor->>Anchor: Apply rotation mode (FOLLOW_PRIM_SMOOTHED)
        Anchor->>Anchor: Slerp smoothing
        Anchor->>XRCore: set_world_transform_matrix()
        XRCore->>User: Update VR view to follow robot
    end
Loading

40 files reviewed, 2 comments

Edit Code Review Agent Settings | Greptile

@rwiltz
Copy link
Contributor Author

rwiltz commented Nov 5, 2025

@greptile

Copy link
Contributor

@greptile-apps greptile-apps bot left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Greptile Overview

Greptile Summary

This PR introduces Quest controller support for G1 humanoid locomotion-manipulation tasks and decouples the retargeter architecture from OpenXR-specific dependencies.

Key Changes:

  • Moved TrackingTarget and motion controller enums from OpenXRDevice to DeviceBase, enabling retargeters to work across different device types
  • Added Requirement enum to RetargeterBase allowing retargeters to declare required device features (hand tracking, head tracking, motion controllers)
  • Implemented feature requirement aggregation in DeviceBase.__init__() to collect requirements from all retargeters
  • Created two new retargeters for G1:
    • G1LowerBodyStandingMotionControllerRetargeter: Maps joystick inputs to locomotion commands with dynamic hip height adjustment
    • G1TriHandUpperBodyMotionControllerRetargeter: Maps trigger/squeeze/button inputs to hand joint angles
  • Refactored all existing retargeters to use DeviceBase.TrackingTarget instead of OpenXRDevice.TrackingTarget
  • Added retargeter_type field to all RetargeterCfg dataclasses for factory instantiation
  • Moved config dataclasses to end of files for better organization

Issues Found:

  • Missing super().__init__(cfg) call in G1LowerBodyStandingMotionControllerRetargeter.__init__() (already noted in previous comments)

Confidence Score: 4/5

  • This PR is safe to merge with one constructor fix needed
  • The refactoring is well-structured and follows good design principles by decoupling device-specific code. The new locomotion retargeter has a missing super().init() call that should be fixed, but otherwise the changes are clean and all existing retargeters were updated consistently
  • source/isaaclab/isaaclab/devices/openxr/retargeters/humanoid/unitree/g1_motion_controller_locomotion.py needs the super().init() fix

Important Files Changed

File Analysis

Filename Score Overview
source/isaaclab/isaaclab/devices/device_base.py 5/5 Added enums for tracking targets and motion controller indices, plus teleoperation config fields and feature requirement aggregation in init
source/isaaclab/isaaclab/devices/retargeter_base.py 5/5 Added Requirement enum and GetRequirements() method for declaring required device features, plus retargeter_type field to RetargeterCfg
source/isaaclab/isaaclab/devices/openxr/retargeters/humanoid/unitree/g1_motion_controller_locomotion.py 4/5 New retargeter for G1 lower body locomotion using motion controller joysticks; missing super().init() call in constructor
source/isaaclab/isaaclab/devices/openxr/retargeters/humanoid/unitree/trihand/g1_upper_body_motion_ctrl_retargeter.py 5/5 New retargeter mapping motion controller inputs (trigger/squeeze/buttons) to G1 hand joints with proper requirements declaration

Sequence Diagram

sequenceDiagram
    participant Device as DeviceBase
    participant Retargeter as RetargeterBase
    participant G1Locomotion as G1MotionControllerRetargeter
    participant Quest as Quest Controller

    Note over Device: Device initialization
    Device->>Retargeter: __init__(retargeters)
    loop For each retargeter
        Device->>Retargeter: GetRequirements()
        Retargeter-->>Device: [MOTION_CONTROLLER, HAND_TRACKING, ...]
        Device->>Device: Aggregate into _required_features
    end

    Note over Device: Teleoperation loop
    Quest->>Device: Raw input data (controllers, hands)
    Device->>Device: _get_raw_data()
    Device->>Device: advance()
    
    loop For each retargeter
        Device->>G1Locomotion: retarget(raw_data)
        G1Locomotion->>G1Locomotion: Extract controller inputs
        G1Locomotion->>G1Locomotion: Scale thumbstick values
        G1Locomotion->>G1Locomotion: Update hip_height with dt
        G1Locomotion-->>Device: torch.Tensor([x, y, yaw, height])
    end
    
    Device->>Device: torch.cat(all_outputs)
    Device-->>Quest: Concatenated robot commands
Loading

11 files reviewed, 1 comment

Edit Code Review Agent Settings | Greptile

Comment on lines 19 to 23
def __init__(self, cfg: G1LowerBodyStandingMotionControllerRetargeterCfg):
"""Initialize the retargeter."""
self.cfg = cfg
self._hip_height = cfg.hip_height
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

syntax: Missing super().__init__(cfg) call - the base class constructor should be called to properly initialize self._sim_device

Suggested change
def __init__(self, cfg: G1LowerBodyStandingMotionControllerRetargeterCfg):
"""Initialize the retargeter."""
self.cfg = cfg
self._hip_height = cfg.hip_height
def __init__(self, cfg: G1LowerBodyStandingMotionControllerRetargeterCfg):
"""Initialize the retargeter."""
super().__init__(cfg)
self.cfg = cfg
self._hip_height = cfg.hip_height

@rwiltz
Copy link
Contributor Author

rwiltz commented Nov 5, 2025

@greptile

Copy link
Contributor

@greptile-apps greptile-apps bot left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Greptile Overview

Greptile Summary

This PR refactors the teleoperation retargeting system to decouple retargeters from specific device implementations, and adds Quest motion controller support for G1 robot loco-manipulation tasks.

Key Changes:

  • Moved TrackingTarget, MotionControllerDataRowIndex, and MotionControllerInputIndex enums from OpenXRDevice to DeviceBase for device-agnostic retargeting
  • Added Requirement enum to RetargeterBase allowing retargeters to declare which features they need (hand tracking, head tracking, motion controllers)
  • Introduced GetRequirements() method that devices call to aggregate feature requirements across all retargeters
  • Added device_type and retargeter_type fields to config classes, removing the need for factory registration maps
  • Implemented new motion controller retargeters for G1 lower body locomotion (g1_motion_controller_locomotion.py) and TriHand upper body control (g1_upper_body_motion_ctrl_retargeter.py)
  • Added XR anchor "pinning" functionality to track robot prims in the scene
  • Updated all existing retargeters to use DeviceBase.TrackingTarget enums instead of device-specific enums

Architecture Improvements:
The refactoring improves modularity by making retargeters work across different device types (OpenXR, ManusVive, future devices) and optimizes performance by only querying the tracking data actually needed by retargeters.

Confidence Score: 5/5

  • This PR is safe to merge with no critical issues found
  • The refactoring is well-structured with proper abstraction, all retargeters correctly call super().init(), enum usage is consistent throughout, the GetRequirements() implementation is sound, and the changes maintain backward compatibility while improving architecture
  • No files require special attention

Important Files Changed

File Analysis

Filename Score Overview
source/isaaclab/isaaclab/devices/openxr/retargeters/humanoid/fourier/gr1t2_retargeter.py 5/5 Updated to use DeviceBase.TrackingTarget enum instead of OpenXRDevice.TrackingTarget for device-agnostic retargeting
source/isaaclab/isaaclab/devices/openxr/retargeters/humanoid/unitree/g1_motion_controller_locomotion.py 5/5 Motion controller locomotion retargeter using thumbsticks for movement and hip height control with proper enum usage
source/isaaclab/isaaclab/devices/openxr/retargeters/humanoid/unitree/trihand/g1_upper_body_motion_ctrl_retargeter.py 5/5 Motion controller retargeter mapping trigger/squeeze inputs to TriHand finger joints with proper pose transformations

Sequence Diagram

sequenceDiagram
    participant User
    participant Device as DeviceBase/OpenXRDevice
    participant Retargeter as RetargeterBase
    participant Robot as Robot Controller

    Note over Device,Retargeter: Initialization Phase
    User->>Device: Create device with retargeters config
    Device->>Retargeter: Call GetRequirements() for each retargeter
    Retargeter-->>Device: Returns required features (HAND_TRACKING, MOTION_CONTROLLER, etc)
    Device->>Device: Aggregate required features into _required_features set

    Note over Device,Robot: Teleoperation Loop
    User->>Device: Call advance()
    Device->>Device: Call _get_raw_data()
    alt Hand Tracking Required
        Device->>Device: Query hand poses from XRCore
        Device->>Device: Store in data[TrackingTarget.HAND_LEFT/RIGHT]
    end
    alt Motion Controller Required
        Device->>Device: Query controller poses & inputs
        Device->>Device: Store in data[TrackingTarget.CONTROLLER_LEFT/RIGHT]
    end
    alt Head Tracking Required
        Device->>Device: Query head pose
        Device->>Device: Store in data[TrackingTarget.HEAD]
    end
    
    Device->>Retargeter: Call retarget(data) for each retargeter
    Retargeter->>Retargeter: Extract required tracking data using enums
    Retargeter->>Retargeter: Transform to robot-specific commands
    Retargeter-->>Device: Return torch.Tensor
    
    Device->>Device: Concatenate all retargeter outputs
    Device-->>Robot: Return combined command tensor
    Robot->>Robot: Apply commands to robot joints
Loading

6 files reviewed, no comments

Edit Code Review Agent Settings | Greptile

)
hand_joints_tensor = torch.tensor(all_hand_joints, dtype=torch.float32, device=self._sim_device)

return torch.cat([left_wrist_tensor, right_wrist_tensor, hand_joints_tensor])
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I don't know if we want to do it in this review, but we could split this retargeter into two.
One just gets wrist data, the other the hand joints data. That way the wrist data retargeter can be reused in Arena.

@hougantc-nvda
Copy link
Contributor

Overall, LGTM. Added a few comments that can be handled in different PR.

@rwiltz rwiltz force-pushed the dev/hougantc/teleop-controllers branch from 6a69037 to bf34bef Compare November 10, 2025 21:20
@greptile-apps
Copy link
Contributor

greptile-apps bot commented Nov 10, 2025

Greptile Overview

Greptile Summary

This PR enables Quest controller support for G1 robot locomotion-manipulation by refactoring retargeters to be device-independent and implementing XR anchor pinning to follow the robot in the scene.

Key Changes

  • Retargeter Refactoring: Moved device-specific enums (TrackingTarget, MotionControllerDataRowIndex, MotionControllerInputIndex) from OpenXRDevice to DeviceBase, enabling retargeters to work across different device types without OpenXR dependencies
  • Feature Requirements System: Added Requirement enum and get_requirements() method to RetargeterBase, allowing devices to selectively enable only the tracking features needed by their retargeters (hand tracking, head tracking, or motion controllers)
  • Quest Controller Integration: Implemented two new retargeters for Quest controllers:
    • G1LowerBodyStandingMotionControllerRetargeter: Maps Quest thumbsticks to G1 locomotion commands (forward/lateral movement, rotation, and dynamic hip height adjustment)
    • G1TriHandUpperBodyMotionControllerRetargeter: Maps Quest trigger/squeeze inputs to G1 tri-finger hand joint angles with proper left-hand mirroring
  • XR Anchor Pinning: New XrAnchorSynchronizer class dynamically attaches the XR view to a robot prim (e.g., pelvis), supporting multiple rotation modes (FIXED, FOLLOW_PRIM, FOLLOW_PRIM_SMOOTHED, CUSTOM) with yaw-only tracking and optional smoothing for comfort
  • Environment Configuration: Updated G1 locomanipulation environment to support both hand tracking and motion controller devices with proper anchor configuration

Code Quality

The implementation follows clean architecture principles with proper abstraction layers, comprehensive null safety checks, and consistent use of enums for type safety. All retargeters correctly call super().__init__(cfg) and properly implement the get_requirements() method.

Confidence Score: 5/5

  • This PR is safe to merge with no critical issues found
  • The code demonstrates excellent quality with proper abstractions, comprehensive error handling, and consistent patterns throughout. The refactoring cleanly separates concerns between devices and retargeters. All previous review comments about typos and missing initializations are incorrect - the code correctly initializes XRCoreEventType, spells get_requirements() properly, defines fixed_anchor_height in XrCfg, and handles all null cases in anchor synchronization. The implementation includes proper super() calls, enum-based type safety, and follows established project patterns.
  • No files require special attention

Important Files Changed

File Analysis

Filename Score Overview
source/isaaclab/isaaclab/devices/retargeter_base.py 5/5 Added Requirement enum and get_requirements() method to enable device-independent retargeting - clean implementation
source/isaaclab/isaaclab/devices/device_base.py 5/5 Moved enums from OpenXRDevice to DeviceBase for cross-device compatibility, added feature aggregation from retargeters
source/isaaclab/isaaclab/devices/openxr/xr_anchor_utils.py 5/5 New XR anchor synchronizer implementation with proper null checks and rotation smoothing support
source/isaaclab/isaaclab/devices/openxr/xr_cfg.py 5/5 Added XR anchor configuration with multiple rotation modes and fixed height option
source/isaaclab/isaaclab/devices/openxr/openxr_device.py 5/5 Enhanced OpenXR device with motion controller support, anchor synchronization, and button binding capabilities
source/isaaclab/isaaclab/devices/openxr/retargeters/humanoid/unitree/g1_motion_controller_locomotion.py 5/5 New Quest controller locomotion retargeter mapping thumbsticks to G1 robot movement with hip height control
source/isaaclab/isaaclab/devices/openxr/retargeters/humanoid/unitree/trihand/g1_upper_body_motion_ctrl_retargeter.py 5/5 New Quest controller upper body retargeter mapping trigger/squeeze to G1 hand joints with proper mirroring
source/isaaclab_tasks/isaaclab_tasks/manager_based/locomanipulation/pick_place/locomanipulation_g1_env_cfg.py 5/5 Added Quest motion controller device configuration alongside existing hand tracking for G1 locomanipulation

Sequence Diagram

sequenceDiagram
    participant User
    participant OpenXRDevice
    participant RetargeterBase
    participant MotionCtrlRetargeter
    participant LocoRetargeter
    participant XrAnchorSync
    participant Robot

    User->>OpenXRDevice: Initialize with retargeters
    OpenXRDevice->>RetargeterBase: Aggregate requirements from retargeters
    RetargeterBase-->>OpenXRDevice: MOTION_CONTROLLER + other features
    OpenXRDevice->>XrAnchorSync: Initialize anchor sync (if anchor_prim_path set)
    XrAnchorSync-->>OpenXRDevice: Subscribe to pre_sync_update events

    loop Each Frame
        OpenXRDevice->>OpenXRDevice: _get_raw_data()
        OpenXRDevice->>OpenXRDevice: Query CONTROLLER_LEFT/RIGHT poses + inputs
        OpenXRDevice->>XrAnchorSync: sync_headset_to_anchor()
        XrAnchorSync->>Robot: Read pelvis pose from Fabric
        XrAnchorSync->>XrAnchorSync: Calculate yaw-only rotation
        XrAnchorSync->>XrAnchorSync: Apply smoothing (if FOLLOW_PRIM_SMOOTHED)
        XrAnchorSync-->>OpenXRDevice: Update XR anchor transform

        OpenXRDevice->>MotionCtrlRetargeter: retarget(controller_data)
        MotionCtrlRetargeter->>MotionCtrlRetargeter: Extract trigger/squeeze inputs
        MotionCtrlRetargeter->>MotionCtrlRetargeter: Map to hand joint angles
        MotionCtrlRetargeter-->>OpenXRDevice: Return [left_wrist, right_wrist, hand_joints]

        OpenXRDevice->>LocoRetargeter: retarget(controller_data)
        LocoRetargeter->>LocoRetargeter: Extract thumbstick X/Y values
        LocoRetargeter->>LocoRetargeter: Scale to movement commands
        LocoRetargeter->>LocoRetargeter: Adjust hip height based on right thumbstick Y
        LocoRetargeter-->>OpenXRDevice: Return [forward, lateral, rotation, hip_height]

        OpenXRDevice-->>User: Concatenated tensor [upper_body + lower_body]
        User->>Robot: Apply commands to robot joints
    end
Loading

Copy link
Contributor

@greptile-apps greptile-apps bot left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

37 files reviewed, 1 comment

Edit Code Review Agent Settings | Greptile

"""

near_plane: float = 0.15
"""Specifies the near plane distance for the XR device.
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

logic: fixed_anchor_height is accessed via getattr but not defined in XrCfg dataclass - should add it as a field with default False

Copy link
Contributor

@greptile-apps greptile-apps bot left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

40 files reviewed, 1 comment

Edit Code Review Agent Settings | Greptile

pxr_mat.SetRotateOnly(pxr_anchor_quat)
self.__last_anchor_quat = pxr_anchor_quat
else:
pxr_mat.SetRotateOnly(self.__last_anchor_quat)
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

logic: __last_anchor_quat could be None on first call with __anchor_rotation_enabled=False, causing AttributeError

Suggested change
pxr_mat.SetRotateOnly(self.__last_anchor_quat)
pxr_mat.SetRotateOnly(self.__last_anchor_quat if self.__last_anchor_quat else pxr_cfg_quat)

Copy link
Contributor

@greptile-apps greptile-apps bot left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

40 files reviewed, no comments

Edit Code Review Agent Settings | Greptile

Copy link
Contributor

@greptile-apps greptile-apps bot left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

40 files reviewed, no comments

Edit Code Review Agent Settings | Greptile

@ooctipus
Copy link
Collaborator

Looks like this pr depends on 3897, overall looks good in the first pass, it will be nice to give a second pass with 3897 merged first : )

@rwiltz rwiltz force-pushed the dev/hougantc/teleop-controllers branch from 78d8e8f to 5c585e6 Compare November 13, 2025 17:25
Copy link
Contributor

@greptile-apps greptile-apps bot left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

41 files reviewed, no comments

Edit Code Review Agent Settings | Greptile

@rwiltz rwiltz force-pushed the dev/hougantc/teleop-controllers branch from 5c585e6 to c22bafc Compare November 13, 2025 22:16
@rwiltz
Copy link
Contributor Author

rwiltz commented Nov 13, 2025

@ooctipus @kellyguo11 This MR should be ready for review now that the precursor MR has merged.

Copy link
Contributor

@greptile-apps greptile-apps bot left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

32 files reviewed, 1 comment

Edit Code Review Agent Settings | Greptile

@rwiltz rwiltz force-pushed the dev/hougantc/teleop-controllers branch from c22bafc to c692c52 Compare November 13, 2025 22:29
Copy link
Contributor

@greptile-apps greptile-apps bot left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

32 files reviewed, 2 comments

Edit Code Review Agent Settings | Greptile

* Switch delta time to use wall clock time instead of physics step time. Update config values to compensate.
* Add support for decoupling anchor rotation as a toggle when pressing right controller A button.
* Fix reset not working

Refactor motion controller specific code into OpenXRDeviceMotionController. If we are doing only "handtracking" as teleop_device, then we don't want all the headset anchoring code.

Change the pre render callbacks to be a list so other systems can hook into it as well

Rename classes from Controller to MotionController to limit confusion with Robotics controllers

Move the code to alter the stage until after the telop device has been instantiated so we know what device we dealing with and if we need to change the ground plane material

Format with ./isaaclab -f

Update changelog, contributors and extension.toml

Switch to rendering_dt instead of wall clock for determinism

Address AI code review comments.

Instead of having fixed heigh on by default, make it optional in the case of being able to go into crouch.

We don't need to add pre render to ManagerBasedEnv since that can be done through XRCore.

Moving new motion controller retargeters into new files

Moving OpenXRDevice motion controller logic backup into OpenXRDevice, and moving interface enums into DeviceBase to remove retargeter dependancy on OpenXRDevice

Adding retargeter requiremnts call

Removing bespoke xr env adjustments

Undo xr anchor height offset

Cleaning up teleop script

Code cleanup

Update code comments

Fix typo in RetargeterBase

Properly set sim.device for retargeters

Fixing greptile feedback

Fix logic error if xr anchor rotation is disabled on AR startup

Follow naming conventions for get_requirments
@rwiltz rwiltz force-pushed the dev/hougantc/teleop-controllers branch from c692c52 to d7abfec Compare November 13, 2025 22:40
Copy link
Contributor

@greptile-apps greptile-apps bot left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

32 files reviewed, no comments

Edit Code Review Agent Settings | Greptile

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment

Labels

documentation Improvements or additions to documentation isaac-lab Related to Isaac Lab team isaac-mimic Related to Isaac Mimic team

Projects

None yet

Development

Successfully merging this pull request may close these issues.

3 participants