Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Removes the flag disable_contact_processing from SimulationContext #1861

Open
wants to merge 7 commits into
base: main
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all 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
93 changes: 46 additions & 47 deletions docs/source/migration/migrating_from_omniisaacgymenvs.rst
Original file line number Diff line number Diff line change
Expand Up @@ -70,53 +70,52 @@ depending on the complexity of the environment, the number of expected contacts
and the number of actors in the environment. The :class:`~isaaclab.sim.PhysxCfg` class provides access
for setting the GPU buffer dimensions.

+--------------------------------------------------------------+-------------------------------------------------------------------+
| | |
|.. code-block:: yaml |.. code-block:: python |
| | |
| # OmniIsaacGymEnvs | # IsaacLab |
| sim: | sim: SimulationCfg = SimulationCfg( |
| | device = "cuda:0" # can be "cpu", "cuda", "cuda:<device_id>" |
| dt: 0.0083 # 1/120 s | dt=1 / 120, |
| use_gpu_pipeline: ${eq:${...pipeline},"gpu"} | # use_gpu_pipeline is deduced from the device |
| use_fabric: True | use_fabric=True, |
| enable_scene_query_support: False | enable_scene_query_support=False, |
| disable_contact_processing: False | disable_contact_processing=False, |
| gravity: [0.0, 0.0, -9.81] | gravity=(0.0, 0.0, -9.81), |
| | |
| default_physics_material: | physics_material=RigidBodyMaterialCfg( |
| static_friction: 1.0 | static_friction=1.0, |
| dynamic_friction: 1.0 | dynamic_friction=1.0, |
| restitution: 0.0 | restitution=0.0 |
| | ) |
| physx: | physx: PhysxCfg = PhysxCfg( |
| worker_thread_count: ${....num_threads} | # worker_thread_count is no longer needed |
| solver_type: ${....solver_type} | solver_type=1, |
| use_gpu: ${contains:"cuda",${....sim_device}} | # use_gpu is deduced from the device |
| solver_position_iteration_count: 4 | max_position_iteration_count=4, |
| solver_velocity_iteration_count: 0 | max_velocity_iteration_count=0, |
| contact_offset: 0.02 | # moved to actor config |
| rest_offset: 0.001 | # moved to actor config |
| bounce_threshold_velocity: 0.2 | bounce_threshold_velocity=0.2, |
| friction_offset_threshold: 0.04 | friction_offset_threshold=0.04, |
| friction_correlation_distance: 0.025 | friction_correlation_distance=0.025, |
| enable_sleeping: True | # enable_sleeping is no longer needed |
| enable_stabilization: True | enable_stabilization=True, |
| max_depenetration_velocity: 100.0 | # moved to RigidBodyPropertiesCfg |
| | |
| gpu_max_rigid_contact_count: 524288 | gpu_max_rigid_contact_count=2**23, |
| gpu_max_rigid_patch_count: 81920 | gpu_max_rigid_patch_count=5 * 2**15, |
| gpu_found_lost_pairs_capacity: 1024 | gpu_found_lost_pairs_capacity=2**21, |
| gpu_found_lost_aggregate_pairs_capacity: 262144 | gpu_found_lost_aggregate_pairs_capacity=2**25, |
| gpu_total_aggregate_pairs_capacity: 1024 | gpu_total_aggregate_pairs_capacity=2**21, |
| gpu_heap_capacity: 67108864 | gpu_heap_capacity=2**26, |
| gpu_temp_buffer_capacity: 16777216 | gpu_temp_buffer_capacity=2**24, |
| gpu_max_num_partitions: 8 | gpu_max_num_partitions=8, |
| gpu_max_soft_body_contacts: 1048576 | gpu_max_soft_body_contacts=2**20, |
| gpu_max_particle_contacts: 1048576 | gpu_max_particle_contacts=2**20, |
| | ) |
| | ) |
+--------------------------------------------------------------+-------------------------------------------------------------------+
+--------------------------------------------------+---------------------------------------------------------------+
|| || |
|| || |
|| # OmniIsaacGymEnvs || # IsaacLab |
|| sim: || sim: SimulationCfg = SimulationCfg( |
|| || device = "cuda:0" # can be "cpu", "cuda", "cuda:<device_id>" |
|| dt: 0.0083 # 1/120 s || dt=1 / 120, |
|| use_gpu_pipeline: ${eq:${...pipeline},"gpu"} || # use_gpu_pipeline is deduced from the device |
|| use_fabric: True || use_fabric=True, |
|| enable_scene_query_support: False || enable_scene_query_support=False, |
|| disable_contact_processing: False || |
|| gravity: [0.0, 0.0, -9.81] || gravity=(0.0, 0.0, -9.81), |
|| || |
|| default_physics_material: || physics_material=RigidBodyMaterialCfg( |
|| static_friction: 1.0 || static_friction=1.0, |
|| dynamic_friction: 1.0 || dynamic_friction=1.0, |
|| restitution: 0.0 || restitution=0.0 |
|| || ) |
|| physx: || physx: PhysxCfg = PhysxCfg( |
|| worker_thread_count: ${....num_threads} || # worker_thread_count is no longer needed |
|| solver_type: ${....solver_type} || solver_type=1, |
|| use_gpu: ${contains:"cuda",${....sim_device}} || # use_gpu is deduced from the device |
|| solver_position_iteration_count: 4 || max_position_iteration_count=4, |
|| solver_velocity_iteration_count: 0 || max_velocity_iteration_count=0, |
|| contact_offset: 0.02 || # moved to actor config |
|| rest_offset: 0.001 || # moved to actor config |
|| bounce_threshold_velocity: 0.2 || bounce_threshold_velocity=0.2, |
|| friction_offset_threshold: 0.04 || friction_offset_threshold=0.04, |
|| friction_correlation_distance: 0.025 || friction_correlation_distance=0.025, |
|| enable_sleeping: True || # enable_sleeping is no longer needed |
|| enable_stabilization: True || enable_stabilization=True, |
|| max_depenetration_velocity: 100.0 || # moved to RigidBodyPropertiesCfg |
|| || |
|| gpu_max_rigid_contact_count: 524288 || gpu_max_rigid_contact_count=2**23, |
|| gpu_max_rigid_patch_count: 81920 || gpu_max_rigid_patch_count=5 * 2**15, |
|| gpu_found_lost_pairs_capacity: 1024 || gpu_found_lost_pairs_capacity=2**21, |
|| gpu_found_lost_aggregate_pairs_capacity: 262144 || gpu_found_lost_aggregate_pairs_capacity=2**25, |
|| gpu_total_aggregate_pairs_capacity: 1024 || gpu_total_aggregate_pairs_capacity=2**21, |
|| gpu_heap_capacity: 67108864 || gpu_heap_capacity=2**26, |
|| gpu_temp_buffer_capacity: 16777216 || gpu_temp_buffer_capacity=2**24, |
|| gpu_max_num_partitions: 8 || gpu_max_num_partitions=8, |
|| gpu_max_soft_body_contacts: 1048576 || gpu_max_soft_body_contacts=2**20, |
|| gpu_max_particle_contacts: 1048576 || gpu_max_particle_contacts=2**20, |
|| || ) |
|| || ) |
+--------------------------------------------------+---------------------------------------------------------------+

Parameters such as ``add_ground_plane`` and ``add_distant_light`` are now part of the task logic when creating the scene.
``enable_cameras`` is now a command line argument ``--enable_cameras`` that can be passed directly to the training script.
Expand Down
2 changes: 1 addition & 1 deletion source/isaaclab/config/extension.toml
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
[package]

# Note: Semantic Versioning is used: https://semver.org/
version = "0.34.1"
version = "0.35.1"

# Description
title = "Isaac Lab framework for Robot Learning"
Expand Down
19 changes: 19 additions & 0 deletions source/isaaclab/docs/CHANGELOG.rst
Original file line number Diff line number Diff line change
@@ -1,6 +1,24 @@
Changelog
---------

0.35.0 (2025-02-14)
~~~~~~~~~~~~~~~~~~~

Removed
^^^^^^^

* Removed the attribute ``disable_contact_processing`` from :class:`~isaaclab.sim.SimulationContact`.

Changed
^^^^^^^

* Enabled the physics flag for disabling contact processing in the :class:`~isaaclab.sim.SimulationContact`
class. This means that by default, no contact reporting is done by the physics engine, which should provide
a performance boost in simulations with no contact processing requirements.
* Disabled the physics flag for disabling contact processing in the :class:`~isaaclab.sensors.ContactSensor`
class when the sensor is created to allow contact reporting for the sensor.


0.34.1 (2025-02-17)
~~~~~~~~~~~~~~~~~~~

Expand All @@ -11,6 +29,7 @@ Fixed
to prevent any unexpected behavior during inference.



0.34.0 (2025-02-14)
~~~~~~~~~~~~~~~~~~~

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -12,6 +12,7 @@
from collections.abc import Sequence
from typing import TYPE_CHECKING

import carb
import omni.physics.tensors.impl.api as physx
from pxr import PhysxSchema

Expand Down Expand Up @@ -70,6 +71,11 @@ def __init__(self, cfg: ContactSensorCfg):
"""
# initialize base class
super().__init__(cfg)

# Enable contact processing
carb_settings_iface = carb.settings.get_settings()
carb_settings_iface.set_bool("/physics/disableContactProcessing", False)

# Create empty variables for storing output data
self._data: ContactSensorData = ContactSensorData()
# initialize self._body_physx_view for running in extension mode
Expand Down
12 changes: 0 additions & 12 deletions source/isaaclab/isaaclab/sim/simulation_cfg.py
Original file line number Diff line number Diff line change
Expand Up @@ -266,18 +266,6 @@ class SimulationCfg:
updates, please set this flag to :obj:`False`.
"""

disable_contact_processing: bool = False
"""Enable/disable contact processing. Default is False.

By default, the physics engine processes all the contacts in the scene. However, reporting this contact
information can be expensive due to its combinatorial complexity. This flag allows disabling the contact
processing and querying the contacts manually by the user over a limited set of primitives in the scene.

.. note::

It is required to set this flag to :obj:`True` when using the TensorAPIs for contact reporting.
"""

physx: PhysxCfg = PhysxCfg()
"""PhysX solver settings. Default is PhysxCfg()."""

Expand Down
15 changes: 10 additions & 5 deletions source/isaaclab/isaaclab/sim/simulation_context.py
Original file line number Diff line number Diff line change
Expand Up @@ -130,11 +130,16 @@ def __init__(self, cfg: SimulationCfg | None = None):
# change dispatcher to use the default dispatcher in PhysX SDK instead of carb tasking
# note: dispatcher handles how threads are launched for multi-threaded physics
carb_settings_iface.set_bool("/physics/physxDispatcher", True)
# disable contact processing in omni.physx if requested
# note: helpful when creating contact reporting over limited number of objects in the scene
if self.cfg.disable_contact_processing:
carb_settings_iface.set_bool("/physics/disableContactProcessing", True)
# enable custom geometry for cylinder and cone collision shapes to allow contact reporting for them
# disable contact processing in omni.physx
# note: we disable it by default to avoid the overhead of contact processing when it isn't needed.
# The physics flag gets enabled when a contact sensor is created.
if hasattr(self.cfg, "disable_contact_processing"):
omni.log.error(
"The `disable_contact_processing` attribute is deprecated. This flag is always set to True, "
" unless the contact sensor is enabled."
)
carb_settings_iface.set_bool("/physics/disableContactProcessing", True)
# disable custom geometry for cylinder and cone collision shapes to allow contact reporting for them
# reason: cylinders and cones aren't natively supported by PhysX so we need to use custom geometry flags
# reference: https://nvidia-omniverse.github.io/PhysX/physx/5.4.1/docs/Geometry.html?highlight=capsule#geometry
carb_settings_iface.set_bool("/physics/collisionConeCustomGeometry", False)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -63,7 +63,6 @@ class AnymalCFlatEnvCfg(DirectRLEnvCfg):
sim: SimulationCfg = SimulationCfg(
dt=1 / 200,
render_interval=decimation,
disable_contact_processing=True,
physics_material=sim_utils.RigidBodyMaterialCfg(
friction_combine_mode="multiply",
restitution_combine_mode="multiply",
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -36,7 +36,6 @@ class FrankaCabinetEnvCfg(DirectRLEnvCfg):
sim: SimulationCfg = SimulationCfg(
dt=1 / 120,
render_interval=decimation,
disable_contact_processing=True,
physics_material=sim_utils.RigidBodyMaterialCfg(
friction_combine_mode="multiply",
restitution_combine_mode="multiply",
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -62,7 +62,6 @@ class QuadcopterEnvCfg(DirectRLEnvCfg):
sim: SimulationCfg = SimulationCfg(
dt=1 / 100,
render_interval=decimation,
disable_contact_processing=True,
physics_material=sim_utils.RigidBodyMaterialCfg(
friction_combine_mode="multiply",
restitution_combine_mode="multiply",
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -319,7 +319,6 @@ def __post_init__(self):
# simulation settings
self.sim.dt = 0.002 # 500 Hz
self.sim.render_interval = self.decimation
self.sim.disable_contact_processing = True
self.sim.physics_material.static_friction = 1.0
self.sim.physics_material.dynamic_friction = 1.0
self.sim.physics_material.friction_combine_mode = "multiply"
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -301,7 +301,6 @@ def __post_init__(self):
# simulation settings
self.sim.dt = 0.005
self.sim.render_interval = self.decimation
self.sim.disable_contact_processing = True
self.sim.physics_material = self.scene.terrain.physics_material
self.sim.physx.gpu_max_rigid_patch_count = 10 * 2**15
# update sensor update periods
Expand Down