Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 1 addition & 1 deletion source/extensions/omni.isaac.lab/config/extension.toml
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
[package]

# Note: Semantic Versioning is used: https://semver.org/
version = "0.17.13"
version = "0.18.0"

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

0.18.0 (2024-06-13)
~~~~~~~~~~~~~~~~~~~~

Fixed
^^^^^

* Fixed the rendering logic to render at the specified interval. Earlier, the substep parameter had no effect and rendering
would happen once every env.step() when active.

Changed
^^^^^^^

* Renamed :attr:`omni.isaac.lab.sim.SimulationCfg.substeps` to :attr:`omni.isaac.lab.sim.SimulationCfg.render_interval`.
The render logic is now integrated in the decimation loop of the environment.


0.17.13 (2024-06-13)
~~~~~~~~~~~~~~~~~~~~

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

import carb
import omni.isaac.core.utils.torch as torch_utils
import omni.kit.app
from omni.isaac.version import get_version
Expand Down Expand Up @@ -91,11 +92,19 @@ def __init__(self, cfg: DirectRLEnvCfg, render_mode: str | None = None, **kwargs
print("[INFO]: Base environment:")
print(f"\tEnvironment device : {self.device}")
print(f"\tPhysics step-size : {self.physics_dt}")
print(f"\tRendering step-size : {self.physics_dt * self.cfg.sim.substeps}")
print(f"\tRendering step-size : {self.physics_dt * self.cfg.sim.render_interval}")
print(f"\tEnvironment step-size : {self.step_dt}")
print(f"\tPhysics GPU pipeline : {self.cfg.sim.use_gpu_pipeline}")
print(f"\tPhysics GPU simulation: {self.cfg.sim.physx.use_gpu}")

if self.cfg.sim.render_interval < self.cfg.decimation:
msg = (
f"The render interval ({self.cfg.sim.render_interval}) is smaller than the decimation "
f"({self.cfg.decimation}). Multiple multiple render calls will happen for each environment step."
"If this is not intended, set the render interval to be equal to the decimation."
)
carb.log_warn(msg)

# generate scene
with Timer("[INFO]: Time taken for scene creation"):
self.scene = InteractiveScene(self.cfg.scene)
Expand Down Expand Up @@ -146,6 +155,8 @@ def __init__(self, cfg: DirectRLEnvCfg, render_mode: str | None = None, **kwargs
self.extras = {}

# initialize data and constants
# -- counter for simulation steps
self._sim_step_counter = 0
# -- counter for curriculum
self.common_step_counter = 0
# -- init buffers
Expand Down Expand Up @@ -270,17 +281,18 @@ def step(self, action: torch.Tensor) -> VecEnvStepReturn:
self._pre_physics_step(action)
# perform physics stepping
for _ in range(self.cfg.decimation):
self._sim_step_counter += 1
# set actions into buffers
self._apply_action()
# set actions into simulator
self.scene.write_data_to_sim()
render = self._sim_step_counter % self.cfg.sim.render_interval == 0 and (
self.sim.has_gui() or self.sim.has_rtx_sensors()
)
# simulate
self.sim.step(render=False)
self.sim.step(render=render)
# update buffers at sim dt
self.scene.update(dt=self.physics_dt)
# perform rendering if gui is enabled
if self.sim.has_gui() or self.sim.has_rtx_sensors():
self.sim.render()

# post-step:
# -- update env counters (used for curriculum generation)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -87,11 +87,22 @@ def __init__(self, cfg: ManagerBasedEnvCfg):
print("[INFO]: Base environment:")
print(f"\tEnvironment device : {self.device}")
print(f"\tPhysics step-size : {self.physics_dt}")
print(f"\tRendering step-size : {self.physics_dt * self.cfg.sim.substeps}")
print(f"\tRendering step-size : {self.physics_dt * self.cfg.sim.render_interval}")
print(f"\tEnvironment step-size : {self.step_dt}")
print(f"\tPhysics GPU pipeline : {self.cfg.sim.use_gpu_pipeline}")
print(f"\tPhysics GPU simulation: {self.cfg.sim.physx.use_gpu}")

if self.cfg.sim.render_interval < self.cfg.decimation:
msg = (
f"The render interval ({self.cfg.sim.render_interval}) is smaller than the decimation "
f"({self.cfg.decimation}). Multiple multiple render calls will happen for each environment step. "
"If this is not intended, set the render interval to be equal to the decimation."
)
carb.log_warn(msg)

# counter for simulation steps
self._sim_step_counter = 0

# generate scene
with Timer("[INFO]: Time taken for scene creation"):
self.scene = InteractiveScene(self.cfg.scene)
Expand Down Expand Up @@ -253,17 +264,18 @@ def step(self, action: torch.Tensor) -> tuple[VecEnvObs, dict]:
self.action_manager.process_action(action)
# perform physics stepping
for _ in range(self.cfg.decimation):
self._sim_step_counter += 1
# set actions into buffers
self.action_manager.apply_action()
# set actions into simulator
self.scene.write_data_to_sim()
render = self._sim_step_counter % self.cfg.sim.render_interval == 0 and (
self.sim.has_gui() or self.sim.has_rtx_sensors()
)
# simulate
self.sim.step(render=False)
self.sim.step(render=render)
# update buffers at sim dt
self.scene.update(dt=self.physics_dt)
# perform rendering if gui is enabled
if self.sim.has_gui() or self.sim.has_rtx_sensors():
self.sim.render()

# post-step: step interval event
if "interval" in self.event_manager.available_modes:
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -154,17 +154,18 @@ def step(self, action: torch.Tensor) -> VecEnvStepReturn:
self.action_manager.process_action(action)
# perform physics stepping
for _ in range(self.cfg.decimation):
self._sim_step_counter += 1
# set actions into buffers
self.action_manager.apply_action()
# set actions into simulator
self.scene.write_data_to_sim()
render = self._sim_step_counter % self.cfg.sim.render_interval == 0 and (
self.sim.has_gui() or self.sim.has_rtx_sensors()
)
# simulate
self.sim.step(render=False)
self.sim.step(render=render)
# update buffers at sim dt
self.scene.update(dt=self.physics_dt)
# perform rendering if gui is enabled
if self.sim.has_gui() or self.sim.has_rtx_sensors():
self.sim.render()

# post-step:
# -- update env counters (used for curriculum generation)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -168,7 +168,7 @@ class SimulationCfg:
dt: float = 1.0 / 60.0
"""The physics simulation time-step (in seconds). Default is 0.0167 seconds."""

substeps: int = 1
render_interval: 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)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -214,7 +214,7 @@ def __init__(self, cfg: SimulationCfg | None = None):
super().__init__(
stage_units_in_meters=1.0,
physics_dt=self.cfg.dt,
rendering_dt=self.cfg.dt * self.cfg.substeps,
rendering_dt=self.cfg.dt * self.cfg.render_interval,
backend="torch",
sim_params=sim_params,
physics_prim_path=self.cfg.physics_prim_path,
Expand Down Expand Up @@ -384,14 +384,14 @@ def reset(self, soft: bool = False):
self.render()

def step(self, render: bool = True):
"""Steps the physics simulation with the pre-defined time-step.
"""Steps the simulation.

.. note::
This function blocks if the timeline is paused. It only returns when the timeline is playing.

Args:
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.
If set to False, the scene is not rendered and only the physics simulation is stepped.
"""
# check if the simulation timeline is paused. in that case keep stepping until it is playing
if not self.is_playing():
Expand Down Expand Up @@ -467,6 +467,11 @@ async def reset_async(self, soft: bool = False):

def _init_stage(self, *args, **kwargs) -> Usd.Stage:
_ = super()._init_stage(*args, **kwargs)
# a stage update here is needed for the case when physics_dt != rendering_dt, otherwise the app crashes
# when in headless mode
self.set_setting("/app/player/playSimulations", False)
self._app.update()
self.set_setting("/app/player/playSimulations", True)
# set additional physx parameters and bind material
self._set_additional_physx_params()
# load flatcache/fabric interface
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -144,7 +144,7 @@ def main():
"""Main function."""

# Initialize the simulation context
sim = sim_utils.SimulationContext(sim_utils.SimulationCfg(dt=0.01, substeps=1))
sim = sim_utils.SimulationContext(sim_utils.SimulationCfg(dt=0.01))
# Set main camera
sim.set_camera_view(eye=[2.5, 2.5, 2.5], target=[0.0, 0.0, 0.0])
# design scene
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -128,7 +128,7 @@ def main():
"""Main function."""

# Initialize the simulation context
sim_cfg = sim_utils.SimulationCfg(dt=0.005, substeps=1)
sim_cfg = sim_utils.SimulationCfg(dt=0.005)
sim = sim_utils.SimulationContext(sim_cfg)
# Set main camera
sim.set_camera_view(eye=[3.5, 3.5, 3.5], target=[0.0, 0.0, 0.0])
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -9,10 +9,8 @@

from omni.isaac.lab.app import AppLauncher, run_tests

HEADLESS = True

# launch omniverse app
app_launcher = AppLauncher(headless=HEADLESS)
app_launcher = AppLauncher(headless=True)
simulation_app = app_launcher.app

"""Rest everything follows."""
Expand Down Expand Up @@ -467,7 +465,7 @@ def _perform_sim_step(self) -> None:
# write data to simulation
self.scene.write_data_to_sim()
# simulate
self.sim.step(render=not HEADLESS)
self.sim.step(render=False)
# update buffers at sim dt
self.scene.update(dt=self.sim_dt)

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -52,15 +52,15 @@ def test_singleton(self):

def test_initialization(self):
"""Test the simulation config."""
cfg = SimulationCfg(physics_prim_path="/Physics/PhysX", substeps=5, gravity=(0.0, -0.5, -0.5))
cfg = SimulationCfg(physics_prim_path="/Physics/PhysX", render_interval=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)
self.assertEqual(sim.get_rendering_dt(), cfg.dt * cfg.render_interval)
self.assertFalse(sim.has_rtx_sensors())
# check valid paths
self.assertTrue(prim_utils.is_prim_path_valid("/Physics/PhysX"))
Expand Down
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
[package]

# Note: Semantic Versioning is used: https://semver.org/
version = "0.7.6"
version = "0.7.7"

# Description
title = "Isaac Lab Environments"
Expand Down
9 changes: 9 additions & 0 deletions source/extensions/omni.isaac.lab_tasks/docs/CHANGELOG.rst
Original file line number Diff line number Diff line change
@@ -1,6 +1,15 @@
Changelog
---------

0.7.7 (2024-06-14)
~~~~~~~~~~~~~~~~~~

Changed
^^^^^^^

* Updated the tasks to use the renamed attribute :attr:`omni.isaac.lab.sim.SimulationCfg.render_interval`.


0.7.6 (2024-06-13)
~~~~~~~~~~~~~~~~~~

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -20,8 +20,16 @@

@configclass
class AntEnvCfg(DirectRLEnvCfg):
# env
episode_length_s = 15.0
decimation = 2
action_scale = 0.5
num_actions = 8
num_observations = 36
num_states = 0

# simulation
sim: SimulationCfg = SimulationCfg(dt=1 / 120)
sim: SimulationCfg = SimulationCfg(dt=1 / 120, render_interval=decimation)
terrain = TerrainImporterCfg(
prim_path="/World/ground",
terrain_type="plane",
Expand All @@ -43,14 +51,6 @@ class AntEnvCfg(DirectRLEnvCfg):
robot: ArticulationCfg = ANT_CFG.replace(prim_path="/World/envs/env_.*/Robot")
joint_gears: list = [15, 15, 15, 15, 15, 15, 15, 15]

# env
episode_length_s = 15.0
decimation = 2
action_scale = 0.5
num_actions = 8
num_observations = 36
num_states = 0

heading_weight: float = 0.5
up_weight: float = 0.1

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -25,9 +25,18 @@

@configclass
class AnymalCFlatEnvCfg(DirectRLEnvCfg):
# env
episode_length_s = 20.0
decimation = 4
action_scale = 0.5
num_actions = 12
num_observations = 48
num_states = 0

# simulation
sim: SimulationCfg = SimulationCfg(
dt=1 / 200,
render_interval=decimation,
disable_contact_processing=True,
physics_material=sim_utils.RigidBodyMaterialCfg(
friction_combine_mode="multiply",
Expand Down Expand Up @@ -60,14 +69,6 @@ class AnymalCFlatEnvCfg(DirectRLEnvCfg):
prim_path="/World/envs/env_.*/Robot/.*", history_length=3, update_period=0.005, track_air_time=True
)

# env
episode_length_s = 20.0
decimation = 4
action_scale = 0.5
num_actions = 12
num_observations = 48
num_states = 0

# reward scales
lin_vel_reward_scale = 1.0
yaw_rate_reward_scale = 0.5
Expand Down
Loading