Commit c48b2050 authored by oahmednv's avatar oahmednv Committed by Kelly Guo

Allows physics reset during simulation (#259)

- Allows users to exit on 1 Ctrl+C instead of consecutive 2 key strokes.
- Allows physics reset during simulation.

Example:

**env.sim.reset() # resets physics simulation
env.seed(seed) # ensures running with the same seed
env.reset()**

<!-- As a practice, it is recommended to open an issue to have
discussions on the proposed pull request.
This makes it easier for the community to keep track of what is being
developed or added, and if a given feature
is demanded by more than one party. -->

- New feature (non-breaking change which adds functionality)

- [x] I have run the [`pre-commit` checks](https://pre-commit.com/) with
`./isaaclab.sh --format`
- [x] I have made corresponding changes to the documentation
- [x] 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
- [x] I have added my name to the `CONTRIBUTORS.md` or my name already
exists there
parent 7e352eb7
...@@ -44,14 +44,11 @@ Fixed ...@@ -44,14 +44,11 @@ Fixed
0.36.2 (2025-03-12) 0.36.2 (2025-03-12)
~~~~~~~~~~~~~~~~~~~ ~~~~~~~~~~~~~~~~~~~
Added Changed
^^^^^ ^^^^^^^
* Added a new event mode called "prestartup", which gets called right after the scene design is complete * Allowed users to exit on 1 Ctrl+C instead of consecutive 2 key strokes.
and before the simulation is played. * Allowed physics reset during simulation through :meth:`reset` in :class:`~isaaclab.sim.SimulationContext`.
* Added a callback to resolve the scene entity configurations separately once the simulation plays,
since the scene entities cannot be resolved before the simulation starts playing
(as we currently rely on PhysX to provide us with the joint/body ordering)
0.36.1 (2025-03-10) 0.36.1 (2025-03-10)
...@@ -118,6 +115,19 @@ Changed ...@@ -118,6 +115,19 @@ Changed
* ``set_fixed_tendon_limit`` → ``set_fixed_tendon_position_limit`` * ``set_fixed_tendon_limit`` → ``set_fixed_tendon_position_limit``
0.34.13 (2025-03-06)
~~~~~~~~~~~~~~~~~~~~
Added
^^^^^
* Added a new event mode called "prestartup", which gets called right after the scene design is complete
and before the simulation is played.
* Added a callback to resolve the scene entity configurations separately once the simulation plays,
since the scene entities cannot be resolved before the simulation starts playing
(as we currently rely on PhysX to provide us with the joint/body ordering)
0.34.12 (2025-03-06) 0.34.12 (2025-03-06)
~~~~~~~~~~~~~~~~~~~~ ~~~~~~~~~~~~~~~~~~~~
......
...@@ -117,9 +117,24 @@ class AppLauncher: ...@@ -117,9 +117,24 @@ class AppLauncher:
# Hide the stop button in the toolbar # Hide the stop button in the toolbar
self._hide_stop_button() self._hide_stop_button()
# Hide play button callback if the timeline is stopped
import omni.timeline
self._hide_play_button_callback = (
omni.timeline.get_timeline_interface()
.get_timeline_event_stream()
.create_subscription_to_pop_by_type(
int(omni.timeline.TimelineEventType.STOP), lambda e: self._hide_play_button(True)
)
)
self._unhide_play_button_callback = (
omni.timeline.get_timeline_interface()
.get_timeline_event_stream()
.create_subscription_to_pop_by_type(
int(omni.timeline.TimelineEventType.PLAY), lambda e: self._hide_play_button(False)
)
)
# Set up signal handlers for graceful shutdown # Set up signal handlers for graceful shutdown
# -- during interrupts
signal.signal(signal.SIGINT, self._interrupt_signal_handle_callback)
# -- during explicit `kill` commands # -- during explicit `kill` commands
signal.signal(signal.SIGTERM, self._abort_signal_handle_callback) signal.signal(signal.SIGTERM, self._abort_signal_handle_callback)
# -- during segfaults # -- during segfaults
...@@ -796,12 +811,22 @@ class AppLauncher: ...@@ -796,12 +811,22 @@ class AppLauncher:
play_button_group._stop_button.enabled = False # type: ignore play_button_group._stop_button.enabled = False # type: ignore
play_button_group._stop_button = None # type: ignore play_button_group._stop_button = None # type: ignore
def _interrupt_signal_handle_callback(self, signal, frame): def _hide_play_button(self, flag):
"""Handle the interrupt signal from the keyboard.""" """Hide/Unhide the play button in the toolbar.
# close the app
self._app.close() This is used if the timeline is stopped by a GUI action like "save as" to not allow the user to
# raise the error for keyboard interrupt resume the timeline afterwards.
raise KeyboardInterrupt """
# when we are truly headless, then we can't import the widget toolbar
# thus, we only hide the play button when we are not headless (i.e. GUI is enabled)
if self._livestream >= 1 or not self._headless:
import omni.kit.widget.toolbar
toolbar = omni.kit.widget.toolbar.get_instance()
play_button_group = toolbar._builtin_tools._play_button_group # type: ignore
if play_button_group is not None:
play_button_group._play_button.visible = not flag # type: ignore
play_button_group._play_button.enabled = not flag # type: ignore
def _abort_signal_handle_callback(self, signal, frame): def _abort_signal_handle_callback(self, signal, frame):
"""Handle the abort/segmentation/kill signals.""" """Handle the abort/segmentation/kill signals."""
......
...@@ -16,6 +16,7 @@ from typing import TYPE_CHECKING ...@@ -16,6 +16,7 @@ from typing import TYPE_CHECKING
import isaacsim.core.utils.stage as stage_utils import isaacsim.core.utils.stage as stage_utils
import omni.log import omni.log
import omni.physics.tensors.impl.api as physx import omni.physics.tensors.impl.api as physx
from isaacsim.core.simulation_manager import SimulationManager
from pxr import PhysxSchema, UsdPhysics from pxr import PhysxSchema, UsdPhysics
import isaaclab.sim as sim_utils import isaaclab.sim as sim_utils
...@@ -1144,9 +1145,8 @@ class Articulation(AssetBase): ...@@ -1144,9 +1145,8 @@ class Articulation(AssetBase):
""" """
def _initialize_impl(self): def _initialize_impl(self):
# create simulation view # obtain global simulation view
self._physics_sim_view = physx.create_simulation_view(self._backend) self._physics_sim_view = SimulationManager.get_physics_sim_view()
self._physics_sim_view.set_subspace_roots("/")
# obtain the first prim in the regex expression (all others are assumed to be a copy of this) # obtain the first prim in the regex expression (all others are assumed to be a copy of this)
template_prim = sim_utils.find_first_matching_prim(self.cfg.prim_path) template_prim = sim_utils.find_first_matching_prim(self.cfg.prim_path)
if template_prim is None: if template_prim is None:
...@@ -1301,8 +1301,6 @@ class Articulation(AssetBase): ...@@ -1301,8 +1301,6 @@ class Articulation(AssetBase):
"""Invalidates the scene elements.""" """Invalidates the scene elements."""
# call parent # call parent
super()._invalidate_initialize_callback(event) super()._invalidate_initialize_callback(event)
# set all existing views to None to invalidate them
self._physics_sim_view = None
self._root_physx_view = None self._root_physx_view = None
""" """
......
...@@ -8,6 +8,7 @@ import weakref ...@@ -8,6 +8,7 @@ import weakref
import omni.log import omni.log
import omni.physics.tensors.impl.api as physx import omni.physics.tensors.impl.api as physx
from isaacsim.core.simulation_manager import SimulationManager
import isaaclab.utils.math as math_utils import isaaclab.utils.math as math_utils
from isaaclab.utils.buffers import TimestampedBuffer from isaaclab.utils.buffers import TimestampedBuffer
...@@ -48,9 +49,8 @@ class ArticulationData: ...@@ -48,9 +49,8 @@ class ArticulationData:
# Set initial time stamp # Set initial time stamp
self._sim_timestamp = 0.0 self._sim_timestamp = 0.0
# Obtain global physics sim view # obtain global simulation view
self._physics_sim_view = physx.create_simulation_view("torch") self._physics_sim_view = SimulationManager.get_physics_sim_view()
self._physics_sim_view.set_subspace_roots("/")
gravity = self._physics_sim_view.get_gravity() gravity = self._physics_sim_view.get_gravity()
# Convert to direction vector # Convert to direction vector
gravity_dir = torch.tensor((gravity[0], gravity[1], gravity[2]), device=self.device) gravity_dir = torch.tensor((gravity[0], gravity[1], gravity[2]), device=self.device)
......
...@@ -14,6 +14,7 @@ from typing import TYPE_CHECKING, Any ...@@ -14,6 +14,7 @@ from typing import TYPE_CHECKING, Any
import omni.kit.app import omni.kit.app
import omni.timeline import omni.timeline
from isaacsim.core.simulation_manager import SimulationManager
import isaaclab.sim as sim_utils import isaaclab.sim as sim_utils
...@@ -255,12 +256,8 @@ class AssetBase(ABC): ...@@ -255,12 +256,8 @@ class AssetBase(ABC):
called whenever the simulator "plays" from a "stop" state. called whenever the simulator "plays" from a "stop" state.
""" """
if not self._is_initialized: if not self._is_initialized:
# obtain simulation related information self._backend = SimulationManager.get_backend()
sim = sim_utils.SimulationContext.instance() self._device = SimulationManager.get_physics_sim_device()
if sim is None:
raise RuntimeError("SimulationContext is not initialized! Please initialize SimulationContext first.")
self._backend = sim.backend
self._device = sim.device
# initialize the asset # initialize the asset
self._initialize_impl() self._initialize_impl()
# set flag # set flag
......
...@@ -11,6 +11,7 @@ from typing import TYPE_CHECKING ...@@ -11,6 +11,7 @@ from typing import TYPE_CHECKING
import omni.log import omni.log
import omni.physics.tensors.impl.api as physx import omni.physics.tensors.impl.api as physx
from isaacsim.core.simulation_manager import SimulationManager
from pxr import PhysxSchema, UsdShade from pxr import PhysxSchema, UsdShade
import isaaclab.sim as sim_utils import isaaclab.sim as sim_utils
...@@ -261,9 +262,8 @@ class DeformableObject(AssetBase): ...@@ -261,9 +262,8 @@ class DeformableObject(AssetBase):
""" """
def _initialize_impl(self): def _initialize_impl(self):
# create simulation view # obtain global simulation view
self._physics_sim_view = physx.create_simulation_view(self._backend) self._physics_sim_view = SimulationManager.get_physics_sim_view()
self._physics_sim_view.set_subspace_roots("/")
# obtain the first prim in the regex expression (all others are assumed to be a copy of this) # obtain the first prim in the regex expression (all others are assumed to be a copy of this)
template_prim = sim_utils.find_first_matching_prim(self.cfg.prim_path) template_prim = sim_utils.find_first_matching_prim(self.cfg.prim_path)
if template_prim is None: if template_prim is None:
...@@ -408,6 +408,4 @@ class DeformableObject(AssetBase): ...@@ -408,6 +408,4 @@ class DeformableObject(AssetBase):
"""Invalidates the scene elements.""" """Invalidates the scene elements."""
# call parent # call parent
super()._invalidate_initialize_callback(event) super()._invalidate_initialize_callback(event)
# set all existing views to None to invalidate them
self._physics_sim_view = None
self._root_physx_view = None self._root_physx_view = None
...@@ -11,6 +11,7 @@ from typing import TYPE_CHECKING ...@@ -11,6 +11,7 @@ from typing import TYPE_CHECKING
import omni.log import omni.log
import omni.physics.tensors.impl.api as physx import omni.physics.tensors.impl.api as physx
from isaacsim.core.simulation_manager import SimulationManager
from pxr import UsdPhysics from pxr import UsdPhysics
import isaaclab.sim as sim_utils import isaaclab.sim as sim_utils
...@@ -400,9 +401,8 @@ class RigidObject(AssetBase): ...@@ -400,9 +401,8 @@ class RigidObject(AssetBase):
""" """
def _initialize_impl(self): def _initialize_impl(self):
# create simulation view # obtain global simulation view
self._physics_sim_view = physx.create_simulation_view(self._backend) self._physics_sim_view = SimulationManager.get_physics_sim_view()
self._physics_sim_view.set_subspace_roots("/")
# obtain the first prim in the regex expression (all others are assumed to be a copy of this) # obtain the first prim in the regex expression (all others are assumed to be a copy of this)
template_prim = sim_utils.find_first_matching_prim(self.cfg.prim_path) template_prim = sim_utils.find_first_matching_prim(self.cfg.prim_path)
if template_prim is None: if template_prim is None:
...@@ -501,5 +501,4 @@ class RigidObject(AssetBase): ...@@ -501,5 +501,4 @@ class RigidObject(AssetBase):
# call parent # call parent
super()._invalidate_initialize_callback(event) super()._invalidate_initialize_callback(event)
# set all existing views to None to invalidate them # set all existing views to None to invalidate them
self._physics_sim_view = None
self._root_physx_view = None self._root_physx_view = None
...@@ -15,6 +15,7 @@ import omni.kit.app ...@@ -15,6 +15,7 @@ import omni.kit.app
import omni.log import omni.log
import omni.physics.tensors.impl.api as physx import omni.physics.tensors.impl.api as physx
import omni.timeline import omni.timeline
from isaacsim.core.simulation_manager import SimulationManager
from pxr import UsdPhysics from pxr import UsdPhysics
import isaaclab.sim as sim_utils import isaaclab.sim as sim_utils
...@@ -529,9 +530,8 @@ class RigidObjectCollection(AssetBase): ...@@ -529,9 +530,8 @@ class RigidObjectCollection(AssetBase):
""" """
def _initialize_impl(self): def _initialize_impl(self):
# create simulation view # obtain global simulation view
self._physics_sim_view = physx.create_simulation_view(self._backend) self._physics_sim_view = SimulationManager.get_physics_sim_view()
self._physics_sim_view.set_subspace_roots("/")
root_prim_path_exprs = [] root_prim_path_exprs = []
for name, rigid_object_cfg in self.cfg.rigid_objects.items(): for name, rigid_object_cfg in self.cfg.rigid_objects.items():
# obtain the first prim in the regex expression (all others are assumed to be a copy of this) # obtain the first prim in the regex expression (all others are assumed to be a copy of this)
...@@ -687,5 +687,4 @@ class RigidObjectCollection(AssetBase): ...@@ -687,5 +687,4 @@ class RigidObjectCollection(AssetBase):
# call parent # call parent
super()._invalidate_initialize_callback(event) super()._invalidate_initialize_callback(event)
# set all existing views to None to invalidate them # set all existing views to None to invalidate them
self._physics_sim_view = None
self._root_physx_view = None self._root_physx_view = None
...@@ -14,6 +14,7 @@ from typing import TYPE_CHECKING ...@@ -14,6 +14,7 @@ from typing import TYPE_CHECKING
import carb import carb
import omni.physics.tensors.impl.api as physx import omni.physics.tensors.impl.api as physx
from isaacsim.core.simulation_manager import SimulationManager
from pxr import PhysxSchema from pxr import PhysxSchema
import isaaclab.sim as sim_utils import isaaclab.sim as sim_utils
...@@ -249,9 +250,8 @@ class ContactSensor(SensorBase): ...@@ -249,9 +250,8 @@ class ContactSensor(SensorBase):
def _initialize_impl(self): def _initialize_impl(self):
super()._initialize_impl() super()._initialize_impl()
# create simulation view # obtain global simulation view
self._physics_sim_view = physx.create_simulation_view(self._backend) self._physics_sim_view = SimulationManager.get_physics_sim_view()
self._physics_sim_view.set_subspace_roots("/")
# check that only rigid bodies are selected # check that only rigid bodies are selected
leaf_pattern = self.cfg.prim_path.rsplit("/", 1)[-1] leaf_pattern = self.cfg.prim_path.rsplit("/", 1)[-1]
template_prim_path = self._parent_prims[0].GetPath().pathString template_prim_path = self._parent_prims[0].GetPath().pathString
...@@ -418,6 +418,5 @@ class ContactSensor(SensorBase): ...@@ -418,6 +418,5 @@ class ContactSensor(SensorBase):
# call parent # call parent
super()._invalidate_initialize_callback(event) super()._invalidate_initialize_callback(event)
# set all existing views to None to invalidate them # set all existing views to None to invalidate them
self._physics_sim_view = None
self._body_physx_view = None self._body_physx_view = None
self._contact_physx_view = None self._contact_physx_view = None
...@@ -11,7 +11,7 @@ from collections.abc import Sequence ...@@ -11,7 +11,7 @@ from collections.abc import Sequence
from typing import TYPE_CHECKING from typing import TYPE_CHECKING
import omni.log import omni.log
import omni.physics.tensors.impl.api as physx from isaacsim.core.simulation_manager import SimulationManager
from pxr import UsdPhysics from pxr import UsdPhysics
import isaaclab.sim as sim_utils import isaaclab.sim as sim_utils
...@@ -205,9 +205,8 @@ class FrameTransformer(SensorBase): ...@@ -205,9 +205,8 @@ class FrameTransformer(SensorBase):
body_names_regex = [tracked_prim_path.replace("env_0", "env_*") for tracked_prim_path in tracked_prim_paths] body_names_regex = [tracked_prim_path.replace("env_0", "env_*") for tracked_prim_path in tracked_prim_paths]
# Create simulation view # obtain global simulation view
self._physics_sim_view = physx.create_simulation_view(self._backend) self._physics_sim_view = SimulationManager.get_physics_sim_view()
self._physics_sim_view.set_subspace_roots("/")
# Create a prim view for all frames and initialize it # Create a prim view for all frames and initialize it
# order of transforms coming out of view will be source frame followed by target frame(s) # order of transforms coming out of view will be source frame followed by target frame(s)
self._frame_physx_view = self._physics_sim_view.create_rigid_body_view(body_names_regex) self._frame_physx_view = self._physics_sim_view.create_rigid_body_view(body_names_regex)
...@@ -410,5 +409,4 @@ class FrameTransformer(SensorBase): ...@@ -410,5 +409,4 @@ class FrameTransformer(SensorBase):
# call parent # call parent
super()._invalidate_initialize_callback(event) super()._invalidate_initialize_callback(event)
# set all existing views to None to invalidate them # set all existing views to None to invalidate them
self._physics_sim_view = None
self._frame_physx_view = None self._frame_physx_view = None
...@@ -10,7 +10,7 @@ from collections.abc import Sequence ...@@ -10,7 +10,7 @@ from collections.abc import Sequence
from typing import TYPE_CHECKING from typing import TYPE_CHECKING
import isaacsim.core.utils.stage as stage_utils import isaacsim.core.utils.stage as stage_utils
import omni.physics.tensors.impl.api as physx from isaacsim.core.simulation_manager import SimulationManager
from pxr import UsdPhysics from pxr import UsdPhysics
import isaaclab.sim as sim_utils import isaaclab.sim as sim_utils
...@@ -123,9 +123,8 @@ class Imu(SensorBase): ...@@ -123,9 +123,8 @@ class Imu(SensorBase):
""" """
# Initialize parent class # Initialize parent class
super()._initialize_impl() super()._initialize_impl()
# create simulation view # obtain global simulation view
self._physics_sim_view = physx.create_simulation_view(self._backend) self._physics_sim_view = SimulationManager.get_physics_sim_view()
self._physics_sim_view.set_subspace_roots("/")
# check if the prim at path is a rigid prim # check if the prim at path is a rigid prim
prim = sim_utils.find_first_matching_prim(self.cfg.prim_path) prim = sim_utils.find_first_matching_prim(self.cfg.prim_path)
if prim is None: if prim is None:
......
...@@ -15,6 +15,7 @@ import omni.log ...@@ -15,6 +15,7 @@ import omni.log
import omni.physics.tensors.impl.api as physx import omni.physics.tensors.impl.api as physx
import warp as wp import warp as wp
from isaacsim.core.prims import XFormPrim from isaacsim.core.prims import XFormPrim
from isaacsim.core.simulation_manager import SimulationManager
from pxr import UsdGeom, UsdPhysics from pxr import UsdGeom, UsdPhysics
import isaaclab.sim as sim_utils import isaaclab.sim as sim_utils
...@@ -118,9 +119,8 @@ class RayCaster(SensorBase): ...@@ -118,9 +119,8 @@ class RayCaster(SensorBase):
def _initialize_impl(self): def _initialize_impl(self):
super()._initialize_impl() super()._initialize_impl()
# create simulation view # obtain global simulation view
self._physics_sim_view = physx.create_simulation_view(self._backend) self._physics_sim_view = SimulationManager.get_physics_sim_view()
self._physics_sim_view.set_subspace_roots("/")
# check if the prim at path is an articulated or rigid prim # check if the prim at path is an articulated or rigid prim
# we do this since for physics-based view classes we can access their data directly # we do this since for physics-based view classes we can access their data directly
# otherwise we need to use the xform view class which is slower # otherwise we need to use the xform view class which is slower
...@@ -287,5 +287,4 @@ class RayCaster(SensorBase): ...@@ -287,5 +287,4 @@ class RayCaster(SensorBase):
# call parent # call parent
super()._invalidate_initialize_callback(event) super()._invalidate_initialize_callback(event)
# set all existing views to None to invalidate them # set all existing views to None to invalidate them
self._physics_sim_view = None
self._view = None self._view = None
...@@ -6,7 +6,6 @@ ...@@ -6,7 +6,6 @@
import builtins import builtins
import enum import enum
import numpy as np import numpy as np
import sys
import torch import torch
import traceback import traceback
import weakref import weakref
...@@ -261,17 +260,17 @@ class SimulationContext(_SimulationContext): ...@@ -261,17 +260,17 @@ class SimulationContext(_SimulationContext):
# you can reproduce the issue by commenting out this line and running the test `test_articulation.py`. # you can reproduce the issue by commenting out this line and running the test `test_articulation.py`.
self._gravity_tensor = torch.tensor(self.cfg.gravity, dtype=torch.float32, device=self.cfg.device) self._gravity_tensor = torch.tensor(self.cfg.gravity, dtype=torch.float32, device=self.cfg.device)
# add callback to deal the simulation app when simulation is stopped. # add a callback to keep rendering when a stop is triggered through different GUI commands like (save as)
# this is needed because physics views go invalid once we stop the simulation
if not builtins.ISAAC_LAUNCHED_FROM_TERMINAL: if not builtins.ISAAC_LAUNCHED_FROM_TERMINAL:
timeline_event_stream = omni.timeline.get_timeline_interface().get_timeline_event_stream() timeline_event_stream = omni.timeline.get_timeline_interface().get_timeline_event_stream()
self._app_control_on_stop_handle = timeline_event_stream.create_subscription_to_pop_by_type( self._app_control_on_stop_handle = timeline_event_stream.create_subscription_to_pop_by_type(
int(omni.timeline.TimelineEventType.STOP), int(omni.timeline.TimelineEventType.STOP),
lambda *args, obj=weakref.proxy(self): obj._app_control_on_stop_callback(*args), lambda *args, obj=weakref.proxy(self): obj._app_control_on_stop_handle_fn(*args),
order=15, order=15,
) )
else: else:
self._app_control_on_stop_handle = None self._app_control_on_stop_handle = None
self._disable_app_control_on_stop_handle = False
# flatten out the simulation dictionary # flatten out the simulation dictionary
sim_params = self.cfg.to_dict() sim_params = self.cfg.to_dict()
...@@ -455,6 +454,7 @@ class SimulationContext(_SimulationContext): ...@@ -455,6 +454,7 @@ class SimulationContext(_SimulationContext):
""" """
def reset(self, soft: bool = False): def reset(self, soft: bool = False):
self._disable_app_control_on_stop_handle = True
super().reset(soft=soft) super().reset(soft=soft)
# app.update() may be changing the cuda device in reset, so we force it back to our desired device here # app.update() may be changing the cuda device in reset, so we force it back to our desired device here
if "cuda" in self.device: if "cuda" in self.device:
...@@ -467,6 +467,7 @@ class SimulationContext(_SimulationContext): ...@@ -467,6 +467,7 @@ class SimulationContext(_SimulationContext):
if not soft: if not soft:
for _ in range(2): for _ in range(2):
self.render() self.render()
self._disable_app_control_on_stop_handle = False
def step(self, render: bool = True): def step(self, render: bool = True):
"""Steps the simulation. """Steps the simulation.
...@@ -662,7 +663,7 @@ class SimulationContext(_SimulationContext): ...@@ -662,7 +663,7 @@ class SimulationContext(_SimulationContext):
Callbacks. Callbacks.
""" """
def _app_control_on_stop_callback(self, event: carb.events.IEvent): def _app_control_on_stop_handle_fn(self, event: carb.events.IEvent):
"""Callback to deal with the app when the simulation is stopped. """Callback to deal with the app when the simulation is stopped.
Once the simulation is stopped, the physics handles go invalid. After that, it is not possible to Once the simulation is stopped, the physics handles go invalid. After that, it is not possible to
...@@ -679,67 +680,10 @@ class SimulationContext(_SimulationContext): ...@@ -679,67 +680,10 @@ class SimulationContext(_SimulationContext):
This callback is used only when running the simulation in a standalone python script. In an extension, This callback is used only when running the simulation in a standalone python script. In an extension,
it is expected that the user handles the extension shutdown. it is expected that the user handles the extension shutdown.
""" """
# check if the simulation is stopped if not self._disable_app_control_on_stop_handle:
if event.type == int(omni.timeline.TimelineEventType.STOP): while not omni.timeline.get_timeline_interface().is_playing():
# keep running the simulator when configured to not shutdown the app self.render()
if self._has_gui and sys.exc_info()[0] is None: return
omni.log.warn(
"Simulation is stopped. The app will keep running with physics disabled."
" Press Ctrl+C or close the window to exit the app."
)
while self.app.is_running():
self.render()
# Note: For the following code:
# The method is an exact copy of the implementation in the `isaacsim.simulation_app.SimulationApp` class.
# We need to remove this method once the SimulationApp class becomes a singleton.
# make sure that any replicator workflows finish rendering/writing
try:
import omni.replicator.core as rep
rep_status = rep.orchestrator.get_status()
if rep_status not in [rep.orchestrator.Status.STOPPED, rep.orchestrator.Status.STOPPING]:
rep.orchestrator.stop()
if rep_status != rep.orchestrator.Status.STOPPED:
rep.orchestrator.wait_until_complete()
# Disable capture on play to avoid replicator engaging on any new timeline events
rep.orchestrator.set_capture_on_play(False)
except Exception:
pass
# clear the instance and all callbacks
# note: clearing callbacks is important to prevent memory leaks
self.clear_all_callbacks()
# workaround for exit issues, clean the stage first:
if omni.usd.get_context().can_close_stage():
omni.usd.get_context().close_stage()
# print logging information
print("[INFO]: Simulation is stopped. Shutting down the app.")
# Cleanup any running tracy instances so data is not lost
try:
profiler_tracy = carb.profiler.acquire_profiler_interface(plugin_name="carb.profiler-tracy.plugin")
if profiler_tracy:
profiler_tracy.set_capture_mask(0)
profiler_tracy.end(0)
profiler_tracy.shutdown()
except RuntimeError:
# Tracy plugin was not loaded, so profiler never started - skip checks.
pass
# Disable logging before shutdown to keep the log clean
# Warnings at this point don't matter as the python process is about to be terminated
logging = carb.logging.acquire_logging()
logging.set_level_threshold(carb.logging.LEVEL_ERROR)
# App shutdown is disabled to prevent crashes on shutdown. Terminating carb is faster
self._app.shutdown()
self._framework.unload_all_plugins()
sys.exit(0)
@contextmanager @contextmanager
......
...@@ -613,7 +613,7 @@ class TestArticulation(unittest.TestCase): ...@@ -613,7 +613,7 @@ class TestArticulation(unittest.TestCase):
# Play sim # Play sim
sim.reset() sim.reset()
# Check if articulation is initialized # Check if articulation is initialized
self.assertFalse(articulation._is_initialized) self.assertFalse(articulation.is_initialized)
def test_out_of_range_default_joint_vel(self): def test_out_of_range_default_joint_vel(self):
"""Test that the default joint velocity from configuration is out of range.""" """Test that the default joint velocity from configuration is out of range."""
...@@ -633,7 +633,7 @@ class TestArticulation(unittest.TestCase): ...@@ -633,7 +633,7 @@ class TestArticulation(unittest.TestCase):
# Play sim # Play sim
sim.reset() sim.reset()
# Check if articulation is initialized # Check if articulation is initialized
self.assertFalse(articulation._is_initialized) self.assertFalse(articulation.is_initialized)
def test_joint_pos_limits(self): def test_joint_pos_limits(self):
"""Test write_joint_position_limit_to_sim API and when default position falls outside of the new limits.""" """Test write_joint_position_limit_to_sim API and when default position falls outside of the new limits."""
...@@ -649,7 +649,7 @@ class TestArticulation(unittest.TestCase): ...@@ -649,7 +649,7 @@ class TestArticulation(unittest.TestCase):
# Play sim # Play sim
sim.reset() sim.reset()
# Check if articulation is initialized # Check if articulation is initialized
self.assertTrue(articulation._is_initialized) self.assertTrue(articulation.is_initialized)
# Get current default joint pos # Get current default joint pos
default_joint_pos = articulation._data.default_joint_pos.clone() default_joint_pos = articulation._data.default_joint_pos.clone()
......
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