Unverified Commit 2ddb90f0 authored by Mayank Mittal's avatar Mayank Mittal Committed by GitHub

Adds `SimulationContext` into the orbit module (#102)

# Description

This MR adds our own `SimulationContext` class that inherits the one
from Isaac Sim. This is motivated by two reasons:

* We want to make the configuration of the simulation context consistent
with the rest of the APIs.
* We want to override some of the functions from the `SimulationContext`
that suit our needs better.

## Type of change

- New feature (non-breaking change which adds functionality)
- Breaking change (fix or feature that would cause existing
functionality to not work as expected)
- This change requires a documentation update

## Checklist

- [x] I have run the [`pre-commit` checks](https://pre-commit.com/) with
`./orbit.sh --format`
- [x] I have made corresponding changes to the documentation
- [x] My changes generate no new warnings
- [ ] 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
parent fd72e345
[package]
# Note: Semantic Versioning is used: https://semver.org/
version = "0.8.3"
version = "0.8.4"
# Description
title = "ORBIT framework for Robot Learning"
......
Changelog
---------
0.8.4 (2023-08-02)
~~~~~~~~~~~~~~~~~~
Added
^^^^^
* Added the :class:`omni.isaac.orbit.sim.SimulationContext` class to the :mod:`omni.isaac.orbit.sim` module.
This class inherits from the :class:`omni.isaac.core.simulation_context.SimulationContext` class and adds
the ability to create a simulation context from a configuration object.
0.8.3 (2023-08-02)
~~~~~~~~~~~~~~~~~~
......
# Copyright (c) 2022, NVIDIA CORPORATION & AFFILIATES, ETH Zurich, and University of Toronto
# All rights reserved.
#
# SPDX-License-Identifier: BSD-3-Clause
"""This sub-module provides the ``SimulationContext`` class.
The :class:`SimulationContext` inherits from the :class:`omni.isaac.core.simulation_context.SimulationContext` class
to provide additional functionality for the Orbit extension. This includes configuring the simulation through
the configuration class :class:`SimulationCfg` and providing a context manager for the simulation.
"""
from .simulation_cfg import PhysicsMaterialCfg, PhysxCfg, SimulationCfg
from .simulation_context import SimulationContext
__all__ = ["PhysicsMaterialCfg", "PhysxCfg", "SimulationCfg", "SimulationContext"]
# Copyright (c) 2022, NVIDIA CORPORATION & AFFILIATES, ETH Zurich, and University of Toronto
# All rights reserved.
#
# SPDX-License-Identifier: BSD-3-Clause
"""Base configuration of the environment.
This module defines the general configuration of the environment. It includes parameters for
configuring the environment instances, viewer settings, and simulation parameters.
"""
from typing import Tuple
from omni.isaac.orbit.utils import configclass
__all__ = ["PhysicsMaterialCfg", "PhysxCfg", "SimulationCfg"]
##
# Simulation settings
##
@configclass
class PhysicsMaterialCfg:
"""Physics material parameters."""
static_friction: float = 1.0
"""The static friction coefficient. Defaults to 1.0."""
dynamic_friction: float = 1.0
"""The dynamic friction coefficient. Defaults to 1.0."""
restitution: float = 0.0
"""The restitution coefficient. Defaults to 0.0."""
improve_patch_friction: bool = False
"""Whether to enable patch friction. Defaults to False."""
combine_mode: str = "average"
"""Determines the way physics materials will be combined during collisions. Defaults to `average`.
This includes for both friction and restitution combination.
Available options are `average`, `min`, `multiply`, `multiply`, and `max`.
"""
@configclass
class PhysxCfg:
"""PhysX solver parameters.
These parameters are used to configure the PhysX solver. For more information, see the PhysX 5 SDK
documentation.
PhysX 5 supports GPU-accelerated physics simulation. This is enabled by default, but can be disabled
through the flag `use_gpu`. Unlike CPU PhysX, the GPU simulation feature is not able to dynamically
grow all the buffers. Therefore, it is necessary to provide a reasonable estimate of the buffer sizes
for GPU features. If insufficient buffer sizes are provided, the simulation will fail with errors and
lead to adverse behaviors. The buffer sizes can be adjusted through the `gpu_*` parameters.
References:
* PhysX 5 documentation: https://nvidia-omniverse.github.io/PhysX/
"""
use_gpu: bool = True
"""Enable/disable GPU accelerated dynamics simulation. Default is True.
This enables GPU-accelerated implementations for broad-phase collision checks, contact generation,
shape and body management, and constrained solver.
"""
solver_type: int = 1
"""The type of solver to use.Default is 1 (TGS).
Available solvers:
* :obj:`0`: PGS (Projective Gauss-Seidel)
* :obj:`1`: TGS (Truncated Gauss-Seidel)
"""
enable_stabilization: bool = True
"""Enable/disable additional stabilization pass in solver. Default is True."""
bounce_threshold_velocity: float = 0.5
"""Relative velocity threshold for contacts to bounce (in m/s). Default is 0.5 m/s."""
friction_offset_threshold: float = 0.04
"""Threshold for contact point to experience friction force (in m). Default is 0.04 m."""
friction_correlation_distance: float = 0.025
"""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
"""Size of rigid contact stream buffer allocated in pinned host memory. Default is 2 ** 20."""
gpu_max_rigid_patch_count: int = 80 * 1024 * 2
"""Size of the rigid contact patch stream buffer allocated in pinned host memory. Default is 80 * 2 ** 11."""
gpu_found_lost_pairs_capacity: int = 1024 * 1024 * 2
"""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.
"""
gpu_found_lost_aggregate_pairs_capacity: int = 1024 * 1024 * 32
"""Capacity of found and lost buffers in aggregate system allocated in GPU global memory.
Default is 2 ** 21.
This is used for the found/lost pair reports in AABB manager.
"""
gpu_total_aggregate_pairs_capacity: int = 1024 * 1024 * 2
"""Capacity of total number of aggregate pairs allocated in GPU global memory. Default is 2 ** 21."""
gpu_heap_capacity: int = 64 * 1024 * 1024
"""Initial capacity of the GPU and pinned host memory heaps. Additional memory will be allocated
if more memory is required. Default is 2 ** 26."""
gpu_temp_buffer_capacity: int = 16 * 1024 * 1024
"""Capacity of temp buffer allocated in pinned host memory. Default is 2 ** 24."""
gpu_max_num_partitions: int = 8
"""Limitation for the partitions in the GPU dynamics pipeline. Default is 8.
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
"""Size of soft body contacts stream buffer allocated in pinned host memory. Default is 2 ** 20."""
gpu_max_particle_contacts: int = 1024 * 1024
"""Size of particle contacts stream buffer allocated in pinned host memory. Default is 2 ** 20."""
@configclass
class SimulationCfg:
"""Configuration for simulation physics."""
physics_prim_path: str = "/physicsScene"
"""The prim path where the USD PhysicsScene is created. Default is "/physicsScene"."""
dt: float = 1.0 / 60.0
"""The physics simulation time-step (in seconds). Default is 0.0167 seconds."""
substeps: int = 1
"""The number of physics simulation steps per rendering step. Default is 1."""
gravity: Tuple[float, float, float] = (0.0, 0.0, -9.81)
"""The gravity vector (in m/s^2). Default is (0.0, 0.0, -9.81)."""
enable_scene_query_support: bool = False
"""Enable/disable scene query support for collision shapes. Default is False.
This flag allows performing collision queries (raycasts, sweeps, and overlaps) on actors and
attached shapes in the scene. This is useful for implementing custom collision detection logic
outside of the physics engine.
If set to False, the physics engine does not create the scene query manager and the scene query
functionality will not be available. However, this provides some performance speed-up.
Note:
This flag is overridden to True inside the :class:`IsaacEnv` class when running the simulation
with the GUI enabled. This is to allow certain GUI features to work properly.
"""
use_flatcache: bool = 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.
This leads to an overhead in reading the data and does not scale well with massive parallelization.
This flag allows disabling the synchronization and reading the data directly from the physics buffers.
It is recommended to set this flag to :obj:`True` when running the simulation with a large number
of primitives in the scene.
Note:
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`.
"""
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.
It is recommended to set this flag to :obj:`True` when using the TensorAPIs for contact reporting.
"""
use_gpu_pipeline: bool = True
"""Enable/disable GPU pipeline. Default is True.
If set to False, the physics data will be read as CPU buffers.
"""
device: str = "cuda:0"
"""The device for running the simulation/environment. Default is "cuda:0"."""
physx: PhysxCfg = PhysxCfg()
"""PhysX solver settings. Default is PhysxCfg()."""
default_physics_material: PhysicsMaterialCfg = PhysicsMaterialCfg()
"""Default physics material settings. Default is PhysicsMaterialCfg().
The physics engine defaults to this physics material for all the rigid body prims that do not have any
physics material specified on them.
The material is created at the path: ``{physics_prim_path}/defaultMaterial``.
"""
# Copyright (c) 2022, NVIDIA CORPORATION & AFFILIATES, ETH Zurich, and University of Toronto
# All rights reserved.
#
# SPDX-License-Identifier: BSD-3-Clause
import carb
import omni.isaac.core.utils.prims as prim_utils
import omni.isaac.core.utils.stage as stage_utils
import omni.physx
from omni.isaac.core.simulation_context import SimulationContext as _SimulationContext
from pxr import PhysxSchema
from .simulation_cfg import SimulationCfg
class SimulationContext(_SimulationContext):
"""A class to control simulation-related events such as physics stepping and rendering.
It wraps the ``SimulationContext`` class from ``omni.isaac.core`` and adds some additional
functionality such as setting up the simulation context with a configuration object.
"""
def __init__(self, cfg: SimulationCfg = None):
"""Creates a simulation context to control the simulator.
Args:
cfg (SimulationCfg, optional): The configuration of the simulation. Defaults to None,
in which case the default configuration is used.
"""
# store input
if cfg is None:
cfg = SimulationCfg()
self.cfg = cfg
# check that simulation is running
if stage_utils.get_current_stage() is None:
raise RuntimeError("The stage has not been created. Did you run the simulator?")
# set flags for simulator
# acquire settings interface
carb_settings_iface = carb.settings.get_settings()
# enable hydra scene-graph instancing
# note: this allows rendering of instanceable assets on the GUI
carb_settings_iface.set_bool("/persistent/omnihydra/useSceneGraphInstancing", True)
# 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)
# read flag for whether headless mode is enabled
# note: we read this once since it is not expected to change during runtime
self._is_headless = not carb_settings_iface.get("/app/window/enabled")
# enable scene querying if rendering is enabled
# this is needed for some GUI features
if not self._is_headless:
self.cfg.enable_scene_query_support = True
# set up flatcache interface (default is None)
# note: need to do this here because super().__init__ calls render and this variable is needed
self._flatcache_iface = None
# flatten out the simulation dictionary
sim_params = self.cfg.to_dict()
if sim_params is not None:
if "physx" in sim_params:
physx_params = sim_params.pop("physx")
sim_params.update(physx_params)
# create a simulation context to control the simulator
super().__init__(
stage_units_in_meters=1.0,
physics_dt=self.cfg.dt,
rendering_dt=self.cfg.dt * self.cfg.substeps,
backend="torch",
sim_params=sim_params,
physics_prim_path=self.cfg.physics_prim_path,
device=self.cfg.device,
)
# modify the physics material
material_path = f"{self.cfg.physics_prim_path}/defaultMaterial"
material_prim = prim_utils.get_prim_at_path(material_path)
# Apply PhysX Rigid Material schema
physx_material_api = PhysxSchema.PhysxMaterialAPI.Apply(material_prim)
# Set patch friction property
improve_patch_friction = self.cfg.default_physics_material.improve_patch_friction
physx_material_api.CreateImprovePatchFrictionAttr().Set(improve_patch_friction)
# Set combination mode for coefficients
combine_mode = self.cfg.default_physics_material.combine_mode
physx_material_api.CreateFrictionCombineModeAttr().Set(combine_mode)
physx_material_api.CreateRestitutionCombineModeAttr().Set(combine_mode)
# check if flatcache is enabled
# this is needed to flush the flatcache data into Hydra manually when calling `render()`
# ref: https://docs.omniverse.nvidia.com/prod_extensions/prod_extensions/ext_physics.html
if self.cfg.use_flatcache:
from omni.physxflatcache import get_physx_flatcache_interface
# acquire flatcache interface
self._flatcache_iface = get_physx_flatcache_interface()
"""
Operations - Override.
"""
def reset(self, soft: bool = False):
# need to load all "physics" information from the USD file
# FIXME: Remove this for Isaac Sim 2023.1 release if it will be fixed in the core.
if not soft:
omni.physx.acquire_physx_interface().force_load_physics_from_usd()
# play the simulation
super().reset(soft=soft)
def step(self, render: bool = True):
# override render settings if we are in headless mode
if self._is_headless:
render = False
# step the simulation
super().step(render=render)
def render(self, flush: bool = True):
"""Refreshes the rendering components including UI elements and view-ports.
Args:
flush (bool, optional): Whether to flush the flatcache data to update Hydra textures.
"""
# manually flush the flatcache data to update Hydra textures
if self._flatcache_iface is not None and flush:
self._flatcache_iface.update(0.0, 0.0)
# render the simulation
super().render()
"""
Operations - New.
"""
def is_headless(self) -> bool:
"""Returns whether the simulation is running in headless mode.
Note:
Headless mode is enabled when the simulator is running without a GUI.
"""
return self._is_headless
[package]
# Note: Semantic Versioning is used: https://semver.org/
version = "0.4.0"
version = "0.4.1"
# Description
title = "ORBIT Environments"
......
Changelog
---------
0.4.1 (2023-08-02)
~~~~~~~~~~~~~~~~~~
Changed
^^^^^^^
* Adapted the base :class:`IsaacEnv` class to use the :class:`SimulationContext` class from the
:mod:`omni.isaac.orbit.sim` module. This simplifies setting of simulation parameters.
0.4.0 (2023-07-26)
~~~~~~~~~~~~~~~~~~
......
......@@ -19,12 +19,11 @@ import omni.isaac.core.utils.stage as stage_utils
import omni.isaac.core.utils.torch as torch_utils
import omni.usd
from omni.isaac.cloner import GridCloner
from omni.isaac.core.simulation_context import SimulationContext
from omni.isaac.core.utils.extensions import enable_extension
from omni.isaac.core.utils.viewports import set_camera_view
from omni.isaac.orbit.sensors import * # noqa: F401, F403
from omni.isaac.orbit.sensors.sensor_base import SensorBase
from omni.isaac.orbit.sim import SimulationContext
from .isaac_env_cfg import IsaacEnvCfg
......@@ -128,24 +127,8 @@ class IsaacEnv(gym.Env):
# check that simulation is running
if stage_utils.get_current_stage() is None:
raise RuntimeError("The stage has not been created. Did you run the simulator?")
# flatten out the simulation dictionary
sim_params = self.cfg.sim.to_dict()
if sim_params is not None:
if "physx" in sim_params:
physx_params = sim_params.pop("physx")
sim_params.update(physx_params)
# set flags for simulator
self._configure_simulation_flags(sim_params)
# create a simulation context to control the simulator
self.sim = SimulationContext(
stage_units_in_meters=1.0,
physics_dt=self.physics_dt,
rendering_dt=self.rendering_dt,
backend="torch",
sim_params=sim_params,
physics_prim_path="/physicsScene",
device=self.device,
)
self.sim = SimulationContext(self.cfg.sim)
# create renderer and set camera view
self._create_viewport_render_product()
# add flag for checking closing status
......@@ -207,7 +190,7 @@ class IsaacEnv(gym.Env):
self.envs_positions = cloner.clone(
source_prim_path=self.template_env_ns,
prim_paths=self.envs_prim_paths,
replicate_physics=self.cfg.sim.replicate_physics,
replicate_physics=self.cfg.env.replicate_physics,
)
# convert environment positions to torch tensor
# self.envs_positions = torch.tensor(self.envs_positions, dtype=torch.float, device=self.device)
......@@ -325,11 +308,8 @@ class IsaacEnv(gym.Env):
if self._ui_throttle_counter % self._ui_throttle_period == 0:
self._ui_throttle_counter = 0
# here we don't render viewport so don't need to flush flatcache
self.sim.render()
self.sim.render(flush=False)
elif self.render_mode == RenderMode.FULL_RENDERING:
# manually flush the flatcache data to update Hydra textures
if self._flatcache_iface is not None:
self._flatcache_iface.update(0.0, 0.0)
# perform debug visualization
if self.cfg.viewer.debug_vis:
self._debug_vis()
......@@ -354,9 +334,6 @@ class IsaacEnv(gym.Env):
# render the scene only if rendering at every step is disabled
# this is because we do not want to render the scene twice
if not self.enable_render:
# manually flush the flatcache data to update Hydra textures
if self._flatcache_iface is not None:
self._flatcache_iface.update(0.0, 0.0)
# render the scene
self.sim.render()
# decide the rendering mode
......@@ -515,60 +492,11 @@ class IsaacEnv(gym.Env):
Helper functions - Simulation.
"""
def _configure_simulation_flags(self, sim_params: dict = None):
"""Configure simulation flags and extensions at load and run time."""
# acquire settings interface
carb_settings_iface = carb.settings.get_settings()
# enable hydra scene-graph instancing
# note: this allows rendering of instanceable assets on the GUI
carb_settings_iface.set_bool("/persistent/omnihydra/useSceneGraphInstancing", True)
# 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 sim_params["disable_contact_processing"]:
carb_settings_iface.set_bool("/physics/disableContactProcessing", True)
# set flags based on whether rendering is enabled or not
# note: enabling extensions is order-sensitive. please do not change the order.
if self.enable_render or self.enable_viewport:
# enable scene querying if rendering is enabled
# this is needed for some GUI features
sim_params["enable_scene_query_support"] = True
# load extra viewport extensions if requested
if self.enable_viewport:
# extension to enable UI buttons (otherwise we get attribute errors)
enable_extension("omni.kit.window.toolbar")
# extension to make RTX realtime and path-traced renderers
enable_extension("omni.kit.viewport.rtx")
# extension to make HydraDelegate renderers
enable_extension("omni.kit.viewport.pxr")
# enable viewport extension if full rendering is enabled
enable_extension("omni.kit.viewport.bundle")
# load extra render extensions if requested
if self.enable_viewport:
# extension for window status bar
enable_extension("omni.kit.window.status_bar")
# enable isaac replicator extension
# note: moved here since it requires to have the viewport extension to be enabled first.
enable_extension("omni.replicator.isaac")
def _create_viewport_render_product(self):
"""Create a render product of the viewport for rendering."""
# set camera view for "/OmniverseKit_Persp" camera
set_camera_view(eye=self.cfg.viewer.eye, target=self.cfg.viewer.lookat)
# check if flatcache is enabled
# this is needed to flush the flatcache data into Hydra manually when calling `env.render()`
# ref: https://docs.omniverse.nvidia.com/prod_extensions/prod_extensions/ext_physics.html
if self.sim.get_physics_context().use_flatcache:
from omni.physxflatcache import get_physx_flatcache_interface
# acquire flatcache interface
self._flatcache_iface = get_physx_flatcache_interface()
else:
self._flatcache_iface = None
# check if viewport is enabled before creating render product
if self.enable_viewport:
import omni.replicator.core as rep
......
......@@ -12,9 +12,10 @@ configuring the environment instances, viewer settings, and simulation parameter
from dataclasses import MISSING
from typing import Tuple
from omni.isaac.orbit.sim import SimulationCfg
from omni.isaac.orbit.utils import configclass
__all__ = ["IsaacEnvCfg", "EnvCfg", "ViewerCfg", "PhysxCfg", "SimCfg"]
__all__ = ["IsaacEnvCfg", "EnvCfg", "ViewerCfg"]
##
......@@ -34,6 +35,13 @@ class EnvCfg:
"""Duration of an episode (in seconds). Default is None (no limit)."""
send_time_outs: bool = True
"""Whether to send time-outs to the algorithm. Default is True."""
replicate_physics: bool = True
"""Enable/disable replication of physics schemas when using the Cloner APIs. Default is False.
Note:
In Isaac Sim 2022.2.0, domain randomization of material properties is not supported when
``replicate_physics`` is set to True.
"""
@configclass
......@@ -54,172 +62,6 @@ class ViewerCfg:
"""
##
# Simulation settings
##
@configclass
class PhysxCfg:
"""PhysX solver parameters.
These parameters are used to configure the PhysX solver. For more information, see the PhysX 5 SDK
documentation.
PhysX 5 supports GPU-accelerated physics simulation. This is enabled by default, but can be disabled
through the flag `use_gpu`. Unlike CPU PhysX, the GPU simulation feature is not able to dynamically
grow all the buffers. Therefore, it is necessary to provide a reasonable estimate of the buffer sizes
for GPU features. If insufficient buffer sizes are provided, the simulation will fail with errors and
lead to adverse behaviors. The buffer sizes can be adjusted through the `gpu_*` parameters.
References:
* PhysX 5 documentation: https://nvidia-omniverse.github.io/PhysX/
"""
use_gpu: bool = True
"""Enable/disable GPU accelerated dynamics simulation. Default is True.
This enables GPU-accelerated implementations for broad-phase collision checks, contact generation,
shape and body management, and constrained solver.
"""
solver_type: int = 1
"""The type of solver to use.Default is 1 (TGS).
Available solvers:
* :obj:`0`: PGS (Projective Gauss-Seidel)
* :obj:`1`: TGS (Truncated Gauss-Seidel)
"""
enable_stabilization: bool = True
"""Enable/disable additional stabilization pass in solver. Default is True."""
bounce_threshold_velocity: float = 0.5
"""Relative velocity threshold for contacts to bounce (in m/s). Default is 0.5 m/s."""
friction_offset_threshold: float = 0.04
"""Threshold for contact point to experience friction force (in m). Default is 0.04 m."""
friction_correlation_distance: float = 0.025
"""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
"""Size of rigid contact stream buffer allocated in pinned host memory. Default is 2 ** 20."""
gpu_max_rigid_patch_count: int = 80 * 1024 * 2
"""Size of the rigid contact patch stream buffer allocated in pinned host memory. Default is 80 * 2 ** 11."""
gpu_found_lost_pairs_capacity: int = 1024 * 1024 * 2
"""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.
"""
gpu_found_lost_aggregate_pairs_capacity: int = 1024 * 1024 * 32
"""Capacity of found and lost buffers in aggregate system allocated in GPU global memory.
Default is 2 ** 21.
This is used for the found/lost pair reports in AABB manager.
"""
gpu_total_aggregate_pairs_capacity: int = 1024 * 1024 * 2
"""Capacity of total number of aggregate pairs allocated in GPU global memory. Default is 2 ** 21."""
gpu_heap_capacity: int = 64 * 1024 * 1024
"""Initial capacity of the GPU and pinned host memory heaps. Additional memory will be allocated
if more memory is required. Default is 2 ** 26."""
gpu_temp_buffer_capacity: int = 16 * 1024 * 1024
"""Capacity of temp buffer allocated in pinned host memory. Default is 2 ** 24."""
gpu_max_num_partitions: int = 8
"""Limitation for the partitions in the GPU dynamics pipeline. Default is 8.
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
"""Size of soft body contacts stream buffer allocated in pinned host memory. Default is 2 ** 20."""
gpu_max_particle_contacts: int = 1024 * 1024
"""Size of particle contacts stream buffer allocated in pinned host memory. Default is 2 ** 20."""
@configclass
class SimCfg:
"""Configuration for simulation physics."""
dt: float = 1.0 / 60.0
"""The physics simulation time-step (in seconds). Default is 0.0167 seconds."""
substeps: int = 1
"""The number of physics simulation steps per rendering step. Default is 1."""
gravity: Tuple[float, float, float] = (0.0, 0.0, -9.81)
"""The gravity vector (in m/s^2). Default is (0.0, 0.0, -9.81)."""
enable_scene_query_support: bool = False
"""Enable/disable scene query support for collision shapes. Default is False.
This flag allows performing collision queries (raycasts, sweeps, and overlaps) on actors and
attached shapes in the scene. This is useful for implementing custom collision detection logic
outside of the physics engine.
If set to False, the physics engine does not create the scene query manager and the scene query
functionality will not be available. However, this provides some performance speed-up.
Note:
This flag is overridden to True inside the :class:`IsaacEnv` class when running the simulation
with the GUI enabled. This is to allow certain GUI features to work properly.
"""
replicate_physics: bool = True
"""Enable/disable replication of physics schemas when using the Cloner APIs. Default is False.
Note:
In Isaac Sim 2022.2.0, domain randomization of material properties is not supported when
``replicate_physics`` is set to True.
"""
use_flatcache: bool = 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.
This leads to an overhead in reading the data and does not scale well with massive parallelization.
This flag allows disabling the synchronization and reading the data directly from the physics buffers.
It is recommended to set this flag to :obj:`True` when running the simulation with a large number
of primitives in the scene.
Note:
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`.
"""
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.
It is recommended to set this flag to :obj:`True` when using the TensorAPIs for contact reporting.
"""
use_gpu_pipeline: bool = True
"""Enable/disable GPU pipeline. Default is True.
If set to False, the physics data will be read as CPU buffers.
"""
device: str = "cuda:0"
"""The device for running the simulation/environment. Default is "cuda:0"."""
physx: PhysxCfg = PhysxCfg()
"""PhysX solver settings. Default is PhysxCfg()."""
##
# Environment configuration
##
......@@ -233,5 +75,5 @@ class IsaacEnvCfg:
"""General environment configuration."""
viewer: ViewerCfg = ViewerCfg()
"""Viewer configuration. Default is ViewerCfg()."""
sim: SimCfg = SimCfg()
"""Physics simulation configuration. Default is SimCfg()."""
sim: SimulationCfg = SimulationCfg()
"""Physics simulation configuration. Default is SimulationCfg()."""
......@@ -16,6 +16,7 @@ from omni.isaac.orbit.robots.config.anymal import ANYMAL_C_CFG
from omni.isaac.orbit.robots.legged_robot import LeggedRobotCfg
from omni.isaac.orbit.sensors.contact_sensor import ContactSensorCfg
from omni.isaac.orbit.sensors.ray_caster import GridPatternCfg, RayCasterCfg
from omni.isaac.orbit.sim import SimulationCfg
from omni.isaac.orbit.terrains import TerrainImporterCfg
from omni.isaac.orbit.terrains.config.rough import ROUGH_TERRAINS_CFG
from omni.isaac.orbit.utils import configclass
......@@ -26,7 +27,7 @@ import omni.isaac.orbit_envs.locomotion.observations as Obs
import omni.isaac.orbit_envs.locomotion.randomizations as Rand
import omni.isaac.orbit_envs.locomotion.rewards as Rew
import omni.isaac.orbit_envs.locomotion.terminations as Done
from omni.isaac.orbit_envs.isaac_env_cfg import EnvCfg, IsaacEnvCfg, SimCfg, ViewerCfg
from omni.isaac.orbit_envs.isaac_env_cfg import EnvCfg, IsaacEnvCfg, ViewerCfg
from omni.isaac.orbit_envs.locomotion.actions import JointPositionActionCfg
##
......@@ -222,12 +223,12 @@ class LocomotionEnvCfg(IsaacEnvCfg):
"""Configuration for the locomotion velocity environment."""
# General Settings
env: EnvCfg = EnvCfg(num_envs=4096, env_spacing=2.5, episode_length_s=20.0)
viewer: ViewerCfg = ViewerCfg(debug_vis=True)
# Physics settings
# disable replicate physics to use physics domain randomization
# TODO: This is a temporary fix. Should be resolved in the future.
sim: SimCfg = SimCfg(dt=0.005, substeps=1, replicate_physics=False, disable_contact_processing=True)
env: EnvCfg = EnvCfg(num_envs=4096, env_spacing=2.5, episode_length_s=20.0, replicate_physics=False)
viewer: ViewerCfg = ViewerCfg(debug_vis=True)
# Physics settings
sim: SimulationCfg = SimulationCfg(dt=0.005, substeps=1, disable_contact_processing=True)
# Scene Settings
terrain: TerrainImporterCfg = TerrainImporterCfg(
......
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