Meta Quest 3 VR Teleop Setup

Complete step-by-step path from a bare Quest 3 to live robot arm teleoperation. Covers network setup, Unity configuration, the Python UDP server, piper_controller.py, and the adapter pattern for any arm.

1

Network & Prerequisites

Before writing any code, confirm that the Meta Quest 3 and the control PC can reach each other over the same local network. The system uses UDP — both devices must share the same subnet, and UDP ports 8888 and 8889 must be open in the PC firewall.

Requirements checklist:

  • Meta Quest 3 headset with hand-tracking enabled (Settings → Movement Tracking → Hand Tracking)
  • Wi-Fi 6 access point — strongly recommended to keep UDP transit latency below 10 ms
  • Control PC running Linux (Ubuntu 22.04+) or macOS with Python 3.10+
  • For AgileX Piper: USB-to-CAN adapter (e.g. Kvaser or PEAK), CAN cable connected to arm
  • UDP ports 8888 and 8889 open inbound on the PC firewall

Verify connectivity:

# On the control PC — find your IP address
ip addr show   # Linux
ipconfig getifaddr en0   # macOS (Wi-Fi)

# Quick UDP listener test (run on PC, send any packet from Quest)
python3 -c "import socket; s=socket.socket(socket.AF_INET,socket.SOCK_DGRAM); s.bind(('0.0.0.0',8888)); print('Listening...'); print(s.recvfrom(256))"
Same subnet required. Run ip addr on the PC and verify the first three octets match the Quest 3's IP (visible in Quest Settings → Wi-Fi → gear icon). A common issue is that corporate Wi-Fi networks isolate clients from each other — use a dedicated access point for robotics work.
2

Unity App Configuration

The Unity app running on the Quest 3 is built with Unity 2022.3 LTS or later, using the XR Hands package for hand-tracking. Three scripts handle the teleoperation side:

  • VRHandPoseSender.cs — reads hand pose from the XR Hands subsystem, serializes to a 45-byte binary packet, sends via UDP
  • VRGripperController.cs — maps pinch strength to a normalised gripper value [0, 1]
  • VRTeleoperationManager.cs — lifecycle management, connection status UI, auto-reconnect

You do not need to recompile the Unity app to switch between robot arms. Expose the following fields as serialized Inspector fields and tune them from the Unity Editor or via a config file:

Inspector Field AgileX Piper Starting Value Notes
Target IP Your PC's IP address Run ip addr on the PC to find it
positionOffset (m) (0, 0, 0.3) Shifts the virtual robot origin; Piper reach is shorter than xArm6
rotationOffset (deg) (0, 90, 0) 90° Y correction for Piper CAN frame; adjust per mount orientation
scaleFactor 0.75 Reduces hand motion range to fit Piper workspace (~600 mm reach)
Workspace X (mm) ±400 Leave 50 mm margin inside physical limits
Workspace Z (mm) 50 – 700 Keep Z min above table surface to avoid collision
Calibrate before your first live run. Move the Quest 3 slowly to each edge of the intended workspace and watch the commanded position in your terminal output. Confirm the robot stays well inside its joint limits before enabling full-speed streaming.
3

Python UDP Server Setup

The Python server runs three concurrent threads: a receiver thread that reads raw UDP datagrams, a safety thread that validates packets and enqueues them, and a robot control thread that drains the queue and calls the robot controller. This separation ensures slow robot SDK calls never block UDP reception.

Install dependencies:

pip install python-can piper_sdk

# Activate the CAN interface (run once per boot, requires root or dialout group)
bash can_activate.sh can0 1000000

# Verify the interface is UP
ifconfig can0

Run the teleoperation server:

python3 teleoperation_main.py

The server binds to 0.0.0.0:8888 (right hand) and optionally 0.0.0.0:8889 (left hand). When a packet arrives with the valid flag set, the control thread calls robot.set_pose() and robot.set_gripper(). Press Ctrl-C to trigger an emergency stop and clean shutdown.

The simplified server structure showing how all three threads interact:

# teleoperation_main.py (simplified structure)
import socket, struct, queue, threading, signal, time
from piper_controller import PiperController   # swap this to change arms

HOST = "0.0.0.0"
RIGHT_PORT    = 8888
LEFT_PORT     = 8889
QUEUE_MAXSIZE = 3   # drop stale frames if robot is slow
CONTROL_HZ    = 30  # robot command rate

pose_queue     = queue.Queue(maxsize=QUEUE_MAXSIZE)
shutdown_event = threading.Event()

def udp_receiver(port: int):
    """Thread 1 — receive raw UDP datagrams."""
    sock = socket.socket(socket.AF_INET, socket.SOCK_DGRAM)
    sock.bind((HOST, port))
    sock.settimeout(1.0)
    while not shutdown_event.is_set():
        try:
            data, _ = sock.recvfrom(256)
            pose = parse_packet(data)
            if pose and pose["valid"]:
                try:
                    pose_queue.put_nowait(pose)
                except queue.Full:
                    pose_queue.get_nowait()   # drop oldest frame
                    pose_queue.put_nowait(pose)
        except socket.timeout:
            continue
    sock.close()

def robot_control_loop(robot: PiperController):
    """Thread 3 — drain queue and command robot at CONTROL_HZ."""
    period = 1.0 / CONTROL_HZ
    last_pose = None
    while not shutdown_event.is_set():
        t0 = time.monotonic()
        try:
            pose = pose_queue.get(timeout=0.1)
            if pose["estop"]:
                robot.emergency_stop()
                continue
            if pose["valid"]:
                last_pose = pose
                x, y, z = transform_position(pose["position"])
                roll, pitch, yaw = quat_to_euler(pose["rotation"])
                robot.set_pose(x, y, z, roll, pitch, yaw)
                robot.set_gripper(pose["gripper"])
            # tracking lost — hold last known position (do not send zero)
        except queue.Empty:
            pass
        time.sleep(max(0, period - (time.monotonic() - t0)))
Queue size controls latency vs. smoothness. A QUEUE_MAXSIZE of 1 gives minimum latency but can feel jerky. A value of 3–5 smooths motion over packet loss but adds up to 100 ms extra latency at 30 Hz. Start at 3 and tune to taste.
4

piper_controller.py Walkthrough

The piper_controller.py module wraps the AgileX piper_sdk Python library. It implements the five-method interface expected by teleoperation_main.py. Key design decisions:

  • CAN via USB: The Piper arm communicates over CAN bus. The SDK takes a CAN interface name (can0) and requires the interface to be activated before connecting.
  • Slave mode: Calling MasterSlaveConfig(0xFC, 0, 0, 0) puts the arm into slave mode so it accepts streaming position commands.
  • Workspace clamping: Positions are hard-clamped to the constants at the top of the file before every SDK call — these are the last line of software defence before the firmware.
  • SDK units: Position is in micrometres (integer), orientation in millidegrees — multiply float mm/deg values by 1000 before passing to EndEffectorCtrl.
# piper_controller.py
from piper_sdk import C_PiperInterface
import math, logging

logger = logging.getLogger(__name__)

# Piper workspace limits (millimetres) — keep 50 mm inside physical limits
X_MIN, X_MAX = -400, 400
Y_MIN, Y_MAX = -400, 400
Z_MIN, Z_MAX =  50,  700

# Maximum joint speed (0–100 %; keep conservative for teleop)
SPEED_PERCENT = 25


class PiperController:
    """Drop-in replacement for XArmController — same five-method interface."""

    def __init__(self, can_interface: str = "can0"):
        self.can_interface = can_interface
        self._piper: C_PiperInterface | None = None
        self.connected = False

    def connect(self) -> bool:
        """Open CAN port and enable slave mode."""
        try:
            self._piper = C_PiperInterface(
                can_name=self.can_interface,
                judge_flag=False,     # allow 3rd-party CAN adapters
                can_auto_init=True,
                dh_is_offset=1,      # firmware >= V1.6-3
            )
            self._piper.ConnectPort()
            self._piper.MasterSlaveConfig(0xFC, 0, 0, 0)  # enter slave mode
            self.connected = True
            logger.info("Piper connected on %s", self.can_interface)
            return True
        except Exception as e:
            logger.error("Piper connect failed: %s", e)
            return False

    def disconnect(self):
        """Disable servo and close port."""
        if self._piper:
            try:
                self._piper.DisableArm(7)   # disable all joints
            except Exception:
                pass
        self.connected = False

    def set_pose(self, x: float, y: float, z: float,
                 roll: float, pitch: float, yaw: float):
        """Move end-effector to (x,y,z) mm with orientation (roll,pitch,yaw) degrees."""
        if not self.connected:
            return
        x = max(X_MIN, min(X_MAX, x))
        y = max(Y_MIN, min(Y_MAX, y))
        z = max(Z_MIN, min(Z_MAX, z))
        try:
            self._piper.EndEffectorCtrl(
                int(x * 1000), int(y * 1000), int(z * 1000),
                int(roll  * 1000),
                int(pitch * 1000),
                int(yaw   * 1000),
                SPEED_PERCENT,
            )
        except Exception as e:
            logger.warning("set_pose error: %s", e)

    def set_gripper(self, value: float):
        """Set gripper openness. 0.0 = fully closed, 1.0 = fully open."""
        if not self.connected:
            return
        GRIPPER_MAX_UM = 70_000   # 70 mm max opening in µm
        target_um = int(value * GRIPPER_MAX_UM)
        try:
            self._piper.GripperCtrl(target_um, SPEED_PERCENT, 0x01, 0)
        except Exception as e:
            logger.warning("set_gripper error: %s", e)

    def emergency_stop(self):
        """Immediately disable all joints. Safe to call from any thread."""
        if self._piper:
            try:
                self._piper.DisableArm(7)
            except Exception:
                pass
Check SDK units for your firmware version. The Piper SDK evolves rapidly. In some firmware versions position is in micrometres (integer); in others it is millimetres (float). Print piper.GetPiperFirmwareVersion() and verify against the AgileX developer docs before commanding any motion.
5

Safety Validation & First Session

Read before powering on. VR teleoperation commands the robot in real time based on your hand motion. An incorrectly calibrated positionOffset or scaleFactor can cause the arm to move instantly to a position that damages itself or injures nearby people. Always dry-run with robot power OFF first.

Dry-run checklist (power OFF):

  • Start the Python server and connect Quest 3. Watch the transform_position output printed to the terminal.
  • Hold your hand at the centre of the intended workspace. Confirm the printed XYZ values are near the robot's home position (approximately 0, 0, 300 mm for Piper).
  • Move your hand to each workspace edge. Confirm the values stay within the clamped bounds and never go negative on Z.
  • Press the Menu button on the Quest to trigger the software e-stop. Confirm emergency_stop() is called and the loop halts.

First live session:

  • Start at SPEED_PERCENT = 20 — this is roughly 40°/s maximum joint speed.
  • Enable servo power. Move slowly, staying near the arm's home position for the first minute.
  • Verify that hand motion and robot motion are in the same direction. If the wrist rotates backwards, adjust rotationOffset by ±90° on Y in the Unity Inspector.
  • Gradually expand the motion range once the direction mapping is confirmed correct.
  • Keep a physical emergency stop (power relay) within reach at all times.

Two software e-stop paths are implemented:

  • Quest 3 Menu button: Sets Bit 1 of the flags byte in every subsequent UDP packet. The Python server calls robot.emergency_stop() immediately.
  • Ctrl-C (SIGINT): The signal handler sets the shutdown event, which causes the control loop to call emergency_stop() and exit cleanly.
Tracking loss is handled safely. When the Quest 3 loses hand tracking (hand leaves camera FOV, fingers overlap), the valid flag in the UDP packet drops to 0. The Python server holds the last known position rather than snapping the arm to position zero.
6

Adapter Interface — Port to Any Arm

The controller-swap pattern generalises to any arm with a Python SDK. The only requirement is that your controller class implements these five methods with exactly this signature:

Method Signature Contract
connect() () → bool Opens communication channel; returns True on success
disconnect() () → None Disables servo power and closes port or socket
set_pose(x, y, z, roll, pitch, yaw) (float×6) → None Cartesian end-effector target in mm + degrees; must clamp internally
set_gripper(value) (float) → None Normalised openness 0.0–1.0; map to arm-specific units internally
emergency_stop() () → None Must be safe to call from any thread at any time

Steps to add a new arm:

  1. Write myarm_controller.py implementing the five methods above using your arm's SDK. Hardcode workspace bounds and speed limits as module-level constants.
  2. Unit-test in isolation: call connect(), then set_pose with a safe position 5 cm from home. Verify the arm moves and returns the expected position.
  3. Swap the import in teleoperation_main.py: replace from piper_controller import PiperController with your new controller. No other changes needed.
  4. Calibrate the Unity Inspector parameters (positionOffset, rotationOffset, scaleFactor) for the new arm's workspace.
  5. Validate e-stop behaviour, tracking-loss hold, and workspace clamps before any operator session.
Using ROS 2 instead of a direct SDK? Publish to a geometry_msgs/PoseStamped topic inside set_pose — the rest of the architecture stays identical. The queue-based design naturally absorbs the latency of a ROS 2 pub/sub cycle.

Setup Complete?

Check the full UDP packet specs or read the complete developer wiki for deeper coverage.