isaaclab_contrib.sensors

Contents

isaaclab_contrib.sensors#

Sub-package for externally contributed sensors.

This package provides specialized sensor classes for simulating externally contributed sensors in Isaac Lab. These sensors are not part of the core Isaac Lab framework yet, but are planned to be added in the future. They are contributed by the community to extend the capabilities of Isaac Lab.

Following the categorization in isaaclab.sensors sub-package, the prim paths passed to the sensor’s configuration class are interpreted differently based on the sensor type. The following table summarizes the interpretation of the prim paths for different sensor types:

Sensor Type

Example Prim Path

Pre-check

Visuo-Tactile Sensor

/World/robot/base

Leaf exists and is a physics body (Rigid Body)

Classes

VisuoTactileSensor

A tactile sensor for both camera-based and force field tactile sensing.

VisuoTactileSensorCfg

Configuration for the visuo-tactile sensor.

VisuoTactileSensorData

Data container for the visuo-tactile sensor.

GelSightRenderCfg

Configuration for GelSight sensor rendering parameters.

Visuo-Tactile Sensor#

class isaaclab_contrib.sensors.VisuoTactileSensor[source]#

Bases: SensorBase

A tactile sensor for both camera-based and force field tactile sensing.

This sensor provides: 1. Camera-based tactile sensing: depth images from tactile surface 2. Force field tactile sensing: Penalty-based normal and shear forces using SDF queries

The sensor can be configured to use either or both sensing modalities.

Computation Pipeline:

Camera-based sensing computes depth differences from a nominal (no-contact) baseline and processes them through the tac-sl GelSight renderer to produce realistic tactile images.

Force field sensing queries Signed Distance Fields (SDF) to compute penetration depths, then applies penalty-based spring-damper models (\(F_n = k_n \cdot \text{depth}\), \(F_t = \min(k_t \cdot \|v_t\|, \mu \cdot F_n)\)) to compute normal and shear forces at discrete tactile points.

Example Usage:

For a complete working example, see: scripts/demos/sensors/tacsl/tacsl_example.py

Current Limitations:
  • SDF collision meshes must be pre-computed and objects specified before simulation starts

  • Force field computation requires specific rigid body and mesh configurations

  • No support for dynamic addition/removal of interacting objects during runtime

Configuration Requirements:

The following requirements must be satisfied for proper sensor operation:

Camera Tactile Imaging

If enable_camera_tactile=True, a valid camera_cfg (TiledCameraCfg) must be provided with appropriate camera parameters.

Force Field Computation

If enable_force_field=True, the following parameters are required:

  • contact_object_prim_path_expr - Prim path expression to find the contact object prim

SDF Computation

When force field computation is enabled, penalty-based normal and shear forces are computed using Signed Distance Field (SDF) queries. To achieve GPU acceleration:

  • Interacting objects should have pre-computed SDF collision meshes

  • An SDFView must be defined during initialization, therefore interacting objects should be specified before simulation.

Attributes:

cfg

The configuration parameters.

num_instances

Number of instances of the sensor.

data

Data from the sensor.

device

Memory device for computation.

has_debug_vis_implementation

Whether the sensor has a debug visualization implemented.

is_initialized

Whether the sensor is initialized.

Methods:

__init__(cfg)

Initializes the tactile sensor object.

reset([env_ids])

Resets the sensor internals.

get_initial_render()

Get the initial tactile sensor render for baseline comparison.

set_debug_vis(debug_vis)

Sets whether to visualize the sensor data.

cfg: VisuoTactileSensorCfg#

The configuration parameters.

__init__(cfg: VisuoTactileSensorCfg)[source]#

Initializes the tactile sensor object.

Parameters:

cfg – The configuration parameters.

property num_instances: int#

Number of instances of the sensor.

This is equal to the number of sensors per environment multiplied by the number of environments.

property data: VisuoTactileSensorData#

Data from the sensor.

This property is only updated when the user tries to access the data. This is done to avoid unnecessary computation when the sensor data is not used.

For updating the sensor when this property is accessed, you can use the following code snippet in your sensor implementation:

# update sensors if needed
self._update_outdated_buffers()
# return the data (where `_data` is the data for the sensor)
return self._data
reset(env_ids: Sequence[int] | None = None)[source]#

Resets the sensor internals.

get_initial_render() dict | None[source]#

Get the initial tactile sensor render for baseline comparison.

This method captures the initial state of the tactile sensor when no contact is occurring. This baseline is used for computing relative changes during tactile interactions.

Warning

It is the user’s responsibility to ensure that the sensor is in a “no contact” state when this method is called. If the sensor is in contact with an object, the baseline will be incorrect, leading to erroneous tactile readings.

Returns:

Dictionary containing initial render data with sensor output keys

and corresponding tensor values. Returns None if camera tactile sensing is disabled.

Return type:

dict | None

Raises:

RuntimeError – If camera sensor is not initialized or initial render fails.

property device: str#

Memory device for computation.

property has_debug_vis_implementation: bool#

Whether the sensor has a debug visualization implemented.

property is_initialized: bool#

Whether the sensor is initialized.

Returns True if the sensor is initialized, False otherwise.

set_debug_vis(debug_vis: bool) bool#

Sets whether to visualize the sensor data.

Parameters:

debug_vis – Whether to visualize the sensor data.

Returns:

Whether the debug visualization was successfully set. False if the sensor does not support debug visualization.

class isaaclab_contrib.sensors.VisuoTactileSensorData[source]#

Data container for the visuo-tactile sensor.

This class contains the tactile sensor data that includes:

  • Camera-based tactile sensing (RGB and depth images)

  • Force field tactile sensing (normal and shear forces)

  • Tactile point positions and contact information

Attributes:

tactile_depth_image

Tactile depth images.

tactile_rgb_image

Tactile RGB images rendered using the Taxim approach from Si and Yuan [SY22].

tactile_points_pos_w

Positions of tactile points in world frame.

tactile_points_quat_w

Orientations of tactile points in world frame.

penetration_depth

Penetration depth at each tactile point.

tactile_normal_force

Normal forces at each tactile point in sensor frame.

tactile_shear_force

Shear forces at each tactile point in sensor frame.

tactile_depth_image: torch.Tensor | None = None#

Tactile depth images. Shape is (num_instances, height, width, 1).

tactile_rgb_image: torch.Tensor | None = None#

Tactile RGB images rendered using the Taxim approach from Si and Yuan [SY22]. Shape is (num_instances, height, width, 3).

tactile_points_pos_w: torch.Tensor | None = None#

Positions of tactile points in world frame. Shape is (num_instances, num_tactile_points, 3).

tactile_points_quat_w: torch.Tensor | None = None#

Orientations of tactile points in world frame. Shape is (num_instances, num_tactile_points, 4).

penetration_depth: torch.Tensor | None = None#

Penetration depth at each tactile point. Shape is (num_instances, num_tactile_points).

tactile_normal_force: torch.Tensor | None = None#

Normal forces at each tactile point in sensor frame. Shape is (num_instances, num_tactile_points).

tactile_shear_force: torch.Tensor | None = None#

Shear forces at each tactile point in sensor frame. Shape is (num_instances, num_tactile_points, 2).

class isaaclab_contrib.sensors.VisuoTactileSensorCfg[source]#

Bases: SensorBaseCfg

Configuration for the visuo-tactile sensor.

This sensor provides both camera-based tactile sensing and force field tactile sensing. It can capture tactile RGB/depth images and compute penalty-based contact forces.

Attributes:

render_cfg

Configuration for GelSight sensor rendering.

enable_camera_tactile

Whether to enable camera-based tactile sensing.

prim_path

Prim path (or expression) to the sensor.

update_period

Update period of the sensor buffers (in seconds).

history_length

Number of past frames to store in the sensor buffers.

debug_vis

Whether to visualize the sensor.

enable_force_field

Whether to enable force field tactile sensing.

tactile_array_size

Number of tactile points for force field sensing in (rows, cols) format.

tactile_margin

Margin for tactile point generation (in meters).

contact_object_prim_path_expr

Prim path expression to find the contact object for force field computation.

normal_contact_stiffness

Normal contact stiffness for penalty-based force computation.

friction_coefficient

Friction coefficient for shear forces.

tangential_stiffness

Tangential stiffness for shear forces.

camera_cfg

Camera configuration for tactile RGB/depth sensing.

visualizer_cfg

The configuration object for the visualization markers.

trimesh_vis_tactile_points

Whether to visualize tactile points for debugging using trimesh.

visualize_sdf_closest_pts

Whether to visualize SDF closest points for debugging.

render_cfg: GelSightRenderCfg#

Configuration for GelSight sensor rendering.

This defines the rendering parameters for converting depth maps to realistic tactile images.

For simplicity, you can use the predefined configs for standard sensor models:

  • isaaclab_assets.sensors.GELSIGHT_R15_CFG

  • isaaclab_assets.sensors.GELSIGHT_MINI_CFG

enable_camera_tactile: bool#

Whether to enable camera-based tactile sensing.

prim_path: str#

Prim path (or expression) to the sensor.

Note

The expression can contain the environment namespace regex {ENV_REGEX_NS} which will be replaced with the environment namespace.

Example: {ENV_REGEX_NS}/Robot/sensor will be replaced with /World/envs/env_.*/Robot/sensor.

update_period: float#

Update period of the sensor buffers (in seconds). Defaults to 0.0 (update every step).

history_length: int#

Number of past frames to store in the sensor buffers. Defaults to 0, which means that only the current data is stored (no history).

debug_vis: bool#

Whether to visualize the sensor. Defaults to False.

enable_force_field: bool#

Whether to enable force field tactile sensing.

tactile_array_size: tuple[int, int]#

Number of tactile points for force field sensing in (rows, cols) format.

tactile_margin: float#

Margin for tactile point generation (in meters).

This parameter defines the exclusion margin from the edges of the elastomer mesh when generating the tactile point grid. It ensures that force field points are not generated on the very edges of the sensor surface where geometry might be unstable or less relevant for contact.

contact_object_prim_path_expr: str | None#

Prim path expression to find the contact object for force field computation.

This specifies the object that will make contact with the tactile sensor. The sensor will automatically find the SDF collision mesh within this object for optimal force field computation.

Note

The expression can contain the environment namespace regex {ENV_REGEX_NS} which will be replaced with the environment namespace.

Example: {ENV_REGEX_NS}/ContactObject will be replaced with /World/envs/env_.*/ContactObject.

Attention

For force field computation to work properly, the contact object must have an SDF collision mesh. The sensor will search for the first SDF mesh within the specified prim hierarchy.

normal_contact_stiffness: float#

Normal contact stiffness for penalty-based force computation.

friction_coefficient: float#

Friction coefficient for shear forces.

tangential_stiffness: float#

Tangential stiffness for shear forces.

camera_cfg: TiledCameraCfg | None#

Camera configuration for tactile RGB/depth sensing.

If None, camera-based sensing will be disabled even if enable_camera_tactile is True.

visualizer_cfg: VisualizationMarkersCfg#

The configuration object for the visualization markers.

Note

This attribute is only used when debug visualization is enabled.

trimesh_vis_tactile_points: bool#

Whether to visualize tactile points for debugging using trimesh. Defaults to False.

visualize_sdf_closest_pts: bool#

Whether to visualize SDF closest points for debugging. Defaults to False.

class isaaclab_contrib.sensors.GelSightRenderCfg[source]#

Bases: object

Configuration for GelSight sensor rendering parameters.

This configuration defines the rendering parameters for example-based tactile image synthesis using the Taxim approach.

Reference:

Si, Z., & Yuan, W. (2022). Taxim: An example-based simulation model for GelSight tactile sensors. IEEE Robotics and Automation Letters, 7(2), 2361-2368. https://arxiv.org/abs/2109.04027

Data Directory Structure:

The sensor data should be organized in the following structure:

base_data_path/
└── sensor_data_dir_name/
    ├── bg.jpg              # Background image (required)
    ├── polycalib.npz       # Polynomial calibration data (required)
    └── real_bg.npy         # Real background data (optional)

Example

Using predefined sensor configuration:

from isaaclab_contrib.sensors.tacsl_sensor import VisuoTactileSensorCfg

from isaaclab_assets.sensors import GELSIGHT_R15_CFG

sensor_cfg = VisuoTactileSensorCfg(render_cfg=GELSIGHT_R15_CFG)

Using custom sensor data:

custom_cfg = GelSightRenderCfg(
    base_data_path="/path/to/my/sensors",
    sensor_data_dir_name="my_custom_sensor",
    image_height=480,
    image_width=640,
    mm_per_pixel=0.05,
)

Attributes:

base_data_path

Base path to the directory containing sensor calibration data.

sensor_data_dir_name

Directory name containing the sensor calibration and background data.

background_path

Filename of the background image within the data directory.

calib_path

Filename of the polynomial calibration data within the data directory.

real_background

Filename of the real background data within the data directory.

image_height

Height of the tactile image in pixels.

image_width

Width of the tactile image in pixels.

num_bins

Number of bins for gradient magnitude and direction quantization.

mm_per_pixel

Millimeters per pixel conversion factor for reconstructing 2D tactile image from the height map.

base_data_path: str#

Base path to the directory containing sensor calibration data. Defaults to Isaac Lab Nucleus directory at {ISAACLAB_NUCLEUS_DIR}/TacSL.

sensor_data_dir_name: str#

Directory name containing the sensor calibration and background data.

This should be a relative path (directory name) inside the base_data_path.

background_path: str#

Filename of the background image within the data directory.

calib_path: str#

Filename of the polynomial calibration data within the data directory.

real_background: str#

Filename of the real background data within the data directory.

image_height: int#

Height of the tactile image in pixels.

image_width: int#

Width of the tactile image in pixels.

num_bins: int#

Number of bins for gradient magnitude and direction quantization.

mm_per_pixel: float#

Millimeters per pixel conversion factor for reconstructing 2D tactile image from the height map.