isaaclab.sim#
Sub-package containing simulation-specific functionalities.
These include:
Ability to spawn different objects and materials into Omniverse
Define and modify various schemas on USD prims
Converters to obtain USD file from other file formats (such as URDF, OBJ, STL, FBX)
Utility class to control the simulator
Note
Currently, only a subset of all possible schemas and prims in Omniverse are supported. We are expanding the these set of functions on a need basis. In case, there are specific prims or schemas that you would like to include, please open an issue on GitHub as a feature request elaborating on the required application.
To make it convenient to use the module, we recommend importing the module as follows:
import isaaclab.sim as sim_utils
Submodules
Sub-module containing converters for converting various file types to USD. |
|
Sub-module containing utilities for schemas used in Omniverse. |
|
Sub-module containing utilities for creating prims in Omniverse. |
|
Classes
A class to control simulation-related events such as physics stepping and rendering. |
|
Configuration for simulation physics. |
|
Configuration for PhysX solver-related parameters. |
|
Configuration for Omniverse RTX Renderer. |
Functions
Context manager to build a simulation context with the provided settings. |
Simulation Context#
- class isaaclab.sim.SimulationContext[source]#
Bases:
SimulationContextA class to control simulation-related events such as physics stepping and rendering.
The simulation context helps control various simulation aspects. This includes:
configure the simulator with different settings such as the physics time-step, the number of physics substeps, and the physics solver parameters (for more information, see
isaaclab.sim.SimulationCfg)playing, pausing, stepping and stopping the simulation
adding and removing callbacks to different simulation events such as physics stepping, rendering, etc.
This class inherits from the
isaacsim.core.api.simulation_context.SimulationContextclass and adds additional functionalities such as setting up the simulation context with a configuration object, exposing other commonly used simulator-related functions, and performing version checks of Isaac Sim to ensure compatibility between releases.The simulation context is a singleton object. This means that there can only be one instance of the simulation context at any given time. This is enforced by the parent class. Therefore, it is not possible to create multiple instances of the simulation context. Instead, the simulation context can be accessed using the
instance()method.Attention
Since we only support the PyTorch backend for simulation, the simulation context is configured to use the
torchbackend by default. This means that all the data structures used in the simulation aretorch.Tensorobjects.The simulation context can be used in two different modes of operations:
Standalone python script: In this mode, the user has full control over the simulation and can trigger stepping events synchronously (i.e. as a blocking call). In this case the user has to manually call
step()step the physics simulation andrender()to render the scene.Omniverse extension: In this mode, the user has limited control over the simulation stepping and all the simulation events are triggered asynchronously (i.e. as a non-blocking call). In this case, the user can only trigger the simulation to start, pause, and stop. The simulation takes care of stepping the physics simulation and rendering the scene.
Based on above, for most functions in this class there is an equivalent function that is suffixed with
_async. The_asyncfunctions are used in the Omniverse extension mode and the non-_asyncfunctions are used in the standalone python script mode.Classes:
Different rendering modes for the simulation.
Methods:
__init__([cfg])Creates a simulation context to control the simulator.
has_gui()Returns whether the simulation has a GUI enabled.
Returns whether the simulation has any RTX-rendering related sensors.
Returns whether the fabric interface is enabled.
Returns the version of the simulator.
set_camera_view(eye, target[, camera_prim_path])Set the location and target of the viewport camera in the stage.
set_render_mode(mode)Change the current render mode of the simulation.
set_setting(name, value)Set simulation settings using the Carbonite SDK.
get_setting(name)Read the simulation setting using the Carbonite SDK.
forward()Updates articulation kinematics and fabric for rendering.
Returns stage handle used during scene creation.
step([render])Steps the simulation.
render([mode])Refreshes the rendering components including UI elements and view-ports depending on the render mode.
Attributes:
Device used by the simulation.
- class RenderMode[source]#
Bases:
IntEnumDifferent rendering modes for the simulation.
Render modes correspond to how the viewport and other UI elements (such as listeners to keyboard or mouse events) are updated. There are three main components that can be updated when the simulation is rendered:
UI elements and other extensions: These are UI elements (such as buttons, sliders, etc.) and other extensions that are running in the background that need to be updated when the simulation is running.
Cameras: These are typically based on Hydra textures and are used to render the scene from different viewpoints. They can be attached to a viewport or be used independently to render the scene.
Viewports: These are windows where you can see the rendered scene.
Updating each of the above components has a different overhead. For example, updating the viewports is computationally expensive compared to updating the UI elements. Therefore, it is useful to be able to control what is updated when the simulation is rendered. This is where the render mode comes in. There are four different render modes:
NO_GUI_OR_RENDERING: The simulation is running without a GUI and off-screen rendering flag is disabled, so none of the above are updated.NO_RENDERING: No rendering, where only 1 is updated at a lower rate.PARTIAL_RENDERING: Partial rendering, where only 1 and 2 are updated.FULL_RENDERING: Full rendering, where everything (1, 2, 3) is updated.
Attributes:
The simulation is running without a GUI and off-screen rendering is disabled.
No rendering, where only other UI elements are updated at a lower rate.
Partial rendering, where the simulation cameras and UI elements are updated.
Full rendering, where all the simulation viewports, cameras and UI elements are updated.
Methods:
__new__(value)- NO_GUI_OR_RENDERING = -1#
The simulation is running without a GUI and off-screen rendering is disabled.
- NO_RENDERING = 0#
No rendering, where only other UI elements are updated at a lower rate.
- PARTIAL_RENDERING = 1#
Partial rendering, where the simulation cameras and UI elements are updated.
- FULL_RENDERING = 2#
Full rendering, where all the simulation viewports, cameras and UI elements are updated.
- __new__(value)#
- __init__(cfg: SimulationCfg | None = None)[source]#
Creates a simulation context to control the simulator.
- Parameters:
cfg – The configuration of the simulation. Defaults to None, in which case the default configuration is used.
- property device: str#
Device used by the simulation.
Note
In Omniverse, it is possible to configure multiple GPUs for rendering, while physics engine operates on a single GPU. This function returns the device that is used for physics simulation.
- has_gui() bool[source]#
Returns whether the simulation has a GUI enabled.
True if the simulation has a GUI enabled either locally or live-streamed.
- has_rtx_sensors() bool[source]#
Returns whether the simulation has any RTX-rendering related sensors.
This function returns the value of the simulation parameter
"/isaaclab/render/rtx_sensors". The parameter is set to True when instances of RTX-related sensors (cameras or LiDARs) are created using Isaac Lab’s sensor classes.True if the simulation has RTX sensors (such as USD Cameras or LiDARs).
For more information, please check NVIDIA RTX documentation.
- is_fabric_enabled() bool[source]#
Returns whether the fabric interface is enabled.
When fabric interface is enabled, USD read/write operations are disabled. Instead all applications read and write the simulation state directly from the fabric interface. This reduces a lot of overhead that occurs during USD read/write operations.
For more information, please check Fabric documentation.
- get_version() tuple[int, int, int][source]#
Returns the version of the simulator.
This is a wrapper around the
isaacsim.core.version.get_version()function.The returned tuple contains the following information:
Major version (int): This is the year of the release (e.g. 2022).
Minor version (int): This is the half-year of the release (e.g. 1 or 2).
Patch version (int): This is the patch number of the release (e.g. 0).
- set_camera_view(eye: tuple[float, float, float], target: tuple[float, float, float], camera_prim_path: str = '/OmniverseKit_Persp')[source]#
Set the location and target of the viewport camera in the stage.
Note
This is a wrapper around the \(isaacsim.core.utils.viewports.set_camera_view\) function. It is provided here for convenience to reduce the amount of imports needed.
- Parameters:
eye – The location of the camera eye.
target – The location of the camera target.
camera_prim_path – The path to the camera primitive in the stage. Defaults to “/OmniverseKit_Persp”.
- set_render_mode(mode: RenderMode)[source]#
Change the current render mode of the simulation.
Please see
RenderModefor more information on the different render modes.Note
When no GUI is available (locally or livestreamed), we do not need to choose whether the viewport needs to render or not (since there is no GUI). Thus, in this case, calling the function will not change the render mode.
- Parameters:
mode (RenderMode) – The rendering mode. If different than SimulationContext’s rendering mode,
mode. (SimulationContext's mode is changed to the new) –
- Raises:
ValueError – If the input mode is not supported.
- set_setting(name: str, value: Any)[source]#
Set simulation settings using the Carbonite SDK.
Note
If the input setting name does not exist, it will be created. If it does exist, the value will be overwritten. Please make sure to use the correct setting name.
To understand the settings interface, please refer to the Carbonite SDK documentation.
- Parameters:
name – The name of the setting.
value – The value of the setting.
- get_setting(name: str) Any[source]#
Read the simulation setting using the Carbonite SDK.
- Parameters:
name – The name of the setting.
- Returns:
The value of the setting.
- get_initial_stage() pxr.Usd.Stage[source]#
Returns stage handle used during scene creation.
- Returns:
The stage used during scene creation.
- step(render: bool = True)[source]#
Steps the simulation.
Note
This function blocks if the timeline is paused. It only returns when the timeline is playing.
- Parameters:
render – Whether to render the scene after stepping the physics simulation. If set to False, the scene is not rendered and only the physics simulation is stepped.
- render(mode: RenderMode | None = None)[source]#
Refreshes the rendering components including UI elements and view-ports depending on the render mode.
This function is used to refresh the rendering components of the simulation. This includes updating the view-ports, UI elements, and other extensions (besides physics simulation) that are running in the background. The rendering components are refreshed based on the render mode.
Please see
RenderModefor more information on the different render modes.- Parameters:
mode – The rendering mode. Defaults to None, in which case the current rendering mode is used.
Simulation Configuration#
- class isaaclab.sim.SimulationCfg[source]#
Bases:
objectConfiguration for simulation physics.
Attributes:
The prim path where the USD PhysicsScene is created.
The device to run the simulation on.
The physics simulation time-step (in seconds).
The number of physics simulation steps per rendering step.
The gravity vector (in m/s^2).
Enable/disable scene query support for collision shapes.
Enable/disable reading of physics buffers directly.
PhysX solver settings.
Default physics material settings for rigid bodies.
Render settings.
If stage is first created in memory.
The logging level.
Save logs to a file.
- physics_prim_path: str#
The prim path where the USD PhysicsScene is created. Default is “/physicsScene”.
- device: str#
The device to run the simulation on. Default is
"cuda:0".Valid options are:
"cpu": Use CPU."cuda": Use GPU, where the device ID is inferred fromAppLauncher’s config."cuda:N": Use GPU, where N is the device ID. For example, “cuda:0”.
- gravity: tuple[float, float, float]#
The gravity vector (in m/s^2). Default is (0.0, 0.0, -9.81).
If set to (0.0, 0.0, 0.0), gravity is disabled.
- enable_scene_query_support: bool#
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
SimulationContextclass when running the simulation with the GUI enabled. This is to allow certain GUI features to work properly.
- use_fabric: bool#
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
Truewhen 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
False.When using GPU simulation, it is required to enable Fabric to visualize updates in the renderer. Transform updates are propagated to the renderer through Fabric. If Fabric is disabled with GPU simulation, the renderer will not be able to render any updates in the simulation, although simulation will still be running under the hood.
- physics_material: RigidBodyMaterialCfg#
Default physics material settings for rigid bodies. Default is RigidBodyMaterialCfg().
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.
- create_stage_in_memory: bool#
If stage is first created in memory. Default is False.
Creating the stage in memory can reduce start-up time.
- class isaaclab.sim.PhysxCfg[source]#
Bases:
objectConfiguration for PhysX solver-related 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 by setting the
devicetocpuinSimulationCfg. Unlike CPU PhysX, the GPU simulation feature is unable 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 thegpu_*parameters.Attributes:
The type of solver to use.Default is 1 (TGS).
Minimum number of solver position iterations (rigid bodies, cloth, particles etc.).
Maximum number of solver position iterations (rigid bodies, cloth, particles etc.).
Minimum number of solver velocity iterations (rigid bodies, cloth, particles etc.).
Maximum number of solver velocity iterations (rigid bodies, cloth, particles etc.).
Enable a second broad-phase pass that makes it possible to prevent objects from tunneling through each other.
Enable/disable additional stabilization pass in solver.
Enable/disable improved determinism at the expense of performance.
Relative velocity threshold for contacts to bounce (in m/s).
Threshold for contact point to experience friction force (in m).
Distance threshold for merging contacts into a single friction anchor point (in m).
Size of rigid contact stream buffer allocated in pinned host memory.
Size of the rigid contact patch stream buffer allocated in pinned host memory.
Capacity of found and lost buffers allocated in GPU global memory.
Capacity of found and lost buffers in aggregate system allocated in GPU global memory.
Capacity of total number of aggregate pairs allocated in GPU global memory.
Size of the collision stack buffer allocated in pinned host memory.
Initial capacity of the GPU and pinned host memory heaps.
Capacity of temp buffer allocated in pinned host memory.
Limitation for the partitions in the GPU dynamics pipeline.
Size of soft body contacts stream buffer allocated in pinned host memory.
Size of particle contacts stream buffer allocated in pinned host memory.
Changes the ordering inside the articulation solver.
- solver_type: Literal[0, 1]#
The type of solver to use.Default is 1 (TGS).
Available solvers:
0: PGS (Projective Gauss-Seidel)1: TGS (Temporal Gauss-Seidel)
- min_position_iteration_count: int#
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].
- max_position_iteration_count: int#
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].
- min_velocity_iteration_count: int#
Minimum number of solver velocity 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].
- max_velocity_iteration_count: int#
Maximum number of solver velocity 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].
- enable_ccd: bool#
Enable a second broad-phase pass that makes it possible to prevent objects from tunneling through each other. Default is False.
- enable_stabilization: bool#
Enable/disable additional stabilization pass in solver. Default is False.
Note
We recommend setting this flag to true only when the simulation step size is large (i.e., less than 30 Hz or more than 0.0333 seconds).
Warning
Enabling this flag may lead to incorrect contact forces report from the contact sensor.
- enable_enhanced_determinism: bool#
Enable/disable improved determinism at the expense of performance. Defaults to False.
For more information on PhysX determinism, please check here.
- bounce_threshold_velocity: float#
Relative velocity threshold for contacts to bounce (in m/s). Default is 0.5 m/s.
- friction_offset_threshold: float#
Threshold for contact point to experience friction force (in m). Default is 0.04 m.
- friction_correlation_distance: float#
Distance threshold for merging contacts into a single friction anchor point (in m). Default is 0.025 m.
- gpu_max_rigid_contact_count: int#
Size of rigid contact stream buffer allocated in pinned host memory. Default is 2 ** 23.
- gpu_max_rigid_patch_count: int#
Size of the rigid contact patch stream buffer allocated in pinned host memory. Default is 5 * 2 ** 15.
- gpu_found_lost_pairs_capacity: int#
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#
Capacity of found and lost buffers in aggregate system allocated in GPU global memory. Default is 2 ** 25.
This is used for the found/lost pair reports in AABB manager.
- gpu_total_aggregate_pairs_capacity: int#
Capacity of total number of aggregate pairs allocated in GPU global memory. Default is 2 ** 21.
- gpu_collision_stack_size: int#
Size of the collision stack buffer allocated in pinned host memory. Default is 2 ** 26.
- gpu_heap_capacity: int#
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#
Capacity of temp buffer allocated in pinned host memory. Default is 2 ** 24.
- gpu_max_num_partitions: int#
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#
Size of soft body contacts stream buffer allocated in pinned host memory. Default is 2 ** 20.
- gpu_max_particle_contacts: int#
Size of particle contacts stream buffer allocated in pinned host memory. Default is 2 ** 20.
- solve_articulation_contact_last: bool#
Changes the ordering inside the articulation solver. Default is False.
PhysX employs a strict ordering for handling constraints in an articulation. The outcome of each constraint resolution modifies the joint and associated link speeds. However, the default ordering may not be ideal for gripping scenarios because the solver favours the constraint types that are resolved last. This is particularly true of stiff constraint systems that are hard to resolve without resorting to vanishingly small simulation timesteps.
With dynamic contact resolution being such an important part of gripping, it may make more sense to solve dynamic contact towards the end of the solver rather than at the beginning. This parameter modifies the default ordering to enable this change.
For more information, please check here.
New in version v2.3: This parameter is only available with Isaac Sim 5.1.
- class isaaclab.sim.RenderCfg[source]#
Bases:
objectConfiguration for Omniverse RTX Renderer.
These parameters are used to configure the Omniverse RTX Renderer.
The defaults for IsaacLab are set in the experience files:
apps/isaaclab.python.rendering.kit: Setting used when running the simulation with the GUI enabled.apps/isaaclab.python.headless.rendering.kit: Setting used when running the simulation in headless mode.
Setting any value here will override the defaults of the experience files.
For more information, see the Omniverse RTX Renderer documentation.
Attributes:
Enables translucency for specular transmissive surfaces such as glass at the cost of some performance.
Enables reflections at the cost of some performance.
Enables Diffused Global Illumination at the cost of some performance.
Selects the anti-aliasing mode to use.
"Enables the use of DLSS-G.
Enables the use of a DL denoiser.
For DLSS anti-aliasing, selects the performance/quality tradeoff mode.
Enable direct light contributions from lights.
Defines the Direct Lighting samples per pixel.
Enables shadows at the cost of performance.
Enables ambient occlusion at the cost of some performance.
Selects how to sample the Dome Light.
A general dictionary for users to supply all carb rendering settings with native names.
The rendering mode.
- enable_translucency: bool | None#
Enables translucency for specular transmissive surfaces such as glass at the cost of some performance. Default is False.
This is set by the variable:
/rtx/translucency/enabled.
- enable_reflections: bool | None#
Enables reflections at the cost of some performance. Default is False.
This is set by the variable:
/rtx/reflections/enabled.
- enable_global_illumination: bool | None#
Enables Diffused Global Illumination at the cost of some performance. Default is False.
This is set by the variable:
/rtx/indirectDiffuse/enabled.
- antialiasing_mode: Literal['Off', 'FXAA', 'DLSS', 'TAA', 'DLAA'] | None#
Selects the anti-aliasing mode to use. Defaults to DLSS.
DLSS: Boosts performance by using AI to output higher resolution frames from a lower resolution input. DLSS samples multiple lower resolution images and uses motion data and feedback from prior frames to reconstruct native quality images.
DLAA: Provides higher image quality with an AI-based anti-aliasing technique. DLAA uses the same Super Resolution technology developed for DLSS, reconstructing a native resolution image to maximize image quality.
This is set by the variable:
/rtx/post/dlss/execMode.
- enable_dlssg: bool | None#
“Enables the use of DLSS-G. Default is False.
DLSS Frame Generation boosts performance by using AI to generate more frames. DLSS analyzes sequential frames and motion data to create additional high quality frames.
Note
This feature requires an Ada Lovelace architecture GPU. Enabling this feature also enables additional thread-related activities, which can hurt performance.
This is set by the variable:
/rtx-transient/dlssg/enabled.
- enable_dl_denoiser: bool | None#
Enables the use of a DL denoiser.
The DL denoiser can help improve the quality of renders, but comes at a cost of performance.
This is set by the variable:
/rtx-transient/dldenoiser/enabled.
- dlss_mode: Literal[0, 1, 2, 3] | None#
For DLSS anti-aliasing, selects the performance/quality tradeoff mode. Default is 0.
Valid values are:
0 (Performance)
1 (Balanced)
2 (Quality)
3 (Auto)
This is set by the variable:
/rtx/post/dlss/execMode.
- enable_direct_lighting: bool | None#
Enable direct light contributions from lights. Default is False.
This is set by the variable:
/rtx/directLighting/enabled.
- samples_per_pixel: int | None#
Defines the Direct Lighting samples per pixel. Default is 1.
A higher value increases the direct lighting quality at the cost of performance.
This is set by the variable:
/rtx/directLighting/sampledLighting/samplesPerPixel.
- enable_shadows: bool | None#
Enables shadows at the cost of performance. Defaults to True.
When disabled, lights will not cast shadows.
This is set by the variable:
/rtx/shadows/enabled.
- enable_ambient_occlusion: bool | None#
Enables ambient occlusion at the cost of some performance. Default is False.
This is set by the variable:
/rtx/ambientOcclusion/enabled.
- dome_light_upper_lower_strategy: Literal[0, 3, 4] | None#
Selects how to sample the Dome Light. Default is 0. For more information, refer to the documentation.
Valid values are:
0: Image-Based Lighting (IBL) - Most accurate even for high-frequency Dome Light textures. Can introduce sampling artifacts in real-time mode.
3: Limited Image-Based Lighting - Only sampled for reflection and refraction. Fastest, but least accurate. Good for cases where the Dome Light contributes less than other light sources.
4: Approximated Image-Based Lighting - Fast and artifacts-free sampling in real-time mode but only works well with a low-frequency texture (e.g., a sky with no sun disc where the sun is instead a separate Distant Light). Requires enabling Direct Lighting denoiser.
This is set by the variable:
/rtx/domeLight/upperLowerStrategy.
- carb_settings: dict[str, Any] | None#
A general dictionary for users to supply all carb rendering settings with native names.
The keys of the dictionary can be formatted like a carb setting, .kit file setting, or python variable. For instance, a key value pair can be
/rtx/translucency/enabled: False(carb),rtx.translucency.enabled: False(.kit), orrtx_translucency_enabled: False(python).
Simulation Context Builder#
- simulation_context.build_simulation_context(gravity_enabled: bool = True, device: str = 'cuda:0', dt: float = 0.01, sim_cfg: SimulationCfg | None = None, add_ground_plane: bool = False, add_lighting: bool = False, auto_add_lighting: bool = False) Iterator[SimulationContext]#
Context manager to build a simulation context with the provided settings.
This function facilitates the creation of a simulation context and provides flexibility in configuring various aspects of the simulation, such as time step, gravity, device, and scene elements like ground plane and lighting.
If
sim_cfgis None, then an instance ofSimulationCfgis created with default settings, with parameters overwritten based on arguments to the function.An example usage of the context manager function:
with build_simulation_context() as sim: # Design the scene # Play the simulation sim.reset() while sim.is_playing(): sim.step()
- Parameters:
create_new_stage – Whether to create a new stage. Defaults to True.
gravity_enabled – Whether to enable gravity in the simulation. Defaults to True.
device – Device to run the simulation on. Defaults to “cuda:0”.
dt – Time step for the simulation: Defaults to 0.01.
sim_cfg –
isaaclab.sim.SimulationCfgto use for the simulation. Defaults to None.add_ground_plane – Whether to add a ground plane to the simulation. Defaults to False.
add_lighting – Whether to add a dome light to the simulation. Defaults to False.
auto_add_lighting – Whether to automatically add a dome light to the simulation if the simulation has a GUI. Defaults to False. This is useful for debugging tests in the GUI.
- Yields:
The simulation context to use for the simulation.