Contact Sensor

Contact Sensor#

A contact sensor with filtering

The contact sensor is designed to return the net contact force acting on a given ridgid body. The sensor is written to behave as a physical object, and so the “scope” of the contact sensor is limited to the body (or bodies) that defines it. There are multiple ways to define this scope, depending on your need to filter the forces coming from the contact.

By default, the reported force is the total contact force, but your application may only care about contact forces due to specific objects. Retrieving contact forces from specific objects requires filtering, and this can only be done in a “many-to-one” way. A multi-legged robot that needs filterable contact information for its feet would require one sensor per foot to be defined in the environment, but a robotic hand with contact sensors on the tips of each finger can be defined with a single sensor.

Consider a simple environment with an Anymal Quadruped and a block

@configclass
class ContactSensorsSceneCfg(InteractiveSceneCfg):
    """Design the scene with sensors on the robot."""

    # ground plane
    ground = AssetBaseCfg(prim_path="/World/defaultGroundPlane", spawn=sim_utils.GroundPlaneCfg())

    # lights
    dome_light = AssetBaseCfg(
        prim_path="/World/Light", spawn=sim_utils.DomeLightCfg(intensity=3000.0, color=(0.75, 0.75, 0.75))
    )

    # robot
    robot = ANYMAL_C_CFG.replace(prim_path="{ENV_REGEX_NS}/Robot")

    # Rigid Object
    cube = RigidObjectCfg(
        prim_path="{ENV_REGEX_NS}/Cube",
        spawn=sim_utils.CuboidCfg(
            size=(0.5,0.5,0.1),
            rigid_props=sim_utils.RigidBodyPropertiesCfg(),
            mass_props=sim_utils.MassPropertiesCfg(mass=100.0),
            collision_props=sim_utils.CollisionPropertiesCfg(),
            physics_material=sim_utils.RigidBodyMaterialCfg(static_friction=1.0),
            visual_material=sim_utils.PreviewSurfaceCfg(diffuse_color=(0.0, 1.0, 0.0), metallic=0.2),
        ),
        init_state=RigidObjectCfg.InitialStateCfg(pos=(0.5, 0.5, 0.05)),
    )

    contact_forces_LF = ContactSensorCfg(
        prim_path="{ENV_REGEX_NS}/Robot/LF_FOOT",
        update_period=0.0,
        history_length=6,
        debug_vis=True,
        filter_prim_paths_expr=["{ENV_REGEX_NS}/Cube"],
    )

    contact_forces_RF = ContactSensorCfg(
        prim_path="{ENV_REGEX_NS}/Robot/RF_FOOT",
        update_period=0.0,
        history_length=6,
        debug_vis=True,
        filter_prim_paths_expr=["{ENV_REGEX_NS}/Cube"],
    )

    contact_forces_H = ContactSensorCfg(
        prim_path="{ENV_REGEX_NS}/Robot/.*H_FOOT",
        update_period=0.0,
        history_length=6,
        debug_vis=True,
    )

We define the sensors on the feet of the robot in two different ways. The front feet are independent sensors (one sensor body per foot) and the “Cube” is placed under the left foot. The hind feet are defined as a single sensor with multiple bodies.

We can then run the scene and print the data from the sensors

def run_simulator(sim: sim_utils.SimulationContext, scene: InteractiveScene):
  .
  .
  .
  # Simulate physics
  while simulation_app.is_running():
    .
    .
    .
    # print information from the sensors
    print("-------------------------------")
    print(scene["contact_forces_LF"])
    print("Received force matrix of: ", scene["contact_forces_LF"].data.force_matrix_w)
    print("Received contact force of: ", scene["contact_forces_LF"].data.net_forces_w)
    print("-------------------------------")
    print(scene["contact_forces_RF"])
    print("Received force matrix of: ", scene["contact_forces_RF"].data.force_matrix_w)
    print("Received contact force of: ", scene["contact_forces_RF"].data.net_forces_w)
    print("-------------------------------")
    print(scene["contact_forces_H"])
    print("Received force matrix of: ", scene["contact_forces_H"].data.force_matrix_w)
    print("Received contact force of: ", scene["contact_forces_H"].data.net_forces_w)

Here, we print both the net contact force and the filtered force matrix for each contact sensor defined in the scene. The front left and front right feet report the following

-------------------------------
Contact sensor @ '/World/envs/env_.*/Robot/LF_FOOT':
        view type         : <class 'omni.physics.tensors.impl.api.RigidBodyView'>
        update period (s) : 0.0
        number of bodies  : 1
        body names        : ['LF_FOOT']

Received force matrix of:  tensor([[[[-1.3923e-05,  1.5727e-04,  1.1032e+02]]]], device='cuda:0')
Received contact force of:  tensor([[[-1.3923e-05,  1.5727e-04,  1.1032e+02]]], device='cuda:0')
-------------------------------
Contact sensor @ '/World/envs/env_.*/Robot/RF_FOOT':
        view type         : <class 'omni.physics.tensors.impl.api.RigidBodyView'>
        update period (s) : 0.0
        number of bodies  : 1
        body names        : ['RF_FOOT']

Received force matrix of:  tensor([[[[0., 0., 0.]]]], device='cuda:0')
Received contact force of:  tensor([[[1.3529e-05, 0.0000e+00, 1.0069e+02]]], device='cuda:0')

Notice that even with filtering, both sensors report the net contact force acting on the foot. However only the left foot has a non zero “force matrix”, because the right foot isn’t standing on the filtered body, /World/envs/env_.*/Cube. Now, checkout the data coming from the hind feet!

-------------------------------
Contact sensor @ '/World/envs/env_.*/Robot/.*H_FOOT':
        view type         : <class 'omni.physics.tensors.impl.api.RigidBodyView'>
        update period (s) : 0.0
        number of bodies  : 2
        body names        : ['LH_FOOT', 'RH_FOOT']

Received force matrix of:  None
Received contact force of:  tensor([[[9.7227e-06, 0.0000e+00, 7.2364e+01],
        [2.4322e-05, 0.0000e+00, 1.8102e+02]]], device='cuda:0')

In this case, the contact sensor has two bodies: the left and right hind feet. When the force matrix is queried, the result is None because this is a many body sensor, and presently Isaac Lab only supports “many to one” contact force filtering. Unlike the single body contact sensor, the reported force tensor has multiple entries, with each “row” corresponding to the contact force on a single body of the sensor (matching the ordering at construction).

Code for contact_sensor.py
  1# Copyright (c) 2022-2025, The Isaac Lab Project Developers.
  2# All rights reserved.
  3#
  4# SPDX-License-Identifier: BSD-3-Clause
  5
  6"""Launch Isaac Sim Simulator first."""
  7
  8import argparse
  9
 10from omni.isaac.lab.app import AppLauncher
 11
 12# add argparse arguments
 13parser = argparse.ArgumentParser(description="Tutorial on adding sensors on a robot.")
 14parser.add_argument("--num_envs", type=int, default=1, help="Number of environments to spawn.")
 15# append AppLauncher cli args
 16AppLauncher.add_app_launcher_args(parser)
 17# parse the arguments
 18args_cli = parser.parse_args()
 19
 20# launch omniverse app
 21app_launcher = AppLauncher(args_cli)
 22simulation_app = app_launcher.app
 23
 24"""Rest everything follows."""
 25
 26import torch
 27
 28import omni.isaac.lab.sim as sim_utils
 29from omni.isaac.lab.assets import AssetBaseCfg, RigidObjectCfg
 30from omni.isaac.lab.scene import InteractiveScene, InteractiveSceneCfg
 31from omni.isaac.lab.sensors import ContactSensorCfg
 32from omni.isaac.lab.utils import configclass
 33
 34##
 35# Pre-defined configs
 36##
 37from omni.isaac.lab_assets.anymal import ANYMAL_C_CFG  # isort: skip
 38
 39
 40@configclass
 41class ContactSensorSceneCfg(InteractiveSceneCfg):
 42    """Design the scene with sensors on the robot."""
 43
 44    # ground plane
 45    ground = AssetBaseCfg(prim_path="/World/defaultGroundPlane", spawn=sim_utils.GroundPlaneCfg())
 46
 47    # lights
 48    dome_light = AssetBaseCfg(
 49        prim_path="/World/Light", spawn=sim_utils.DomeLightCfg(intensity=3000.0, color=(0.75, 0.75, 0.75))
 50    )
 51
 52    # robot
 53    robot = ANYMAL_C_CFG.replace(prim_path="{ENV_REGEX_NS}/Robot")
 54
 55    # Rigid Object
 56    cube = RigidObjectCfg(
 57        prim_path="{ENV_REGEX_NS}/Cube",
 58        spawn=sim_utils.CuboidCfg(
 59            size=(0.5, 0.5, 0.1),
 60            rigid_props=sim_utils.RigidBodyPropertiesCfg(),
 61            mass_props=sim_utils.MassPropertiesCfg(mass=100.0),
 62            collision_props=sim_utils.CollisionPropertiesCfg(),
 63            physics_material=sim_utils.RigidBodyMaterialCfg(static_friction=1.0),
 64            visual_material=sim_utils.PreviewSurfaceCfg(diffuse_color=(0.0, 1.0, 0.0), metallic=0.2),
 65        ),
 66        init_state=RigidObjectCfg.InitialStateCfg(pos=(0.5, 0.5, 0.05)),
 67    )
 68
 69    contact_forces_LF = ContactSensorCfg(
 70        prim_path="{ENV_REGEX_NS}/Robot/LF_FOOT",
 71        update_period=0.0,
 72        history_length=6,
 73        debug_vis=True,
 74        filter_prim_paths_expr=["{ENV_REGEX_NS}/Cube"],
 75    )
 76
 77    contact_forces_RF = ContactSensorCfg(
 78        prim_path="{ENV_REGEX_NS}/Robot/RF_FOOT",
 79        update_period=0.0,
 80        history_length=6,
 81        debug_vis=True,
 82        filter_prim_paths_expr=["{ENV_REGEX_NS}/Cube"],
 83    )
 84
 85    contact_forces_H = ContactSensorCfg(
 86        prim_path="{ENV_REGEX_NS}/Robot/.*H_FOOT",
 87        update_period=0.0,
 88        history_length=6,
 89        debug_vis=True,
 90    )
 91
 92
 93def run_simulator(sim: sim_utils.SimulationContext, scene: InteractiveScene):
 94    """Run the simulator."""
 95    # Define simulation stepping
 96    sim_dt = sim.get_physics_dt()
 97    sim_time = 0.0
 98    count = 0
 99
100    # Simulate physics
101    while simulation_app.is_running():
102
103        if count % 500 == 0:
104            # reset counter
105            count = 0
106            # reset the scene entities
107            # root state
108            # we offset the root state by the origin since the states are written in simulation world frame
109            # if this is not done, then the robots will be spawned at the (0, 0, 0) of the simulation world
110            root_state = scene["robot"].data.default_root_state.clone()
111            root_state[:, :3] += scene.env_origins
112            scene["robot"].write_root_link_pose_to_sim(root_state[:, :7])
113            scene["robot"].write_root_com_velocity_to_sim(root_state[:, 7:])
114            # set joint positions with some noise
115            joint_pos, joint_vel = (
116                scene["robot"].data.default_joint_pos.clone(),
117                scene["robot"].data.default_joint_vel.clone(),
118            )
119            joint_pos += torch.rand_like(joint_pos) * 0.1
120            scene["robot"].write_joint_state_to_sim(joint_pos, joint_vel)
121            # clear internal buffers
122            scene.reset()
123            print("[INFO]: Resetting robot state...")
124        # Apply default actions to the robot
125        # -- generate actions/commands
126        targets = scene["robot"].data.default_joint_pos
127        # -- apply action to the robot
128        scene["robot"].set_joint_position_target(targets)
129        # -- write data to sim
130        scene.write_data_to_sim()
131        # perform step
132        sim.step()
133        # update sim-time
134        sim_time += sim_dt
135        count += 1
136        # update buffers
137        scene.update(sim_dt)
138
139        # print information from the sensors
140        print("-------------------------------")
141        print(scene["contact_forces_LF"])
142        print("Received force matrix of: ", scene["contact_forces_LF"].data.force_matrix_w)
143        print("Received contact force of: ", scene["contact_forces_LF"].data.net_forces_w)
144        print("-------------------------------")
145        print(scene["contact_forces_RF"])
146        print("Received force matrix of: ", scene["contact_forces_RF"].data.force_matrix_w)
147        print("Received contact force of: ", scene["contact_forces_RF"].data.net_forces_w)
148        print("-------------------------------")
149        print(scene["contact_forces_H"])
150        print("Received force matrix of: ", scene["contact_forces_H"].data.force_matrix_w)
151        print("Received contact force of: ", scene["contact_forces_H"].data.net_forces_w)
152
153
154def main():
155    """Main function."""
156
157    # Initialize the simulation context
158    sim_cfg = sim_utils.SimulationCfg(dt=0.005, device=args_cli.device)
159    sim = sim_utils.SimulationContext(sim_cfg)
160    # Set main camera
161    sim.set_camera_view(eye=[3.5, 3.5, 3.5], target=[0.0, 0.0, 0.0])
162    # design scene
163    scene_cfg = ContactSensorSceneCfg(num_envs=args_cli.num_envs, env_spacing=2.0)
164    scene = InteractiveScene(scene_cfg)
165    # Play the simulator
166    sim.reset()
167    # Now we are ready!
168    print("[INFO]: Setup complete...")
169    # Run the simulator
170    run_simulator(sim, scene)
171
172
173if __name__ == "__main__":
174    # run the main function
175    main()
176    # close sim app
177    simulation_app.close()