Touch Sensor#

Touch sensors are used to detect contact and measure normal forces at specified site locations. In robot simulation, touch sensors are commonly used to implement tactile perception, collision detection, and force feedback control.

๐ŸŽฏ Functionality Description#

Touch sensors measure the contact normal force experienced at the mounted site location. When other objects contact the sensorโ€™s detection area (defined by the siteโ€™s shape and size), the sensor returns the magnitude of the normal force generated at the contact points.

Core Features#

  1. Location-Specific: Detects contact at specific site locations

  2. Force Measurement: Returns scalar values of contact normal force

  3. Shape-Aware: Detection based on siteโ€™s geometric shape

  4. Real-Time Response: Provides contact force information at each simulation step

๐Ÿ“‹ Return Value Format#

touch_force = model.get_sensor_value("touch_sensor_name", data)
# Type: numpy.ndarray[float32]
# Shape: shape = (*data.shape, 1)
# Unit: N (Newtons)
  • touch_force[โ€ฆ, 0]: Contact normal force magnitude

  • Value = 0: No contact state

  • Value > 0: Contact present, value represents normal force magnitude

โš™๏ธ MJCF Configuration Parameters#

In MotrixSim, touch sensors support the following MJCF configuration fields:

Basic Configuration#

<sensor>
    <touch name="sensor_name"
          site="site_name"/>
</sensor>

Supported Attributes#

Attribute Name

Type

Required

Default

Description

name

string

โœ…

-

Unique identifier name for the sensor

site

string

โœ…

-

Name of the reference site for the sensor

Note: MotrixSim currently does not support cutoff, noise, and user attributes from the MJCF standard.

๐Ÿ“ Configuration Examples#

Basic Touch Sensor Configuration#

<!-- Define tactile detection point -->
<site name="palm_touch" type="sphere" size="0.05" rgba="1 0 1 1" pos="0 0 0"/>

<!-- Define touch sensor -->
<sensor>
    <touch name="palm_sensor" site="palm_touch"/>
</sensor>

Cylinder Collision Detection Configuration (from touch_sensor_demo.xml)#

<mujoco>
  <compiler />
  <option gravity="0 0 -9.8" timestep="0.01"/>
  <statistic center="0 0 0.5" extent="2"/>

  <worldbody>
    <light name="light" pos="0 0 3" directional="true"/>
    <camera name="fixed" pos="2 -2 1.5" xyaxes="1 0 0 0 0.5 1"/>
    <geom name="ground" type="plane" size="5 5 0.1" rgba="0.6 0.6 0.6 1"/>
 
    <body name="arm" pos="0 0 0.15">
      <joint name="arm_joint" type="slide" axis="1 0 0" limited="true" range="-1.57 1.57"/>
      <geom name="arm_geom" type="cylinder" size="0.05 0.3" rgba="0.8 0.3 0.3 1" euler="0 90 0"/>

      <body name="end_effector" pos="0.35 0 0">
        <joint name="wrist_joint" type="hinge" axis="1 0 0" limited="true" range="-1.57 1.57"/>
        <geom name="hand_geom" type="sphere" size="0.08" rgba="0.3 0.8 0.3 1"/>

        <site name="end" type="sphere" size="0.02" rgba="1 0 0 0.8" pos="0.08 0 0"/>
      </body>
    </body>

    <geom name="wall" type="box" size="0.1 2 1" pos="1.2 0 0.5" rgba="0.5 0.5 0.5 1"/>
  </worldbody>

  <actuator>
    <position name="arm_act" joint="arm_joint" kp="1000" kv="100"/>
  </actuator>

  <sensor>
    <touch name="touch sensor" site="end"/>
  </sensor>
</mujoco>

Multiple Touch Sensor Configuration#

<!-- Multiple tactile points on robot fingers -->
<site name="thumb_tip" pos="0.1 0 0.15" type="sphere" size="0.02" rgba="1 0 0 1"/>
<site name="index_tip" pos="0.05 0 0.18" type="sphere" size="0.02" rgba="0 1 0 1"/>
<site name="middle_tip" pos="0 0 0.18" type="sphere" size="0.02" rgba="0 0 1 1"/>

<!-- Corresponding touch sensors -->
<sensor>
    <touch name="thumb_touch" site="thumb_tip"/>
    <touch name="index_touch" site="index_tip"/>
    <touch name="middle_touch" site="middle_tip"/>
</sensor>

Touch Sensors with Different Shapes#

<!-- Spherical tactile sensor -->
<site name="sphere_touch" type="sphere" size="0.03" rgba="1 1 0 1" pos="0 0 0"/>

<!-- Capsule-shaped tactile sensor -->
<site name="capsule_touch" type="capsule" size="0.02 0.1" rgba="1 0 1 1" pos="0 0 0"/>

<!-- Cylindrical tactile sensor -->
<site name="cylinder_touch" type="cylinder" size="0.03 0.08" rgba="0 1 1 1" pos="0 0 0"/>

<sensor>
    <touch name="sphere_sensor" site="sphere_touch"/>
    <touch name="capsule_sensor" site="capsule_touch"/>
    <touch name="cylinder_sensor" site="cylinder_touch"/>
</sensor>

๐Ÿš€ Usage Examples#

Python API Usage#

For complete visualization examples, see examples/sensors/touch_sensor_demo.py.

Basic Configuration and Sensor Data Retrieval#

path = "examples/assets/touch_sensor_demo.xml"

# Load scene model
model = load_model(path)

# Launch renderer
render.launch(model)

# Create physics data
data = SceneData(model)

# Get actuator
arm_act = model.get_actuator("arm_act")

# Get touch sensor site position
end_site = model.get_site("end")

Sensor Data Reading and Visualization#

force_data = model.get_sensor_value("touch sensor", data)
# Handle single environment simulation data (shape is (1,))
force_value = force_data[0]
if force_value > 0.0:
    # Output touch sensor data
    print("Touch force = ", force_value)

# Get touch sensor position
sensor_pose = end_site.get_pose(data)
sensor_pos = sensor_pose[:3]  # Extract position part

# Draw touch sensor position (red sphere)
render.gizmos.draw_sphere(0.03, sensor_pos, color=Color.rgb(1, 0, 0))

# When pressure is detected, draw arrow based on pressure value
if force_value > 0.0:
    arrow_length = force_value * 0.002
    arrow_end = sensor_pos + np.array([arrow_length, 0, 0])  # Along positive x-axis
    render.gizmos.draw_arrow(
        start=sensor_pos,
        end=arrow_end,
        color=Color.rgb(1, 1, 0),  # Yellow arrow
    )

Practical Application Scenarios#

This example demonstrates a cylinder performing linear reciprocating motion along the x-axis, hitting a wall to test the feedback from the end touch sensor:

  1. Linear Motion Control: Cylinder moves from -2 to 2, then returns, achieving reciprocating motion

  2. Real-Time Contact Detection: When the cylinder end contacts the wall, the sensor detects pressure

  3. Visual Feedback:

    • Red sphere shows sensor position

    • Yellow arrow length is proportional to contact force, intuitively displaying force magnitude

  4. Force Monitoring: Console outputs contact force values in real-time

Detection Process#

  1. Contact Point Identification: If a contact point is located within the touch sensorโ€™s site range, or if the normal direction of the contact point passes through the site, it is considered as valid contact

  2. Force Calculation: Calculate normal force at each contact point

  3. Force Accumulation: Sum normal forces from all contact points

  4. Return Result: Return total normal force magnitude

โš ๏ธ Important Notes#

  1. Site Shape Importance: The sensorโ€™s detection range is determined by the siteโ€™s geometric shape and size

  2. Normal Force Measurement: Only measures normal force, excluding tangential force components

  3. Force Accumulation: Forces from multiple contact points are accumulated into a single scalar value

  4. No Advanced Attributes: MotrixSim currently does not support cutoff, noise, and user attributes

  5. Data Type: Return value is numpy.ndarray type, shape supports vectorized environments

  6. Zero Value Meaning: Return value of 0 indicates no contact or negligible contact force