Unverified Commit 0fd5e134 authored by Mayank Mittal's avatar Mayank Mittal Committed by GitHub

Adds additional parameters and utility functions to Orbit's SimulationContext class (#115)

# Description

* Added new parameters to the `SimulationContext` for setting other
quantities that can be set using the `PhyxSceneAPI`
* Added compatibility check to support flatcache/fabric naming in Isaac
Sim 2022.2 and 2023.1 versions

## Type of change

- Bug fix (non-breaking change which fixes an issue)
- This change requires a documentation update

## Checklist

- [x] I have run the [`pre-commit` checks](https://pre-commit.com/) with
`./orbit.sh --format`
- [ ] I have made corresponding changes to the documentation
- [ ] My changes generate no new warnings
- [x] I have added tests that prove my fix is effective or that my
feature works
- [x] I have updated the changelog and the corresponding version in the
extension's `config/extension.toml` file

---------
Signed-off-by: 's avatarMayank Mittal <12863862+Mayankm96@users.noreply.github.com>
Co-authored-by: 's avatarPascal Roth <57946385+pascal-roth@users.noreply.github.com>
Co-authored-by: 's avatarjsmith-bdai <142246516+jsmith-bdai@users.noreply.github.com>
parent af9bc561
[package] [package]
# Note: Semantic Versioning is used: https://semver.org/ # Note: Semantic Versioning is used: https://semver.org/
version = "0.8.11" version = "0.8.12"
# Description # Description
title = "ORBIT framework for Robot Learning" title = "ORBIT framework for Robot Learning"
......
Changelog Changelog
--------- ---------
0.8.11 (2023-08-18) 0.8.12 (2023-08-18)
~~~~~~~~~~~~~~~~~~ ~~~~~~~~~~~~~~~~~~
Added Added
^^^^^ ^^^^^
* Added other properties provided by ``PhysicsScene`` to the :class:`omni.isaac.orbit.sim.SimulationContext`
class to allow setting CCD, solver iterations, etc.
* Added commonly used functions to the :class:`SimulationContext` class itself to avoid having additional
imports from Isaac Sim when doing simple tasks such as setting camera view or retrieving the simulation settings.
Fixed
^^^^^
* Switched the notations of default buffer values in :class:`omni.isaac.orbit.sim.PhysxCfg` from multiplication
to scientific notation to avoid confusion with the values.
0.8.11 (2023-08-18)
~~~~~~~~~~~~~~~~~~~
Added
^^^^^
* Adds utility functions and configuration objects in the :mod:`omni.isaac.orbit.sim.spawners` * Adds utility functions and configuration objects in the :mod:`omni.isaac.orbit.sim.spawners`
to create the following prims in the scene: to create the following prims in the scene:
......
...@@ -10,13 +10,12 @@ configuring the environment instances, viewer settings, and simulation parameter ...@@ -10,13 +10,12 @@ configuring the environment instances, viewer settings, and simulation parameter
""" """
from typing import Tuple from typing import Tuple
from typing_extensions import Literal
from omni.isaac.orbit.utils import configclass from omni.isaac.orbit.utils import configclass
from .spawners.materials import RigidBodyMaterialCfg from .spawners.materials import RigidBodyMaterialCfg
__all__ = ["PhysxCfg", "SimulationCfg"]
@configclass @configclass
class PhysxCfg: class PhysxCfg:
...@@ -42,7 +41,7 @@ class PhysxCfg: ...@@ -42,7 +41,7 @@ class PhysxCfg:
shape and body management, and constrained solver. shape and body management, and constrained solver.
""" """
solver_type: int = 1 solver_type: Literal[0, 1] = 1
"""The type of solver to use.Default is 1 (TGS). """The type of solver to use.Default is 1 (TGS).
Available solvers: Available solvers:
...@@ -51,6 +50,66 @@ class PhysxCfg: ...@@ -51,6 +50,66 @@ class PhysxCfg:
* :obj:`1`: TGS (Truncated Gauss-Seidel) * :obj:`1`: TGS (Truncated Gauss-Seidel)
""" """
min_position_iteration_count: int = 1
"""Minimum number of solver position iterations (rigid bodies, cloth, particles etc.). Default is 1.
.. note::
Each physics actor in Omniverse specifies its own solver iteration count. The solver takes
the number of iterations specified by the actor with the highest iteration and clamps it to
the range ``[min_position_iteration_count, max_position_iteration_count]``.
.. versionchanged:: 2022.2
In Isaac Sim 2022.2.0, this parameter is used for setting both position and velocity iterations count.
"""
max_position_iteration_count: int = 255
"""Maximum number of solver position iterations (rigid bodies, cloth, particles etc.). Default is 255.
.. note::
Each physics actor in Omniverse specifies its own solver iteration count. The solver takes
the number of iterations specified by the actor with the highest iteration and clamps it to
the range ``[min_position_iteration_count, max_position_iteration_count]``.
.. versionchanged:: 2022.2
In Isaac Sim 2022.2.0, this parameter is used for setting both position and velocity iterations count.
"""
min_velocity_iteration_count: int = 0
"""Minimum number of solver position iterations (rigid bodies, cloth, particles etc.). Default is 0.
.. note::
Each physics actor in Omniverse specifies its own solver iteration count. The solver takes
the number of iterations specified by the actor with the highest iteration and clamps it to
the range ``[min_velocity_iteration_count, max_velocity_iteration_count]``.
.. versionadded:: 2023.1
This parameter is introduced in 2023.1.0. For older versions, please use :obj:`min_position_iteration_count`.
"""
max_velocity_iteration_count: int = 255
"""Maximum number of solver position iterations (rigid bodies, cloth, particles etc.). Default is 255.
.. note::
Each physics actor in Omniverse specifies its own solver iteration count. The solver takes
the number of iterations specified by the actor with the highest iteration and clamps it to
the range ``[min_velocity_iteration_count, max_velocity_iteration_count]``.
.. versionadded:: 2023.1
This parameter is introduced in 2023.1.0. For older versions, please use :obj:`max_position_iteration_count`.
"""
enable_ccd: bool = False
"""Enable a second broad-phase pass that makes it possible to prevent objects from tunneling through each other.
Default is False."""
enable_stabilization: bool = True enable_stabilization: bool = True
"""Enable/disable additional stabilization pass in solver. Default is True.""" """Enable/disable additional stabilization pass in solver. Default is True."""
...@@ -63,33 +122,36 @@ class PhysxCfg: ...@@ -63,33 +122,36 @@ class PhysxCfg:
friction_correlation_distance: float = 0.025 friction_correlation_distance: float = 0.025
"""Distance threshold for merging contacts into a single friction anchor point (in m). Default is 0.025 m.""" """Distance threshold for merging contacts into a single friction anchor point (in m). Default is 0.025 m."""
gpu_max_rigid_contact_count: int = 1024 * 1024 gpu_max_rigid_contact_count: int = 2**23
"""Size of rigid contact stream buffer allocated in pinned host memory. Default is 2 ** 20.""" """Size of rigid contact stream buffer allocated in pinned host memory. Default is 2 ** 23."""
gpu_max_rigid_patch_count: int = 80 * 1024 * 2 gpu_max_rigid_patch_count: int = 5 * 2**15
"""Size of the rigid contact patch stream buffer allocated in pinned host memory. Default is 80 * 2 ** 11.""" """Size of the rigid contact patch stream buffer allocated in pinned host memory. Default is 5 * 2 ** 15."""
gpu_found_lost_pairs_capacity: int = 1024 * 1024 * 2 gpu_found_lost_pairs_capacity: int = 2**21
"""Capacity of found and lost buffers allocated in GPU global memory. Default is 2 ** 21. """Capacity of found and lost buffers allocated in GPU global memory. Default is 2 ** 21.
This is used for the found/lost pair reports in the BP. This is used for the found/lost pair reports in the BP.
""" """
gpu_found_lost_aggregate_pairs_capacity: int = 1024 * 1024 * 32 gpu_found_lost_aggregate_pairs_capacity: int = 2**25
"""Capacity of found and lost buffers in aggregate system allocated in GPU global memory. """Capacity of found and lost buffers in aggregate system allocated in GPU global memory.
Default is 2 ** 21. Default is 2 ** 25.
This is used for the found/lost pair reports in AABB manager. This is used for the found/lost pair reports in AABB manager.
""" """
gpu_total_aggregate_pairs_capacity: int = 1024 * 1024 * 2 gpu_total_aggregate_pairs_capacity: int = 2**21
"""Capacity of total number of aggregate pairs allocated in GPU global memory. Default is 2 ** 21.""" """Capacity of total number of aggregate pairs allocated in GPU global memory. Default is 2 ** 21."""
gpu_heap_capacity: int = 64 * 1024 * 1024 gpu_collision_stack_size: int = 2**26
"""Size of the collision stack buffer allocated in pinned host memory. Default is 2 ** 26."""
gpu_heap_capacity: int = 2**26
"""Initial capacity of the GPU and pinned host memory heaps. Additional memory will be allocated """Initial capacity of the GPU and pinned host memory heaps. Additional memory will be allocated
if more memory is required. Default is 2 ** 26.""" if more memory is required. Default is 2 ** 26."""
gpu_temp_buffer_capacity: int = 16 * 1024 * 1024 gpu_temp_buffer_capacity: int = 2**24
"""Capacity of temp buffer allocated in pinned host memory. Default is 2 ** 24.""" """Capacity of temp buffer allocated in pinned host memory. Default is 2 ** 24."""
gpu_max_num_partitions: int = 8 gpu_max_num_partitions: int = 8
...@@ -98,10 +160,10 @@ class PhysxCfg: ...@@ -98,10 +160,10 @@ class PhysxCfg:
This variable must be power of 2. A value greater than 32 is currently not supported. Range: (1, 32) This variable must be power of 2. A value greater than 32 is currently not supported. Range: (1, 32)
""" """
gpu_max_soft_body_contacts: int = 1024 * 1024 gpu_max_soft_body_contacts: int = 2**20
"""Size of soft body contacts stream buffer allocated in pinned host memory. Default is 2 ** 20.""" """Size of soft body contacts stream buffer allocated in pinned host memory. Default is 2 ** 20."""
gpu_max_particle_contacts: int = 1024 * 1024 gpu_max_particle_contacts: int = 2**20
"""Size of particle contacts stream buffer allocated in pinned host memory. Default is 2 ** 20.""" """Size of particle contacts stream buffer allocated in pinned host memory. Default is 2 ** 20."""
...@@ -136,7 +198,7 @@ class SimulationCfg: ...@@ -136,7 +198,7 @@ class SimulationCfg:
with the GUI enabled. This is to allow certain GUI features to work properly. with the GUI enabled. This is to allow certain GUI features to work properly.
""" """
use_flatcache: bool = True use_fabric: bool = True
"""Enable/disable reading of physics buffers directly. Default is True. """Enable/disable reading of physics buffers directly. Default is True.
When running the simulation, updates in the states in the scene is normally synchronized with USD. When running the simulation, updates in the states in the scene is normally synchronized with USD.
...@@ -149,6 +211,18 @@ class SimulationCfg: ...@@ -149,6 +211,18 @@ class SimulationCfg:
Note: Note:
When enabled, the GUI will not update the physics parameters in real-time. To enable real-time When enabled, the GUI will not update the physics parameters in real-time. To enable real-time
updates, please set this flag to :obj:`False`. updates, please set this flag to :obj:`False`.
.. versionadded:: 2023.1
This flag is introduced in 2023.1.0. For older versions, please use :obj:`use_flatcache` instead.
"""
use_flatcache: bool = True
"""Enable/disable reading of physics buffers directly. Default is True.
.. deprecated:: 2023.1
This flag is deprecated and will be removed in the future. Please use :obj:`use_fabric` instead.
""" """
disable_contact_processing: bool = False disable_contact_processing: bool = False
......
...@@ -143,7 +143,7 @@ def spawn_from_urdf( ...@@ -143,7 +143,7 @@ def spawn_from_urdf(
return prim_utils.get_prim_at_path(prim_path) return prim_utils.get_prim_at_path(prim_path)
def spawn_ground_plane(prim_path: str, cfg: from_files_cfg.GroundPlaneCfg, *kwargs) -> Usd.Prim: def spawn_ground_plane(prim_path: str, cfg: from_files_cfg.GroundPlaneCfg, **kwargs) -> Usd.Prim:
"""Spawns a ground plane into the scene. """Spawns a ground plane into the scene.
This function loads the USD file containing the grid plane asset from Isaac Sim. It may This function loads the USD file containing the grid plane asset from Isaac Sim. It may
......
...@@ -277,13 +277,15 @@ def bind_visual_material( ...@@ -277,13 +277,15 @@ def bind_visual_material(
binding_strength = "weakerThanDescendants" binding_strength = "weakerThanDescendants"
# obtain material binding API # obtain material binding API
# note: we prefer using the command here as it is more robust than the USD API # note: we prefer using the command here as it is more robust than the USD API
omni.kit.commands.execute( success, _ = omni.kit.commands.execute(
"BindMaterialCommand", "BindMaterialCommand",
prim_path=prim_path, prim_path=prim_path,
material_path=material_path, material_path=material_path,
strength=binding_strength, strength=binding_strength,
stage=stage, stage=stage,
) )
# return success
return success
@apply_nested @apply_nested
...@@ -293,7 +295,8 @@ def bind_physics_material( ...@@ -293,7 +295,8 @@ def bind_physics_material(
"""Bind a physics material to a prim. """Bind a physics material to a prim.
`Physics material`_ can be applied only to a prim with physics-enabled on them. This includes having `Physics material`_ can be applied only to a prim with physics-enabled on them. This includes having
collision APIs, or deformable body APIs, or being a particle system. collision APIs, or deformable body APIs, or being a particle system. In case the prim does not have
any of these APIs, the function will not apply the material and return False.
.. note:: .. note::
The function is decorated with :meth:`apply_nested` to allow applying the function to a prim path The function is decorated with :meth:`apply_nested` to allow applying the function to a prim path
...@@ -311,7 +314,6 @@ def bind_physics_material( ...@@ -311,7 +314,6 @@ def bind_physics_material(
Raises: Raises:
ValueError: If the provided prim paths do not exist on stage. ValueError: If the provided prim paths do not exist on stage.
ValueError: When prim at specified path is not physics-enabled.
""" """
# resolve stage # resolve stage
if stage is None: if stage is None:
...@@ -329,10 +331,11 @@ def bind_physics_material( ...@@ -329,10 +331,11 @@ def bind_physics_material(
has_deformable_body = prim.HasAPI(PhysxSchema.PhysxDeformableBodyAPI) has_deformable_body = prim.HasAPI(PhysxSchema.PhysxDeformableBodyAPI)
has_particle_system = prim.IsA(PhysxSchema.PhysxParticleSystem) has_particle_system = prim.IsA(PhysxSchema.PhysxParticleSystem)
if not (has_physics_scene_api or has_collider or has_deformable_body or has_particle_system): if not (has_physics_scene_api or has_collider or has_deformable_body or has_particle_system):
raise ValueError( carb.log_verbose(
f"Cannot apply physics material '{material_path}' on prim '{prim_path}'. It is neither a" f"Cannot apply physics material '{material_path}' on prim '{prim_path}'. It is neither a"
" PhysX scene, collider, a deformable body, nor a particle system." " PhysX scene, collider, a deformable body, nor a particle system."
) )
return False
# obtain material binding API # obtain material binding API
if prim.HasAPI(UsdShade.MaterialBindingAPI): if prim.HasAPI(UsdShade.MaterialBindingAPI):
...@@ -348,3 +351,5 @@ def bind_physics_material( ...@@ -348,3 +351,5 @@ def bind_physics_material(
binding_strength = UsdShade.Tokens.weakerThanDescendants binding_strength = UsdShade.Tokens.weakerThanDescendants
# apply the material # apply the material
material_binding_api.Bind(material, bindingStrength=binding_strength, materialPurpose="physics") # type: ignore material_binding_api.Bind(material, bindingStrength=binding_strength, materialPurpose="physics") # type: ignore
# return success
return True
# Copyright (c) 2022, NVIDIA CORPORATION & AFFILIATES, ETH Zurich, and University of Toronto
# All rights reserved.
#
# SPDX-License-Identifier: BSD-3-Clause
"""Launch Isaac Sim Simulator first."""
from omni.isaac.orbit.app import AppLauncher
# launch omniverse app
simulation_app = AppLauncher(headless=True).app
"""Rest everything follows."""
import numpy as np
import traceback
import unittest
import carb
import omni.isaac.core.utils.prims as prim_utils
from omni.isaac.core.simulation_context import SimulationContext as IsaacSimulationContext
from omni.isaac.orbit.sim import SimulationCfg, SimulationContext
class TestSimulationContext(unittest.TestCase):
"""Test fixture for wrapper around simulation context."""
def setUp(self) -> None:
"""Create a blank new stage for each test."""
# Load kit helper
SimulationContext.clear_instance()
def test_singleton(self):
"""Tests that the singleton is working."""
sim1 = SimulationContext()
sim2 = SimulationContext()
sim3 = IsaacSimulationContext()
self.assertIs(sim1, sim2)
self.assertIs(sim1, sim3)
# try to delete the singleton
sim2.__del__()
self.assertTrue(sim1.instance() is None)
# create new instance
sim4 = SimulationContext()
self.assertIsNot(sim1, sim4)
self.assertIsNot(sim3, sim4)
self.assertIs(sim1.instance(), sim4.instance())
self.assertIs(sim3.instance(), sim4.instance())
# clear instance
sim3.clear_instance()
def test_initialization(self):
"""Test the simulation config."""
cfg = SimulationCfg(physics_prim_path="/Physics/PhysX", substeps=5, gravity=(0.0, -0.5, -0.5))
sim = SimulationContext(cfg)
# TODO: Figure out why keyword argument doesn't work.
# note: added a fix in Isaac Sim 2023.1 for this.
# sim = SimulationContext(cfg=cfg)
# check valid settings
self.assertEqual(sim.get_physics_dt(), cfg.dt)
self.assertEqual(sim.get_rendering_dt(), cfg.dt * cfg.substeps)
# check valid paths
self.assertTrue(prim_utils.is_prim_path_valid("/Physics/PhysX"))
self.assertTrue(prim_utils.is_prim_path_valid("/Physics/PhysX/defaultMaterial"))
# check valid gravity
gravity_dir, gravity_mag = sim.get_physics_context().get_gravity()
gravity = np.array(gravity_dir) * gravity_mag
np.testing.assert_almost_equal(gravity, cfg.gravity)
def test_sim_version(self):
"""Test obtaining the version."""
sim = SimulationContext()
version = sim.get_version()
self.assertTrue(len(version) > 0)
self.assertTrue(version[0] >= 2022)
def test_carb_setting(self):
"""Test setting carb settings."""
sim = SimulationContext()
# known carb setting
sim.set_setting("/physics/physxDispatcher", False)
self.assertEqual(sim.get_setting("/physics/physxDispatcher"), False)
# unknown carb setting
sim.set_setting("/myExt/using_omniverse_version", sim.get_version())
self.assertSequenceEqual(sim.get_setting("/myExt/using_omniverse_version"), sim.get_version())
if __name__ == "__main__":
try:
unittest.main()
except Exception as err:
carb.log_error(err)
carb.log_error(traceback.format_exc())
raise
finally:
# close sim app
simulation_app.close()
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment