Skip to content
Open
Show file tree
Hide file tree
Changes from 2 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
2 changes: 2 additions & 0 deletions .gitignore
Original file line number Diff line number Diff line change
Expand Up @@ -69,3 +69,5 @@ tests/

# Docker history
.isaac-lab-docker-history

**/tactile_record/*
1 change: 1 addition & 0 deletions CONTRIBUTORS.md
Original file line number Diff line number Diff line change
Expand Up @@ -84,6 +84,7 @@ Guidelines for modifications:
* Jingzhou Liu
* Jinqi Wei
* Johnson Sun
* Juana Du
* Kaixi Bao
* Kris Wilson
* Kourosh Darvish
Expand Down
2 changes: 2 additions & 0 deletions docs/conf.py
Original file line number Diff line number Diff line change
Expand Up @@ -188,6 +188,8 @@
"nvidia.srl",
"flatdict",
"IPython",
"cv2",
"imageio",
"ipywidgets",
"mpl_toolkits",
]
Expand Down
Copy link
Contributor

Choose a reason for hiding this comment

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

images should be .jpg

Copy link
Author

Choose a reason for hiding this comment

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

all changed to jpg format and documentation is updated accordingly.

Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
22 changes: 22 additions & 0 deletions docs/source/api/lab/isaaclab.sensors.rst
Original file line number Diff line number Diff line change
Expand Up @@ -33,6 +33,9 @@
RayCasterCameraCfg
Imu
ImuCfg
VisuoTactileSensor
VisuoTactileSensorCfg
VisuoTactileSensorData

Sensor Base
-----------
Expand Down Expand Up @@ -166,3 +169,22 @@ Inertia Measurement Unit
:inherited-members:
:show-inheritance:
:exclude-members: __init__, class_type

Visuo-Tactile Sensor
--------------------

.. autoclass:: VisuoTactileSensor
:members:
:inherited-members:
:show-inheritance:

.. autoclass:: VisuoTactileSensorData
:members:
:inherited-members:
:exclude-members: __init__

.. autoclass:: VisuoTactileSensorCfg
:members:
:inherited-members:
:show-inheritance:
:exclude-members: __init__, class_type
1 change: 1 addition & 0 deletions docs/source/overview/core-concepts/sensors/index.rst
Original file line number Diff line number Diff line change
Expand Up @@ -19,3 +19,4 @@ The following pages describe the available sensors in more detail:
frame_transformer
imu
ray_caster
visuo_tactile_sensor
202 changes: 202 additions & 0 deletions docs/source/overview/core-concepts/sensors/visuo_tactile_sensor.rst
Original file line number Diff line number Diff line change
@@ -0,0 +1,202 @@
.. _overview_sensors_tactile:

.. currentmodule:: isaaclab

Visuo-Tactile Sensor
====================


The visuo-tactile sensor in Isaac Lab provides realistic tactile feedback through integration with TacSL (Tactile Sensor Learning) [Akinola2025]_. This sensor is designed to simulate high-fidelity tactile interactions, generating both visual and force-based data that mirrors real-world tactile sensors like GelSight devices. The sensor can provide tactile RGB images, force field distributions, and other relevant tactile measurements that are essential for robotic manipulation tasks requiring fine tactile feedback.


.. figure:: ../../../_static/overview/sensors/tacsl_diagram.png
:align: center
:figwidth: 100%
:alt: Tactile sensor with RGB visualization and force fields


Configuration
~~~~~~~~~~~~~

Tactile sensors require specific configuration parameters to define their behavior and data collection properties. The sensor can be configured with various parameters including sensor resolution, force sensitivity, and output data types.

.. code-block:: python

from isaaclab.sensors.tacsl_sensor import VisuoTactileSensorCfg

tactile_sensor = VisuoTactileSensorCfg(
prim_path="{ENV_REGEX_NS}/Robot/tactile_sensor",
## Sensor configuration
sensor_type="gelsight_r15",
enable_camera_tactile=True,
enable_force_field=True,
## Elastomer configuration
elastomer_rigid_body="elastomer",
elastomer_tactile_mesh="elastomer/visuals",
elastomer_tip_link_name="elastomer_tip",
# Force field configuration
num_tactile_rows=20,
num_tactile_cols=25,
tactile_margin=0.003,
## Indenter configuration (will be set based on indenter type)
indenter_rigid_body="indenter",
indenter_sdf_mesh="factory_nut_loose/collisions",
## Force field physics parameters
tactile_kn=1.0,
tactile_mu=2.0,
tactile_kt=0.1,
## Compliant dynamics
compliance_stiffness=150.0,
compliant_damping=1.0,
## Camera configuration
camera_cfg=TiledCameraCfg(
prim_path="{ENV_REGEX_NS}/Robot/elastomer_tip/tactile_cam",
update_period=1 / 60, # 60 Hz
height=320,
width=240,
data_types=["distance_to_image_plane"],
spawn=sim_utils.PinholeCameraCfg(
focal_length=0.020342857142857145 * 100,
focus_distance=400.0 / 1000,
horizontal_aperture=0.0119885 * 2 * 100,
clipping_range=(0.0001, 1.0e5),
),
offset=TiledCameraCfg.OffsetCfg(
pos=(0.0, 0.0, -0.020342857142857145 + 0.00175), rot=(0.5, 0.5, -0.5, 0.5), convention="world"
),
),

)

The configuration allows for comprehensive customization of:

* **Sensor Type**: Specify the tactile sensor model (e.g., ``"gelsight_r15"``)
* **Tactile Modalities**:
* ``enable_camera_tactile`` - Enable tactile RGB imaging through camera sensors
* ``enable_force_field`` - Enable force field computation and visualization
* **Elastomer Properties**: Configure elastomer links and tip components that define the sensor's deformable surface
* **Force Field Grid**: Set tactile grid dimensions (``num_tactile_rows``, ``num_tactile_cols``) and margins, which directly affects the spatial resolution of the computed force field
* **Indenter Configuration**: Define properties of interacting objects including rigid body name, and collision mesh
* **Physics Parameters**: Control the sensor's physical behavior:
* ``tactile_kn``, ``tactile_mu``, ``tactile_kt`` - Normal, friction, and tangential stiffness
* ``compliance_stiffness``, ``compliant_damping`` - Compliant dynamics parameters
* **Camera Settings**: Configure resolution, focal length, update rates, and 6-DOF positioning relative to the sensor

Configuration Requirements
~~~~~~~~~~~~~~~~~~~~~~~~~~

.. important::
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:

* ``indenter_rigid_body`` - Specific rigid body within the actor
* ``indenter_sdf_mesh`` - Collision mesh for SDF computation

**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.

**Elastomer Configuration**
Elastomer properties (``elastomer_rigid_body``, ``elastomer_tip_link_name``) must match the robot model where the sensor is attached.



Usage Example
~~~~~~~~~~~~~

To use the tactile sensor in a simulation environment, first ensure the required dependencies are installed:

.. code-block:: bash

conda activate env_isaaclab
pip install opencv-python==4.11.0 trimesh==4.5.1 imageio==2.37.0
Copy link
Contributor

Choose a reason for hiding this comment

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

do we need to add these to setup.py?

Copy link
Author

Choose a reason for hiding this comment

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

Added opencv-python to setup.py; trimesh is already included, and imageio's dependency is not required in the newest commit.


Download the required assets and place them in the appropriate assets folder.

Then run the demo:

.. code-block:: bash

cd scripts/demos/sensors/tacsl
python tacsl_example.py --enable_cameras --indenter nut --num_envs 16 --use_tactile_taxim --use_tactile_ff --save_viz

Available command-line options include:

* ``--enable_cameras``: Enable camera rendering for visualization
* ``--indenter``: Specify the type of indenter object (nut, cube, etc.)
* ``--num_envs``: Number of parallel environments
* ``--use_tactile_taxim``: Enable RGB tactile imaging
* ``--use_tactile_ff``: Enable force field computation
* ``--save_viz``: Save visualization outputs for analysis

For a complete list of available options:

.. code-block:: bash

python tacsl_example.py -h

.. figure:: ../../../_static/overview/sensors/tacsl_demo.png
:align: center
:figwidth: 100%
:alt: TacSL tactile sensor demonstration results showing RGB tactile images and force field visualizations

The tactile sensor supports multiple data modalities that provide comprehensive information about contact interactions:


Output Tactile Data
~~~~~~~~~~~~~~~~~~~
**RGB Tactile Images**
Real-time generation of tactile RGB images as objects make contact with the sensor surface. These images show deformation patterns and contact geometry similar to gel-based tactile sensors [Si2022]_


**Force Fields**
Detailed force field of contact forces and pressure distributions across the sensor surface. This provides quantitative information about the magnitude and direction of applied forces.

.. list-table::
:widths: 50 50
:class: borderless

* - .. figure:: ../../../_static/overview/sensors/tacsl_taxim_example.png
:align: center
:figwidth: 80%
:alt: Tactile output with RGB visualization

- .. figure:: ../../../_static/overview/sensors/tacsl_force_field_example.png
:align: center
:figwidth: 80%
:alt: Tactile output with force field visualization

Integration with Learning Frameworks
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~

The tactile sensor is designed to integrate seamlessly with reinforcement learning and imitation learning frameworks. The structured tensor outputs can be directly used as observations in learning algorithms:

.. code-block:: python

def get_tactile_observations(self):
"""Extract tactile observations for learning."""
tactile_data = self.scene["tactile_sensor"].data

# tactile RGB image
tactile_rgb = tactile_data.taxim_tactile

# force field
tactile_normal_force = tactile_data.tactile_normal_force
tactile_shear_force = tactile_data.tactile_shear_force

return [tactile_rgb, tactile_normal_force, tactile_shear_force]



References
~~~~~~~~~~

Copy link
Author

Choose a reason for hiding this comment

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

@iakinola23 Could you help view this documentation here? Thanks!

Copy link
Author

Choose a reason for hiding this comment

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

Hi @iakinola23 updated the documentation with your edits.

.. [Akinola2025] Akinola, I., Xu, J., Carius, J., Fox, D., & Narang, Y. (2025). Tacsl: A library for visuotactile sensor simulation and learning. *IEEE Transactions on Robotics*.
.. [Si2022] Si, Z., & Yuan, W. (2022). Taxim: An example-based simulation model for gelsight tactile sensors. *IEEE Robotics and Automation Letters*, 7(2), 2361-2368.
Loading
Loading