Contact report does not make sense when enabling gpu pipeline (contact sensor ant example)

Hi,
I am using the following modified version of the contact_sensor.py example (modified to enable the use of GPU pipeline):

# Copyright (c) 2022, NVIDIA CORPORATION.  All rights reserved.
#
# NVIDIA CORPORATION and its licensors retain all intellectual property
# and proprietary rights in and to this software, related documentation
# and any modifications thereto.  Any use, reproduction, disclosure or
# distribution of this software and related documentation without an express
# license agreement from NVIDIA CORPORATION is strictly prohibited.
#

# Copyright (c) 2021, NVIDIA CORPORATION.  All rights reserved.
#
# NVIDIA CORPORATION and its licensors retain all intellectual property
# and proprietary rights in and to this software, related documentation
# and any modifications thereto.  Any use, reproduction, disclosure or
# distribution of this software and related documentation without an express
# license agreement from NVIDIA CORPORATION is strictly prohibited.
#

from omni.isaac.kit import SimulationApp

simulation_app = SimulationApp({"headless": False})

from omni.isaac.core import World
from omni.isaac.core.articulations import Articulation
from omni.isaac.sensor import ContactSensor
from omni.isaac.core.utils.stage import add_reference_to_stage
from omni.isaac.core.utils.nucleus import get_assets_root_path
import numpy as np
import carb
import argparse
import sys

parser = argparse.ArgumentParser()
parser.add_argument("--test", default=False, action="store_true", help="Run in test mode")
args, unknown = parser.parse_known_args()

assets_root_path = get_assets_root_path()
if assets_root_path is None:
    carb.log_error("Could not find Isaac Sim assets folder")
    simulation_app.close()
    sys.exit()

sim_params = {}
sim_params["use_gpu_pipeline"] = False
sim_params["backend"] = "torch"

# sim_params["integration_dt"] = 1.0/100.0
# sim_params["rendering_dt"] = 1.0/50.0
# sim_params["substeps"] = 1
# sim_params["gravity"] = np.array([0.0, 0.0, -9.81])
sim_params["enable_scene_query_support"] = True
sim_params["replicate_physics"] = True
sim_params["use_flatcache"] = True
sim_params["disable_contact_processing"] = False
if sim_params["use_gpu_pipeline"]:
    sim_params["device"] = "cuda"
else:
    sim_params["device"] = "cpu"

my_world = World(stage_units_in_meters=1.0, sim_params=sim_params, 
            backend=sim_params["backend"], 
            device =sim_params["device"])
my_world.scene.add_default_ground_plane()
asset_path = assets_root_path + "/Isaac/Robots/Ant/ant.usd"
add_reference_to_stage(usd_path=asset_path, prim_path="/World/Ant")

ant = my_world.scene.add(Articulation(prim_path="/World/Ant/torso", name="ant", translation=np.array([0, 0, 1.5])))

ant_foot_prim_names = ["right_back_foot", "left_back_foot", "front_right_foot", "front_left_foot"]

translations = np.array(
    [[0.38202, -0.40354, -0.0887], [-0.4, -0.40354, -0.0887], [-0.4, 0.4, -0.0887], [0.4, 0.4, -0.0887]]
)

ant_sensors = []
for i in range(4):
    ant_sensors.append(
        my_world.scene.add(
            ContactSensor(
                prim_path="/World/Ant/" + ant_foot_prim_names[i] + "/contact_sensor",
                name="ant_contact_sensor_{}".format(i),
                min_threshold=0,
                max_threshold=10000000,
                radius=0.1,
                translation=translations[i],
            )
        )
    )

ant_sensors[0].add_raw_contact_data_to_frame()
my_world.reset()

while simulation_app.is_running():
    my_world.step(render=True)
    if my_world.is_playing():
        print(ant_sensors[0].get_current_frame())
        if my_world.current_time_step_index == 0:
            my_world.reset()

simulation_app.close()

When running with sim_params["use_gpu_pipeline"] = False everything is fine and I get, for instance,

{'time': 16.866667546331882, 'physics_step': 1012.0, 'contacts': [{'body0': '/World/Ant/right_back_foot', 'body1': '/World/defaultGroundPlane/GroundPlane/CollisionPlane', 'position': tensor([ 7.4642e-01, -7.4641e-01, -6.3133e-06]), 'normal': tensor([1.3436e-07, 0.0000e+00, 1.0000e+00]), 'impulse': tensor([5.1907e-09, 0.0000e+00, 3.8633e-02])}], 'in_contact': True, 'force': 2.317972421646118, 'number_of_contacts': 1}

However, when setting sim_params["use_gpu_pipeline"] = True I get nonsense numbers:

{'time': 4.933333590626717, 'physics_step': 296.0, 'contacts': [{'body0': '/World/Ant/right_back_foot', 'body1': '/World/defaultGroundPlane/GroundPlane/CollisionPlane', 'position': tensor([-4.3160e+08, -4.9734e+17, -4.3160e+08], device='cuda:0'), 'normal': tensor([-4.3160e+08, -4.9734e+17, -4.3160e+08], device='cuda:0'), 'impulse': tensor([-1.6929e+07, -1.9507e+16, -1.6929e+07], device='cuda:0')}], 'in_contact': False, 'force': 0.0, 'number_of_contacts': 1}

Can anyone reproduce this or point me to a solution?
Thanks in advance

1 Like

Unfortunately the contact report pipeline is still CPU dependent. Attempting to use it with the GPU pipeline will indeed produce incorrect results. We will make sure to note that on the documentation.

@rgasoto is this solved in the latest 2023.1.0 release?
In any case, where can I check the release notes on the new version?

i think this is what you are looking for

1 Like

sim_params["use_gpu_pipeline"] = False

Does this mean the GPU isn’t used at all? Or is it more specific than that?

@dan.sandberg from what I know (I may be wrong) enabling GPU pipeline should keep all the data internal to Isaac Sim on GPU. The simulation and rendering are run on GPU anyway, but the difference is that all the quantities you might get from the API (joint positions, velocities, etc…) should automatically live in GPU. You can check this by inspecting the device property of the returned tensors.
You can also have a look at the comment here.
As you see it says “# whether to use the GPU pipeline - data returned from Isaac Sim APIs will be on the GPU if set to True

Hi, using GPU Pipeline means that the data will not be exported back to the CPU RAM - Meaning that any attempt at reading / printing this data for code that is executed in the CPU will return wrong values. This is a more performant version of the simulation, since it doesn’t burden the CPU/GPU with memory transfer - which is known to be one of the biggest bottlenecks for GPU computing. The drawback is that things that depends on CPU code to execute (like contact reporting) will not work, even though the contact still happens and is processed by the simulation - there’s just no easy way to retrieve it.

When Not using the GPU pipeline means that it allows this readback from the GPU, so you can retrieve the simulation data from the GPU.

You can also disable GPU simulation altogether, by setting the main broadphase to CPU. Rendering will still happen on the GPU, though.

This topic was automatically closed 14 days after the last reply. New replies are no longer allowed.