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
150 changes: 104 additions & 46 deletions docs/source/overview/imitation-learning/teleop_imitation.rst
Original file line number Diff line number Diff line change
Expand Up @@ -16,79 +16,137 @@ command is a 6-D vector representing the change in pose.

Presently, Isaac Lab Mimic is only supported in Linux.

To play inverse kinematics (IK) control with a keyboard device:
.. tab-set::
:sync-group: keyboard

.. code:: bash
.. tab-item:: Keyboard
:sync: keyboard

./isaaclab.sh -p scripts/environments/teleoperation/teleop_se3_agent.py --task Isaac-Stack-Cube-Franka-IK-Rel-v0 --num_envs 1 --teleop_device keyboard
To play inverse kinematics (IK) control with a keyboard device:

For smoother operation and off-axis operation, we recommend using a SpaceMouse as the input device. Providing smoother demonstrations will make it easier for the policy to clone the behavior. To use a SpaceMouse, simply change the teleop device accordingly:
.. code:: bash

.. code:: bash
./isaaclab.sh -p scripts/environments/teleoperation/teleop_se3_agent.py --task Isaac-Stack-Cube-Franka-IK-Rel-v0 --num_envs 1 --teleop_device keyboard

./isaaclab.sh -p scripts/environments/teleoperation/teleop_se3_agent.py --task Isaac-Stack-Cube-Franka-IK-Rel-v0 --num_envs 1 --teleop_device spacemouse
The script prints the teleoperation events configured. For keyboard, these are as follows

.. note::
.. code:: text

If the SpaceMouse is not detected, you may need to grant additional user permissions by running ``sudo chmod 666 /dev/hidraw<#>`` where ``<#>`` corresponds to the device index
of the connected SpaceMouse.
Keyboard Controller for SE(3): Se3Keyboard
Reset all commands: R
Toggle gripper (open/close): K
Move arm along x-axis: W/S
Move arm along y-axis: A/D
Move arm along z-axis: Q/E
Rotate arm along x-axis: Z/X
Rotate arm along y-axis: T/G
Rotate arm along z-axis: C/V

To determine the device index, list all ``hidraw`` devices by running ``ls -l /dev/hidraw*``.
Identify the device corresponding to the SpaceMouse by running ``cat /sys/class/hidraw/hidraw<#>/device/uevent`` on each of the devices listed
from the prior step.

We recommend using local deployment of Isaac Lab to use the SpaceMouse. If using container deployment (:ref:`deployment-docker`), you must manually mount the SpaceMouse to the ``isaac-lab-base`` container by
adding a ``devices`` attribute with the path to the device in your ``docker-compose.yaml`` file:
.. tab-item:: SpaceMouse
:sync: spacemouse

.. code:: yaml
For smoother operation and off-axis operation, we recommend using a
SpaceMouse as the input device. Providing smoother demonstrations will
make it easier for the policy to clone the behavior. To use a
SpaceMouse, simply change the teleop device accordingly:

devices:
- /dev/hidraw<#>:/dev/hidraw<#>
.. code:: bash

where ``<#>`` is the device index of the connected SpaceMouse.
./isaaclab.sh -p scripts/environments/teleoperation/teleop_se3_agent.py --task Isaac-Stack-Cube-Franka-IK-Rel-v0 --num_envs 1 --teleop_device spacemouse

If you are using the IsaacLab + CloudXR container deployment (:ref:`cloudxr-teleoperation`), you can add the ``devices`` attribute under the ``services -> isaac-lab-base`` section of the
``docker/docker-compose.cloudxr-runtime.patch.yaml`` file.
The script prints the teleoperation events configured. For SpaceMouse, these are as follows:

Isaac Lab is only compatible with the SpaceMouse Wireless and SpaceMouse Compact models from 3Dconnexion.
.. code:: text

SpaceMouse Controller for SE(3): Se3SpaceMouse
Reset all commands: Right click
Toggle gripper (open/close): Click the left button on the SpaceMouse
Move arm along x/y-axis: Tilt the SpaceMouse
Move arm along z-axis: Push or pull the SpaceMouse
Rotate arm: Twist the SpaceMouse

For tasks that benefit from the use of an extended reality (XR) device with hand tracking, Isaac Lab supports using NVIDIA CloudXR to immersively stream the scene to compatible XR devices for teleoperation. Note that when using hand tracking we recommend using the absolute variant of the task (``Isaac-Stack-Cube-Franka-IK-Abs-v0``), which requires the ``handtracking`` device:
.. note::

.. code:: bash
If the SpaceMouse is not detected, you may need to grant additional
user permissions by running ``sudo chmod 666 /dev/hidraw<#>`` where
``<#>`` corresponds to the device index of the connected SpaceMouse.

./isaaclab.sh -p scripts/environments/teleoperation/teleop_se3_agent.py --task Isaac-Stack-Cube-Franka-IK-Abs-v0 --teleop_device handtracking --device cpu
To determine the device index, list all ``hidraw`` devices by
running ``ls -l /dev/hidraw*``.

.. note::
Identify the device corresponding to the SpaceMouse by running
``cat /sys/class/hidraw/hidraw<#>/device/uevent`` on each of
the devices listed from the prior step.

We recommend using local deployment of Isaac Lab to use the SpaceMouse.
If using container deployment (:ref:`deployment-docker`), you must
manually mount the SpaceMouse to the ``isaac-lab-base`` container by
adding a ``devices`` attribute with the path to the device in your
``docker-compose.yaml`` file:

.. code:: yaml

devices:
- /dev/hidraw<#>:/dev/hidraw<#>

where ``<#>`` is the device index of the connected SpaceMouse.

If you are using the IsaacLab + CloudXR container deployment
(:ref:`cloudxr-teleoperation`), you can add the ``devices``
attribute under the ``services -> isaac-lab-base`` section
of the ``docker/docker-compose.cloudxr-runtime.patch.yaml``
file.

See :ref:`cloudxr-teleoperation` to learn more about using CloudXR with Isaac Lab.
Isaac Lab is only compatible with the SpaceMouse Wireless and
SpaceMouse Compact models from 3Dconnexion.


The script prints the teleoperation events configured. For keyboard,
these are as follows:
.. tab-item:: Phone
:sync: phone

.. code:: text
As an alternative to the keyboard and SpaceMouse, it is also possible
to use your phone as a teleoperation device. It is more instinctive to
use than a keyboard, and more accessible than a SpaceMouse (but less
precise). To use your phone as a teleoperation device, use the
following command:

.. code:: bash

./isaaclab.sh -p scripts/environments/teleoperation/teleop_se3_agent.py --task Isaac-Stack-Cube-Franka-IK-Rel-v0 --num_envs 1 --teleop_device phone

The script prints the teleoperation events configured. For keyboard, these are as follows

.. code:: text

Keyboard Controller for SE(3): Se3Keyboard
Keep the phone upright.
Toggle gripper (open/close): Enabled Gripper button
To move or rotate the arm: Press hold and do the corresponding action
Move arm along x-axis: Push/Pull your phone forward/backward
Move arm along y-axis: Pull/Pull your phone left/right
Move arm along z-axis: Push/Pull your phone up/down
Rotate arm along x-axis: Rotate your phone left/right
Rotate arm along y-axis: Tilt your phone forward/backward
Rotate arm along z-axis: Twist your phone left/right

.. note::

Please note that only android devices are supported at this time.

.. tab-item:: CloudXR Hand Tracking
:sync: cloudxr

For tasks that benefit from the use of an extended reality (XR) device with hand tracking, Isaac Lab supports using NVIDIA CloudXR to immersively stream the scene to compatible XR devices for teleoperation. Note that when using hand tracking we recommend using the absolute variant of the task (``Isaac-Stack-Cube-Franka-IK-Abs-v0``), which requires the ``handtracking`` device:

.. code:: bash

Keyboard Controller for SE(3): Se3Keyboard
Reset all commands: R
Toggle gripper (open/close): K
Move arm along x-axis: W/S
Move arm along y-axis: A/D
Move arm along z-axis: Q/E
Rotate arm along x-axis: Z/X
Rotate arm along y-axis: T/G
Rotate arm along z-axis: C/V
./isaaclab.sh -p scripts/environments/teleoperation/teleop_se3_agent.py --task Isaac-Stack-Cube-Franka-IK-Abs-v0 --teleop_device handtracking --device cpu

For SpaceMouse, these are as follows:
.. note::

.. code:: text
See :ref:`cloudxr-teleoperation` to learn more about using CloudXR with Isaac Lab.

SpaceMouse Controller for SE(3): Se3SpaceMouse
Reset all commands: Right click
Toggle gripper (open/close): Click the left button on the SpaceMouse
Move arm along x/y-axis: Tilt the SpaceMouse
Move arm along z-axis: Push or pull the SpaceMouse
Rotate arm: Twist the SpaceMouse

The next section describes how teleoperation devices can be used for data collection for imitation learning.

Expand Down
17 changes: 15 additions & 2 deletions scripts/environments/teleoperation/teleop_se3_agent.py
Original file line number Diff line number Diff line change
Expand Up @@ -56,7 +56,16 @@

import omni.log

from isaaclab.devices import Se3Gamepad, Se3GamepadCfg, Se3Keyboard, Se3KeyboardCfg, Se3SpaceMouse, Se3SpaceMouseCfg
from isaaclab.devices import (
Se3Gamepad,
Se3GamepadCfg,
Se3Keyboard,
Se3KeyboardCfg,
Se3Phone,
Se3PhoneCfg,
Se3SpaceMouse,
Se3SpaceMouseCfg,
)
from isaaclab.devices.openxr import remove_camera_configs
from isaaclab.devices.teleop_device_factory import create_teleop_device
from isaaclab.managers import TerminationTermCfg as DoneTerm
Expand Down Expand Up @@ -193,9 +202,13 @@ def stop_teleoperation() -> None:
teleop_interface = Se3Gamepad(
Se3GamepadCfg(pos_sensitivity=0.1 * sensitivity, rot_sensitivity=0.1 * sensitivity)
)
elif args_cli.teleop_device.lower() == "phone":
teleop_interface = Se3Phone(
Se3PhoneCfg(pos_sensitivity=0.1 * sensitivity, rot_sensitivity=0.1 * sensitivity)
)
else:
omni.log.error(f"Unsupported teleop device: {args_cli.teleop_device}")
omni.log.error("Supported devices: keyboard, spacemouse, gamepad, handtracking")
omni.log.error("Supported devices: keyboard, phone, spacemouse, gamepad, handtracking")
env.close()
simulation_app.close()
return
Expand Down
4 changes: 3 additions & 1 deletion scripts/tools/record_demos.py
Original file line number Diff line number Diff line change
Expand Up @@ -89,7 +89,7 @@
import omni.log
import omni.ui as ui

from isaaclab.devices import Se3Keyboard, Se3KeyboardCfg, Se3SpaceMouse, Se3SpaceMouseCfg
from isaaclab.devices import Se3Keyboard, Se3KeyboardCfg, Se3Phone, Se3SpaceMouse, Se3SpaceMouseCfg
from isaaclab.devices.openxr import remove_camera_configs
from isaaclab.devices.teleop_device_factory import create_teleop_device

Expand Down Expand Up @@ -272,6 +272,8 @@ def setup_teleop_device(callbacks: dict[str, Callable]) -> object:
teleop_interface = Se3Keyboard(Se3KeyboardCfg(pos_sensitivity=0.2, rot_sensitivity=0.5))
elif args_cli.teleop_device.lower() == "spacemouse":
teleop_interface = Se3SpaceMouse(Se3SpaceMouseCfg(pos_sensitivity=0.2, rot_sensitivity=0.5))
elif args_cli.teleop_device.lower() == "phone":
teleop_interface = Se3Phone()
else:
omni.log.error(f"Unsupported teleop device: {args_cli.teleop_device}")
omni.log.error("Supported devices: keyboard, spacemouse, handtracking")
Expand Down
1 change: 1 addition & 0 deletions source/isaaclab/isaaclab/devices/__init__.py
Original file line number Diff line number Diff line change
Expand Up @@ -23,6 +23,7 @@
from .gamepad import Se2Gamepad, Se2GamepadCfg, Se3Gamepad, Se3GamepadCfg
from .keyboard import Se2Keyboard, Se2KeyboardCfg, Se3Keyboard, Se3KeyboardCfg
from .openxr import ManusVive, ManusViveCfg, OpenXRDevice, OpenXRDeviceCfg
from .phone import Se2Phone, Se2PhoneCfg, Se3Phone, Se3PhoneCfg
from .retargeter_base import RetargeterBase, RetargeterCfg
from .spacemouse import Se2SpaceMouse, Se2SpaceMouseCfg, Se3SpaceMouse, Se3SpaceMouseCfg
from .teleop_device_factory import create_teleop_device
1 change: 0 additions & 1 deletion source/isaaclab/isaaclab/devices/keyboard/se3_keyboard.py
Original file line number Diff line number Diff line change
Expand Up @@ -145,7 +145,6 @@ def advance(self) -> torch.Tensor:
if self.gripper_term:
gripper_value = -1.0 if self._close_gripper else 1.0
command = np.append(command, gripper_value)

return torch.tensor(command, dtype=torch.float32, device=self._sim_device)

"""
Expand Down
9 changes: 9 additions & 0 deletions source/isaaclab/isaaclab/devices/phone/__init__.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,9 @@
# Copyright (c) 2022-2025, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md).
# All rights reserved.
#
# SPDX-License-Identifier: BSD-3-Clause

"""Phone device for SE(2) and SE(3) control."""

from .se2_phone import Se2Phone, Se2PhoneCfg
from .se3_phone import Se3Phone, Se3PhoneCfg
Loading