omni.isaac.lab.devices#

Sub-package providing interfaces to different teleoperation devices.

Currently, the following categories of devices are supported:

  • Keyboard: Standard keyboard with WASD and arrow keys.

  • Spacemouse: 3D mouse with 6 degrees of freedom.

  • Gamepad: Gamepad with 2D two joysticks and buttons. Example: Xbox controller.

All device interfaces inherit from the DeviceBase class, which provides a common interface for all devices. The device interface reads the input data when the DeviceBase.advance() method is called. It also provides the function DeviceBase.add_callback() to add user-defined callback functions to be called when a particular input is pressed from the peripheral device.

Classes

DeviceBase

An interface class for teleoperation devices.

Se2Gamepad

A gamepad controller for sending SE(2) commands as velocity commands.

Se3Gamepad

A gamepad controller for sending SE(3) commands as delta poses and binary command (open/close).

Se2Keyboard

A keyboard controller for sending SE(2) commands as velocity commands.

Se3Keyboard

A keyboard controller for sending SE(3) commands as delta poses and binary command (open/close).

Se3SpaceMouse

A space-mouse controller for sending SE(3) commands as delta poses.

Se3SpaceMouse

A space-mouse controller for sending SE(3) commands as delta poses.

Device Base#

class omni.isaac.lab.devices.DeviceBase[source]#

An interface class for teleoperation devices.

Methods:

__init__()

Initialize the teleoperation interface.

reset()

Reset the internals.

add_callback(key, func)

Add additional functions to bind keyboard.

advance()

Provides the joystick event state.

__init__()[source]#

Initialize the teleoperation interface.

abstract reset()[source]#

Reset the internals.

abstract add_callback(key: Any, func: Callable)[source]#

Add additional functions to bind keyboard.

Parameters:
  • key – The button to check against.

  • func – The function to call when key is pressed. The callback function should not take any arguments.

abstract advance() Any[source]#

Provides the joystick event state.

Returns:

The processed output form the joystick.

Game Pad#

class omni.isaac.lab.devices.Se2Gamepad[source]#

Bases: DeviceBase

A gamepad controller for sending SE(2) commands as velocity commands.

This class is designed to provide a gamepad controller for mobile base (such as quadrupeds). It uses the Omniverse gamepad interface to listen to gamepad events and map them to robot’s task-space commands.

The command comprises of the base linear and angular velocity: \((v_x, v_y, \omega_z)\).

Key bindings:

Command

Key (+ve axis)

Key (-ve axis)

Move along x-axis

left stick up

left stick down

Move along y-axis

left stick right

left stick left

Rotate along z-axis

right stick right

right stick left

See also

The official documentation for the gamepad interface: Carb Gamepad Interface.

Methods:

__init__([v_x_sensitivity, v_y_sensitivity, ...])

Initialize the gamepad layer.

reset()

Reset the internals.

add_callback(key, func)

Add additional functions to bind gamepad.

advance()

Provides the result from gamepad event state.

__init__(v_x_sensitivity: float = 1.0, v_y_sensitivity: float = 1.0, omega_z_sensitivity: float = 1.0, dead_zone: float = 0.01)[source]#

Initialize the gamepad layer.

Parameters:
  • v_x_sensitivity – Magnitude of linear velocity along x-direction scaling. Defaults to 1.0.

  • v_y_sensitivity – Magnitude of linear velocity along y-direction scaling. Defaults to 1.0.

  • omega_z_sensitivity – Magnitude of angular velocity along z-direction scaling. Defaults to 1.0.

  • dead_zone – Magnitude of dead zone for gamepad. An event value from the gamepad less than this value will be ignored. Defaults to 0.01.

reset()[source]#

Reset the internals.

add_callback(key: carb.input.GamepadInput, func: Callable)[source]#

Add additional functions to bind gamepad.

A list of available gamepad keys are present in the carb documentation.

Parameters:
  • key – The gamepad button to check against.

  • func – The function to call when key is pressed. The callback function should not take any arguments.

advance() numpy.ndarray[source]#

Provides the result from gamepad event state.

Returns:

A 3D array containing the linear (x,y) and angular velocity (z).

class omni.isaac.lab.devices.Se3Gamepad[source]#

Bases: DeviceBase

A gamepad controller for sending SE(3) commands as delta poses and binary command (open/close).

This class is designed to provide a gamepad controller for a robotic arm with a gripper. It uses the gamepad interface to listen to gamepad events and map them to the robot’s task-space commands.

The command comprises of two parts:

  • delta pose: a 6D vector of (x, y, z, roll, pitch, yaw) in meters and radians.

  • gripper: a binary command to open or close the gripper.

Stick and Button bindings:

Description

Stick/Button (+ve axis)

Stick/Button (-ve axis)

Toggle gripper(open/close)

X Button

X Button

Move along x-axis

Left Stick Up

Left Stick Down

Move along y-axis

Left Stick Left

Left Stick Right

Move along z-axis

Right Stick Up

Right Stick Down

Rotate along x-axis

D-Pad Left

D-Pad Right

Rotate along y-axis

D-Pad Down

D-Pad Up

Rotate along z-axis

Right Stick Left

Right Stick Right

See also

The official documentation for the gamepad interface: Carb Gamepad Interface.

Methods:

__init__([pos_sensitivity, rot_sensitivity, ...])

Initialize the gamepad layer.

reset()

Reset the internals.

add_callback(key, func)

Add additional functions to bind gamepad.

advance()

Provides the result from gamepad event state.

__init__(pos_sensitivity: float = 1.0, rot_sensitivity: float = 1.6, dead_zone: float = 0.01)[source]#

Initialize the gamepad layer.

Parameters:
  • pos_sensitivity – Magnitude of input position command scaling. Defaults to 1.0.

  • rot_sensitivity – Magnitude of scale input rotation commands scaling. Defaults to 1.6.

  • dead_zone – Magnitude of dead zone for gamepad. An event value from the gamepad less than this value will be ignored. Defaults to 0.01.

reset()[source]#

Reset the internals.

add_callback(key: carb.input.GamepadInput, func: Callable)[source]#

Add additional functions to bind gamepad.

A list of available gamepad keys are present in the carb documentation.

Parameters:
  • key – The gamepad button to check against.

  • func – The function to call when key is pressed. The callback function should not take any arguments.

advance() tuple[numpy.ndarray, bool][source]#

Provides the result from gamepad event state.

Returns:

A tuple containing the delta pose command and gripper commands.

Keyboard#

class omni.isaac.lab.devices.Se2Keyboard[source]#

Bases: DeviceBase

A keyboard controller for sending SE(2) commands as velocity commands.

This class is designed to provide a keyboard controller for mobile base (such as quadrupeds). It uses the Omniverse keyboard interface to listen to keyboard events and map them to robot’s task-space commands.

The command comprises of the base linear and angular velocity: \((v_x, v_y, \omega_z)\).

Key bindings:

Command

Key (+ve axis)

Key (-ve axis)

Move along x-axis

Numpad 8 / Arrow Up

Numpad 2 / Arrow Down

Move along y-axis

Numpad 4 / Arrow Right

Numpad 6 / Arrow Left

Rotate along z-axis

Numpad 7 / Z

Numpad 9 / X

See also

The official documentation for the keyboard interface: Carb Keyboard Interface.

Methods:

__init__([v_x_sensitivity, v_y_sensitivity, ...])

Initialize the keyboard layer.

reset()

Reset the internals.

add_callback(key, func)

Add additional functions to bind keyboard.

advance()

Provides the result from keyboard event state.

__init__(v_x_sensitivity: float = 0.8, v_y_sensitivity: float = 0.4, omega_z_sensitivity: float = 1.0)[source]#

Initialize the keyboard layer.

Parameters:
  • v_x_sensitivity – Magnitude of linear velocity along x-direction scaling. Defaults to 0.8.

  • v_y_sensitivity – Magnitude of linear velocity along y-direction scaling. Defaults to 0.4.

  • omega_z_sensitivity – Magnitude of angular velocity along z-direction scaling. Defaults to 1.0.

reset()[source]#

Reset the internals.

add_callback(key: str, func: Callable)[source]#

Add additional functions to bind keyboard.

A list of available keys are present in the carb documentation.

Parameters:
  • key – The keyboard button to check against.

  • func – The function to call when key is pressed. The callback function should not take any arguments.

advance() numpy.ndarray[source]#

Provides the result from keyboard event state.

Returns:

3D array containing the linear (x,y) and angular velocity (z).

class omni.isaac.lab.devices.Se3Keyboard[source]#

Bases: DeviceBase

A keyboard controller for sending SE(3) commands as delta poses and binary command (open/close).

This class is designed to provide a keyboard controller for a robotic arm with a gripper. It uses the Omniverse keyboard interface to listen to keyboard events and map them to robot’s task-space commands.

The command comprises of two parts:

  • delta pose: a 6D vector of (x, y, z, roll, pitch, yaw) in meters and radians.

  • gripper: a binary command to open or close the gripper.

Key bindings:

Description

Key (+ve axis)

Key (-ve axis)

Toggle gripper (open/close)

K

Move along x-axis

W

S

Move along y-axis

A

D

Move along z-axis

Q

E

Rotate along x-axis

Z

X

Rotate along y-axis

T

G

Rotate along z-axis

C

V

See also

The official documentation for the keyboard interface: Carb Keyboard Interface.

Methods:

__init__([pos_sensitivity, rot_sensitivity])

Initialize the keyboard layer.

reset()

Reset the internals.

add_callback(key, func)

Add additional functions to bind keyboard.

advance()

Provides the result from keyboard event state.

__init__(pos_sensitivity: float = 0.4, rot_sensitivity: float = 0.8)[source]#

Initialize the keyboard layer.

Parameters:
  • pos_sensitivity – Magnitude of input position command scaling. Defaults to 0.05.

  • rot_sensitivity – Magnitude of scale input rotation commands scaling. Defaults to 0.5.

reset()[source]#

Reset the internals.

add_callback(key: str, func: Callable)[source]#

Add additional functions to bind keyboard.

A list of available keys are present in the carb documentation.

Parameters:
  • key – The keyboard button to check against.

  • func – The function to call when key is pressed. The callback function should not take any arguments.

advance() tuple[numpy.ndarray, bool][source]#

Provides the result from keyboard event state.

Returns:

A tuple containing the delta pose command and gripper commands.

Space Mouse#

class omni.isaac.lab.devices.Se2SpaceMouse[source]#

Bases: DeviceBase

A space-mouse controller for sending SE(2) commands as delta poses.

This class implements a space-mouse controller to provide commands to mobile base. It uses the HID-API which interfaces with USD and Bluetooth HID-class devices across multiple platforms.

The command comprises of the base linear and angular velocity: \((v_x, v_y, \omega_z)\).

Note

The interface finds and uses the first supported device connected to the computer.

Currently tested for following devices:

Methods:

__init__([v_x_sensitivity, v_y_sensitivity, ...])

Initialize the spacemouse layer.

reset()

Reset the internals.

add_callback(key, func)

Add additional functions to bind keyboard.

advance()

Provides the result from spacemouse event state.

__init__(v_x_sensitivity: float = 0.8, v_y_sensitivity: float = 0.4, omega_z_sensitivity: float = 1.0)[source]#

Initialize the spacemouse layer.

Parameters:
  • v_x_sensitivity – Magnitude of linear velocity along x-direction scaling. Defaults to 0.8.

  • v_y_sensitivity – Magnitude of linear velocity along y-direction scaling. Defaults to 0.4.

  • omega_z_sensitivity – Magnitude of angular velocity along z-direction scaling. Defaults to 1.0.

reset()[source]#

Reset the internals.

add_callback(key: str, func: Callable)[source]#

Add additional functions to bind keyboard.

Parameters:
  • key – The button to check against.

  • func – The function to call when key is pressed. The callback function should not take any arguments.

advance() numpy.ndarray[source]#

Provides the result from spacemouse event state.

Returns:

A 3D array containing the linear (x,y) and angular velocity (z).

class omni.isaac.lab.devices.Se3SpaceMouse[source]#

Bases: DeviceBase

A space-mouse controller for sending SE(3) commands as delta poses.

This class implements a space-mouse controller to provide commands to a robotic arm with a gripper. It uses the HID-API which interfaces with USD and Bluetooth HID-class devices across multiple platforms [1].

The command comprises of two parts:

  • delta pose: a 6D vector of (x, y, z, roll, pitch, yaw) in meters and radians.

  • gripper: a binary command to open or close the gripper.

Note

The interface finds and uses the first supported device connected to the computer.

Currently tested for following devices:

Methods:

__init__([pos_sensitivity, rot_sensitivity])

Initialize the space-mouse layer.

reset()

Reset the internals.

add_callback(key, func)

Add additional functions to bind keyboard.

advance()

Provides the result from spacemouse event state.

__init__(pos_sensitivity: float = 0.4, rot_sensitivity: float = 0.8)[source]#

Initialize the space-mouse layer.

Parameters:
  • pos_sensitivity – Magnitude of input position command scaling. Defaults to 0.4.

  • rot_sensitivity – Magnitude of scale input rotation commands scaling. Defaults to 0.8.

reset()[source]#

Reset the internals.

add_callback(key: str, func: Callable)[source]#

Add additional functions to bind keyboard.

Parameters:
  • key – The button to check against.

  • func – The function to call when key is pressed. The callback function should not take any arguments.

advance() tuple[numpy.ndarray, bool][source]#

Provides the result from spacemouse event state.

Returns:

A tuple containing the delta pose command and gripper commands.