Unverified Commit 59493b89 authored by David Hoeller's avatar David Hoeller Committed by GitHub

Fixes the rendering logic inside the environment classes (#515)

Fixes #476

The parameter substeps in the Simulation config had no influence on the
rendering frequency.
Additionally, app.update was not properly called when initializing the
stage due to the render method overload. This led to problems when
modifying the render interval.

- Merged physics stepping and rendering inside the step method in the
simulation config.
- Renamed substeps to render_interval in the simulation config.
- Updated all the tasks

## Type of change

- Breaking change (fix or feature that would cause existing
functionality to not work as expected)

## Checklist

- [x] I have run the [`pre-commit` checks](https://pre-commit.com/) with
`./isaaclab.sh --format`
- [ ] 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 run all the tests with `./isaaclab.sh --test` and they pass
- [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 030d0bf5
[package] [package]
# Note: Semantic Versioning is used: https://semver.org/ # Note: Semantic Versioning is used: https://semver.org/
version = "0.17.13" version = "0.18.0"
# Description # Description
title = "Isaac Lab framework for Robot Learning" title = "Isaac Lab framework for Robot Learning"
......
Changelog 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) 0.17.13 (2024-06-13)
~~~~~~~~~~~~~~~~~~~~ ~~~~~~~~~~~~~~~~~~~~
......
...@@ -16,6 +16,7 @@ from abc import abstractmethod ...@@ -16,6 +16,7 @@ from abc import abstractmethod
from collections.abc import Sequence from collections.abc import Sequence
from typing import Any, ClassVar from typing import Any, ClassVar
import carb
import omni.isaac.core.utils.torch as torch_utils import omni.isaac.core.utils.torch as torch_utils
import omni.kit.app import omni.kit.app
from omni.isaac.version import get_version from omni.isaac.version import get_version
...@@ -91,11 +92,19 @@ class DirectRLEnv(gym.Env): ...@@ -91,11 +92,19 @@ class DirectRLEnv(gym.Env):
print("[INFO]: Base environment:") print("[INFO]: Base environment:")
print(f"\tEnvironment device : {self.device}") print(f"\tEnvironment device : {self.device}")
print(f"\tPhysics step-size : {self.physics_dt}") 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"\tEnvironment step-size : {self.step_dt}")
print(f"\tPhysics GPU pipeline : {self.cfg.sim.use_gpu_pipeline}") print(f"\tPhysics GPU pipeline : {self.cfg.sim.use_gpu_pipeline}")
print(f"\tPhysics GPU simulation: {self.cfg.sim.physx.use_gpu}") 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 # generate scene
with Timer("[INFO]: Time taken for scene creation"): with Timer("[INFO]: Time taken for scene creation"):
self.scene = InteractiveScene(self.cfg.scene) self.scene = InteractiveScene(self.cfg.scene)
...@@ -146,6 +155,8 @@ class DirectRLEnv(gym.Env): ...@@ -146,6 +155,8 @@ class DirectRLEnv(gym.Env):
self.extras = {} self.extras = {}
# initialize data and constants # initialize data and constants
# -- counter for simulation steps
self._sim_step_counter = 0
# -- counter for curriculum # -- counter for curriculum
self.common_step_counter = 0 self.common_step_counter = 0
# -- init buffers # -- init buffers
...@@ -270,17 +281,18 @@ class DirectRLEnv(gym.Env): ...@@ -270,17 +281,18 @@ class DirectRLEnv(gym.Env):
self._pre_physics_step(action) self._pre_physics_step(action)
# perform physics stepping # perform physics stepping
for _ in range(self.cfg.decimation): for _ in range(self.cfg.decimation):
self._sim_step_counter += 1
# set actions into buffers # set actions into buffers
self._apply_action() self._apply_action()
# set actions into simulator # set actions into simulator
self.scene.write_data_to_sim() 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 # simulate
self.sim.step(render=False) self.sim.step(render=render)
# update buffers at sim dt # update buffers at sim dt
self.scene.update(dt=self.physics_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: # post-step:
# -- update env counters (used for curriculum generation) # -- update env counters (used for curriculum generation)
......
...@@ -87,11 +87,22 @@ class ManagerBasedEnv: ...@@ -87,11 +87,22 @@ class ManagerBasedEnv:
print("[INFO]: Base environment:") print("[INFO]: Base environment:")
print(f"\tEnvironment device : {self.device}") print(f"\tEnvironment device : {self.device}")
print(f"\tPhysics step-size : {self.physics_dt}") 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"\tEnvironment step-size : {self.step_dt}")
print(f"\tPhysics GPU pipeline : {self.cfg.sim.use_gpu_pipeline}") print(f"\tPhysics GPU pipeline : {self.cfg.sim.use_gpu_pipeline}")
print(f"\tPhysics GPU simulation: {self.cfg.sim.physx.use_gpu}") 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 # generate scene
with Timer("[INFO]: Time taken for scene creation"): with Timer("[INFO]: Time taken for scene creation"):
self.scene = InteractiveScene(self.cfg.scene) self.scene = InteractiveScene(self.cfg.scene)
...@@ -253,17 +264,18 @@ class ManagerBasedEnv: ...@@ -253,17 +264,18 @@ class ManagerBasedEnv:
self.action_manager.process_action(action) self.action_manager.process_action(action)
# perform physics stepping # perform physics stepping
for _ in range(self.cfg.decimation): for _ in range(self.cfg.decimation):
self._sim_step_counter += 1
# set actions into buffers # set actions into buffers
self.action_manager.apply_action() self.action_manager.apply_action()
# set actions into simulator # set actions into simulator
self.scene.write_data_to_sim() 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 # simulate
self.sim.step(render=False) self.sim.step(render=render)
# update buffers at sim dt # update buffers at sim dt
self.scene.update(dt=self.physics_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 # post-step: step interval event
if "interval" in self.event_manager.available_modes: if "interval" in self.event_manager.available_modes:
......
...@@ -154,17 +154,18 @@ class ManagerBasedRLEnv(ManagerBasedEnv, gym.Env): ...@@ -154,17 +154,18 @@ class ManagerBasedRLEnv(ManagerBasedEnv, gym.Env):
self.action_manager.process_action(action) self.action_manager.process_action(action)
# perform physics stepping # perform physics stepping
for _ in range(self.cfg.decimation): for _ in range(self.cfg.decimation):
self._sim_step_counter += 1
# set actions into buffers # set actions into buffers
self.action_manager.apply_action() self.action_manager.apply_action()
# set actions into simulator # set actions into simulator
self.scene.write_data_to_sim() 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 # simulate
self.sim.step(render=False) self.sim.step(render=render)
# update buffers at sim dt # update buffers at sim dt
self.scene.update(dt=self.physics_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: # post-step:
# -- update env counters (used for curriculum generation) # -- update env counters (used for curriculum generation)
......
...@@ -168,7 +168,7 @@ class SimulationCfg: ...@@ -168,7 +168,7 @@ class SimulationCfg:
dt: float = 1.0 / 60.0 dt: float = 1.0 / 60.0
"""The physics simulation time-step (in seconds). Default is 0.0167 seconds.""" """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.""" """The number of physics simulation steps per rendering step. Default is 1."""
gravity: tuple[float, float, float] = (0.0, 0.0, -9.81) gravity: tuple[float, float, float] = (0.0, 0.0, -9.81)
......
...@@ -214,7 +214,7 @@ class SimulationContext(_SimulationContext): ...@@ -214,7 +214,7 @@ class SimulationContext(_SimulationContext):
super().__init__( super().__init__(
stage_units_in_meters=1.0, stage_units_in_meters=1.0,
physics_dt=self.cfg.dt, physics_dt=self.cfg.dt,
rendering_dt=self.cfg.dt * self.cfg.substeps, rendering_dt=self.cfg.dt * self.cfg.render_interval,
backend="torch", backend="torch",
sim_params=sim_params, sim_params=sim_params,
physics_prim_path=self.cfg.physics_prim_path, physics_prim_path=self.cfg.physics_prim_path,
...@@ -384,7 +384,7 @@ class SimulationContext(_SimulationContext): ...@@ -384,7 +384,7 @@ class SimulationContext(_SimulationContext):
self.render() self.render()
def step(self, render: bool = True): def step(self, render: bool = True):
"""Steps the physics simulation with the pre-defined time-step. """Steps the simulation.
.. note:: .. note::
This function blocks if the timeline is paused. It only returns when the timeline is playing. This function blocks if the timeline is paused. It only returns when the timeline is playing.
...@@ -467,6 +467,11 @@ class SimulationContext(_SimulationContext): ...@@ -467,6 +467,11 @@ class SimulationContext(_SimulationContext):
def _init_stage(self, *args, **kwargs) -> Usd.Stage: def _init_stage(self, *args, **kwargs) -> Usd.Stage:
_ = super()._init_stage(*args, **kwargs) _ = 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 # set additional physx parameters and bind material
self._set_additional_physx_params() self._set_additional_physx_params()
# load flatcache/fabric interface # load flatcache/fabric interface
......
...@@ -144,7 +144,7 @@ def main(): ...@@ -144,7 +144,7 @@ def main():
"""Main function.""" """Main function."""
# Initialize the simulation context # 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 # Set main camera
sim.set_camera_view(eye=[2.5, 2.5, 2.5], target=[0.0, 0.0, 0.0]) sim.set_camera_view(eye=[2.5, 2.5, 2.5], target=[0.0, 0.0, 0.0])
# design scene # design scene
......
...@@ -128,7 +128,7 @@ def main(): ...@@ -128,7 +128,7 @@ def main():
"""Main function.""" """Main function."""
# Initialize the simulation context # 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) sim = sim_utils.SimulationContext(sim_cfg)
# Set main camera # Set main camera
sim.set_camera_view(eye=[3.5, 3.5, 3.5], target=[0.0, 0.0, 0.0]) sim.set_camera_view(eye=[3.5, 3.5, 3.5], target=[0.0, 0.0, 0.0])
......
...@@ -9,10 +9,8 @@ ...@@ -9,10 +9,8 @@
from omni.isaac.lab.app import AppLauncher, run_tests from omni.isaac.lab.app import AppLauncher, run_tests
HEADLESS = True
# launch omniverse app # launch omniverse app
app_launcher = AppLauncher(headless=HEADLESS) app_launcher = AppLauncher(headless=True)
simulation_app = app_launcher.app simulation_app = app_launcher.app
"""Rest everything follows.""" """Rest everything follows."""
...@@ -467,7 +465,7 @@ class TestContactSensor(unittest.TestCase): ...@@ -467,7 +465,7 @@ class TestContactSensor(unittest.TestCase):
# write data to simulation # write data to simulation
self.scene.write_data_to_sim() self.scene.write_data_to_sim()
# simulate # simulate
self.sim.step(render=not HEADLESS) self.sim.step(render=False)
# update buffers at sim dt # update buffers at sim dt
self.scene.update(dt=self.sim_dt) self.scene.update(dt=self.sim_dt)
......
...@@ -52,7 +52,7 @@ class TestSimulationContext(unittest.TestCase): ...@@ -52,7 +52,7 @@ class TestSimulationContext(unittest.TestCase):
def test_initialization(self): def test_initialization(self):
"""Test the simulation config.""" """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) sim = SimulationContext(cfg)
# TODO: Figure out why keyword argument doesn't work. # TODO: Figure out why keyword argument doesn't work.
# note: added a fix in Isaac Sim 2023.1 for this. # note: added a fix in Isaac Sim 2023.1 for this.
...@@ -60,7 +60,7 @@ class TestSimulationContext(unittest.TestCase): ...@@ -60,7 +60,7 @@ class TestSimulationContext(unittest.TestCase):
# check valid settings # check valid settings
self.assertEqual(sim.get_physics_dt(), cfg.dt) 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()) self.assertFalse(sim.has_rtx_sensors())
# check valid paths # check valid paths
self.assertTrue(prim_utils.is_prim_path_valid("/Physics/PhysX")) self.assertTrue(prim_utils.is_prim_path_valid("/Physics/PhysX"))
......
[package] [package]
# Note: Semantic Versioning is used: https://semver.org/ # Note: Semantic Versioning is used: https://semver.org/
version = "0.7.6" version = "0.7.7"
# Description # Description
title = "Isaac Lab Environments" title = "Isaac Lab Environments"
......
Changelog 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) 0.7.6 (2024-06-13)
~~~~~~~~~~~~~~~~~~ ~~~~~~~~~~~~~~~~~~
......
...@@ -20,8 +20,16 @@ from omni.isaac.lab_tasks.direct.locomotion.locomotion_env import LocomotionEnv ...@@ -20,8 +20,16 @@ from omni.isaac.lab_tasks.direct.locomotion.locomotion_env import LocomotionEnv
@configclass @configclass
class AntEnvCfg(DirectRLEnvCfg): 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 # simulation
sim: SimulationCfg = SimulationCfg(dt=1 / 120) sim: SimulationCfg = SimulationCfg(dt=1 / 120, render_interval=decimation)
terrain = TerrainImporterCfg( terrain = TerrainImporterCfg(
prim_path="/World/ground", prim_path="/World/ground",
terrain_type="plane", terrain_type="plane",
...@@ -43,14 +51,6 @@ class AntEnvCfg(DirectRLEnvCfg): ...@@ -43,14 +51,6 @@ class AntEnvCfg(DirectRLEnvCfg):
robot: ArticulationCfg = ANT_CFG.replace(prim_path="/World/envs/env_.*/Robot") robot: ArticulationCfg = ANT_CFG.replace(prim_path="/World/envs/env_.*/Robot")
joint_gears: list = [15, 15, 15, 15, 15, 15, 15, 15] 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 heading_weight: float = 0.5
up_weight: float = 0.1 up_weight: float = 0.1
......
...@@ -25,9 +25,18 @@ from omni.isaac.lab.terrains.config.rough import ROUGH_TERRAINS_CFG # isort: sk ...@@ -25,9 +25,18 @@ from omni.isaac.lab.terrains.config.rough import ROUGH_TERRAINS_CFG # isort: sk
@configclass @configclass
class AnymalCFlatEnvCfg(DirectRLEnvCfg): 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 # simulation
sim: SimulationCfg = SimulationCfg( sim: SimulationCfg = SimulationCfg(
dt=1 / 200, dt=1 / 200,
render_interval=decimation,
disable_contact_processing=True, disable_contact_processing=True,
physics_material=sim_utils.RigidBodyMaterialCfg( physics_material=sim_utils.RigidBodyMaterialCfg(
friction_combine_mode="multiply", friction_combine_mode="multiply",
...@@ -60,14 +69,6 @@ class AnymalCFlatEnvCfg(DirectRLEnvCfg): ...@@ -60,14 +69,6 @@ class AnymalCFlatEnvCfg(DirectRLEnvCfg):
prim_path="/World/envs/env_.*/Robot/.*", history_length=3, update_period=0.005, track_air_time=True 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 # reward scales
lin_vel_reward_scale = 1.0 lin_vel_reward_scale = 1.0
yaw_rate_reward_scale = 0.5 yaw_rate_reward_scale = 0.5
......
...@@ -26,8 +26,16 @@ from omni.isaac.lab.utils.math import sample_uniform ...@@ -26,8 +26,16 @@ from omni.isaac.lab.utils.math import sample_uniform
@configclass @configclass
class CartpoleRGBCameraEnvCfg(DirectRLEnvCfg): class CartpoleRGBCameraEnvCfg(DirectRLEnvCfg):
# env
decimation = 2
episode_length_s = 5.0
action_scale = 100.0 # [N]
num_actions = 1
num_channels = 3
num_states = 0
# simulation # simulation
sim: SimulationCfg = SimulationCfg(dt=1 / 120) sim: SimulationCfg = SimulationCfg(dt=1 / 120, render_interval=decimation)
# robot # robot
robot_cfg: ArticulationCfg = CARTPOLE_CFG.replace(prim_path="/World/envs/env_.*/Robot") robot_cfg: ArticulationCfg = CARTPOLE_CFG.replace(prim_path="/World/envs/env_.*/Robot")
...@@ -45,6 +53,7 @@ class CartpoleRGBCameraEnvCfg(DirectRLEnvCfg): ...@@ -45,6 +53,7 @@ class CartpoleRGBCameraEnvCfg(DirectRLEnvCfg):
width=80, width=80,
height=80, height=80,
) )
num_observations = num_channels * tiled_camera.height * tiled_camera.width
write_image_to_file = False write_image_to_file = False
# change viewer settings # change viewer settings
...@@ -53,15 +62,6 @@ class CartpoleRGBCameraEnvCfg(DirectRLEnvCfg): ...@@ -53,15 +62,6 @@ class CartpoleRGBCameraEnvCfg(DirectRLEnvCfg):
# scene # scene
scene: InteractiveSceneCfg = InteractiveSceneCfg(num_envs=256, env_spacing=20.0, replicate_physics=True) scene: InteractiveSceneCfg = InteractiveSceneCfg(num_envs=256, env_spacing=20.0, replicate_physics=True)
# env
decimation = 2
episode_length_s = 5.0
action_scale = 100.0 # [N]
num_actions = 1
num_channels = 3
num_observations = num_channels * tiled_camera.height * tiled_camera.width
num_states = 0
# reset # reset
max_cart_pos = 3.0 # the cart is reset if it exceeds that position [m] max_cart_pos = 3.0 # the cart is reset if it exceeds that position [m]
initial_pole_angle_range = [-0.125, 0.125] # the range in which the pole angle is sampled from on reset [rad] initial_pole_angle_range = [-0.125, 0.125] # the range in which the pole angle is sampled from on reset [rad]
......
...@@ -23,8 +23,16 @@ from omni.isaac.lab.utils.math import sample_uniform ...@@ -23,8 +23,16 @@ from omni.isaac.lab.utils.math import sample_uniform
@configclass @configclass
class CartpoleEnvCfg(DirectRLEnvCfg): class CartpoleEnvCfg(DirectRLEnvCfg):
# env
decimation = 2
episode_length_s = 5.0
action_scale = 100.0 # [N]
num_actions = 1
num_observations = 4
num_states = 0
# simulation # simulation
sim: SimulationCfg = SimulationCfg(dt=1 / 120) sim: SimulationCfg = SimulationCfg(dt=1 / 120, render_interval=decimation)
# robot # robot
robot_cfg: ArticulationCfg = CARTPOLE_CFG.replace(prim_path="/World/envs/env_.*/Robot") robot_cfg: ArticulationCfg = CARTPOLE_CFG.replace(prim_path="/World/envs/env_.*/Robot")
...@@ -34,14 +42,6 @@ class CartpoleEnvCfg(DirectRLEnvCfg): ...@@ -34,14 +42,6 @@ class CartpoleEnvCfg(DirectRLEnvCfg):
# scene # scene
scene: InteractiveSceneCfg = InteractiveSceneCfg(num_envs=4096, env_spacing=4.0, replicate_physics=True) scene: InteractiveSceneCfg = InteractiveSceneCfg(num_envs=4096, env_spacing=4.0, replicate_physics=True)
# env
decimation = 2
episode_length_s = 5.0
action_scale = 100.0 # [N]
num_actions = 1
num_observations = 4
num_states = 0
# reset # reset
max_cart_pos = 3.0 # the cart is reset if it exceeds that position [m] max_cart_pos = 3.0 # the cart is reset if it exceeds that position [m]
initial_pole_angle_range = [-0.25, 0.25] # the range in which the pole angle is sampled from on reset [rad] initial_pole_angle_range = [-0.25, 0.25] # the range in which the pole angle is sampled from on reset [rad]
......
...@@ -25,7 +25,6 @@ from omni.isaac.lab.utils.math import sample_uniform ...@@ -25,7 +25,6 @@ from omni.isaac.lab.utils.math import sample_uniform
@configclass @configclass
class FrankaCabinetEnvCfg(DirectRLEnvCfg): class FrankaCabinetEnvCfg(DirectRLEnvCfg):
# env # env
episode_length_s = 8.3333 # 500 timesteps episode_length_s = 8.3333 # 500 timesteps
decimation = 2 decimation = 2
...@@ -33,12 +32,10 @@ class FrankaCabinetEnvCfg(DirectRLEnvCfg): ...@@ -33,12 +32,10 @@ class FrankaCabinetEnvCfg(DirectRLEnvCfg):
num_observations = 23 num_observations = 23
num_states = 0 num_states = 0
action_scale = 7.5
dof_velocity_scale = 0.1
# simulation # simulation
sim: SimulationCfg = SimulationCfg( sim: SimulationCfg = SimulationCfg(
dt=1 / 120, dt=1 / 120,
render_interval=decimation,
disable_contact_processing=True, disable_contact_processing=True,
physics_material=sim_utils.RigidBodyMaterialCfg( physics_material=sim_utils.RigidBodyMaterialCfg(
friction_combine_mode="multiply", friction_combine_mode="multiply",
...@@ -154,6 +151,9 @@ class FrankaCabinetEnvCfg(DirectRLEnvCfg): ...@@ -154,6 +151,9 @@ class FrankaCabinetEnvCfg(DirectRLEnvCfg):
), ),
) )
action_scale = 7.5
dof_velocity_scale = 0.1
# reward scales # reward scales
dist_reward_scale = 2.0 dist_reward_scale = 2.0
rot_reward_scale = 0.5 rot_reward_scale = 0.5
......
...@@ -20,8 +20,16 @@ from omni.isaac.lab_tasks.direct.locomotion.locomotion_env import LocomotionEnv ...@@ -20,8 +20,16 @@ from omni.isaac.lab_tasks.direct.locomotion.locomotion_env import LocomotionEnv
@configclass @configclass
class HumanoidEnvCfg(DirectRLEnvCfg): class HumanoidEnvCfg(DirectRLEnvCfg):
# env
episode_length_s = 15.0
decimation = 2
action_scale = 1.0
num_actions = 21
num_observations = 75
num_states = 0
# simulation # simulation
sim: SimulationCfg = SimulationCfg(dt=1 / 120) sim: SimulationCfg = SimulationCfg(dt=1 / 120, render_interval=decimation)
terrain = TerrainImporterCfg( terrain = TerrainImporterCfg(
prim_path="/World/ground", prim_path="/World/ground",
terrain_type="plane", terrain_type="plane",
...@@ -65,14 +73,6 @@ class HumanoidEnvCfg(DirectRLEnvCfg): ...@@ -65,14 +73,6 @@ class HumanoidEnvCfg(DirectRLEnvCfg):
22.5, # left_foot 22.5, # left_foot
] ]
# env
episode_length_s = 15.0
decimation = 2
action_scale = 1.0
num_actions = 21
num_observations = 75
num_states = 0
heading_weight: float = 0.5 heading_weight: float = 0.5
up_weight: float = 0.1 up_weight: float = 0.1
......
...@@ -47,11 +47,20 @@ class QuadcopterEnvWindow(BaseEnvWindow): ...@@ -47,11 +47,20 @@ class QuadcopterEnvWindow(BaseEnvWindow):
@configclass @configclass
class QuadcopterEnvCfg(DirectRLEnvCfg): class QuadcopterEnvCfg(DirectRLEnvCfg):
# env
episode_length_s = 10.0
decimation = 2
num_actions = 4
num_observations = 12
num_states = 0
debug_vis = True
ui_window_class_type = QuadcopterEnvWindow ui_window_class_type = QuadcopterEnvWindow
# simulation # simulation
sim: SimulationCfg = SimulationCfg( sim: SimulationCfg = SimulationCfg(
dt=1 / 100, dt=1 / 100,
render_interval=decimation,
disable_contact_processing=True, disable_contact_processing=True,
physics_material=sim_utils.RigidBodyMaterialCfg( physics_material=sim_utils.RigidBodyMaterialCfg(
friction_combine_mode="multiply", friction_combine_mode="multiply",
...@@ -83,14 +92,6 @@ class QuadcopterEnvCfg(DirectRLEnvCfg): ...@@ -83,14 +92,6 @@ class QuadcopterEnvCfg(DirectRLEnvCfg):
thrust_to_weight = 1.9 thrust_to_weight = 1.9
moment_scale = 0.01 moment_scale = 0.01
# env
episode_length_s = 10.0
decimation = 2
num_actions = 4
num_observations = 12
num_states = 0
debug_vis = True
# reward scales # reward scales
lin_vel_reward_scale = -0.05 lin_vel_reward_scale = -0.05
ang_vel_reward_scale = -0.01 ang_vel_reward_scale = -0.01
......
...@@ -110,9 +110,19 @@ class EventCfg: ...@@ -110,9 +110,19 @@ class EventCfg:
@configclass @configclass
class ShadowHandEnvCfg(DirectRLEnvCfg): class ShadowHandEnvCfg(DirectRLEnvCfg):
# env
decimation = 2
episode_length_s = 10.0
num_actions = 20
num_observations = 157 # (full)
num_states = 0
asymmetric_obs = False
obs_type = "full"
# simulation # simulation
sim: SimulationCfg = SimulationCfg( sim: SimulationCfg = SimulationCfg(
dt=1 / 120, dt=1 / 120,
render_interval=decimation,
physics_material=RigidBodyMaterialCfg( physics_material=RigidBodyMaterialCfg(
static_friction=1.0, static_friction=1.0,
dynamic_friction=1.0, dynamic_friction=1.0,
...@@ -190,14 +200,7 @@ class ShadowHandEnvCfg(DirectRLEnvCfg): ...@@ -190,14 +200,7 @@ class ShadowHandEnvCfg(DirectRLEnvCfg):
) )
# scene # scene
scene: InteractiveSceneCfg = InteractiveSceneCfg(num_envs=8192, env_spacing=0.75, replicate_physics=True) scene: InteractiveSceneCfg = InteractiveSceneCfg(num_envs=8192, env_spacing=0.75, replicate_physics=True)
# env
decimation = 2
episode_length_s = 10.0
num_actions = 20
num_observations = 157 # (full)
num_states = 0
asymmetric_obs = False
obs_type = "full"
# reset # reset
reset_position_noise = 0.01 # range of position at reset reset_position_noise = 0.01 # range of position at reset
reset_dof_pos_noise = 0.2 # range of dof pos at reset reset_dof_pos_noise = 0.2 # range of dof pos at reset
......
...@@ -194,6 +194,7 @@ class AntEnvCfg(ManagerBasedRLEnvCfg): ...@@ -194,6 +194,7 @@ class AntEnvCfg(ManagerBasedRLEnvCfg):
self.episode_length_s = 16.0 self.episode_length_s = 16.0
# simulation settings # simulation settings
self.sim.dt = 1 / 120.0 self.sim.dt = 1 / 120.0
self.sim.render_interval = self.decimation
self.sim.physx.bounce_threshold_velocity = 0.2 self.sim.physx.bounce_threshold_velocity = 0.2
# default friction material # default friction material
self.sim.physics_material.static_friction = 1.0 self.sim.physics_material.static_friction = 1.0
......
...@@ -201,3 +201,4 @@ class CartpoleEnvCfg(ManagerBasedRLEnvCfg): ...@@ -201,3 +201,4 @@ class CartpoleEnvCfg(ManagerBasedRLEnvCfg):
self.viewer.eye = (8.0, 0.0, 5.0) self.viewer.eye = (8.0, 0.0, 5.0)
# simulation settings # simulation settings
self.sim.dt = 1 / 120 self.sim.dt = 1 / 120
self.sim.render_interval = self.decimation
...@@ -279,6 +279,7 @@ class HumanoidEnvCfg(ManagerBasedRLEnvCfg): ...@@ -279,6 +279,7 @@ class HumanoidEnvCfg(ManagerBasedRLEnvCfg):
self.episode_length_s = 16.0 self.episode_length_s = 16.0
# simulation settings # simulation settings
self.sim.dt = 1 / 120.0 self.sim.dt = 1 / 120.0
self.sim.render_interval = self.decimation
self.sim.physx.bounce_threshold_velocity = 0.2 self.sim.physx.bounce_threshold_velocity = 0.2
# default friction material # default friction material
self.sim.physics_material.static_friction = 1.0 self.sim.physics_material.static_friction = 1.0
......
...@@ -326,7 +326,7 @@ class SpotFlatEnvCfg(LocomotionVelocityRoughEnvCfg): ...@@ -326,7 +326,7 @@ class SpotFlatEnvCfg(LocomotionVelocityRoughEnvCfg):
self.episode_length_s = 20.0 self.episode_length_s = 20.0
# simulation settings # simulation settings
self.sim.dt = 0.002 # 500 Hz self.sim.dt = 0.002 # 500 Hz
self.sim.substeps = 1 self.sim.render_interval = self.decimation
self.sim.disable_contact_processing = True self.sim.disable_contact_processing = True
self.sim.physics_material.static_friction = 1.0 self.sim.physics_material.static_friction = 1.0
self.sim.physics_material.dynamic_friction = 1.0 self.sim.physics_material.dynamic_friction = 1.0
......
...@@ -300,6 +300,7 @@ class LocomotionVelocityRoughEnvCfg(ManagerBasedRLEnvCfg): ...@@ -300,6 +300,7 @@ class LocomotionVelocityRoughEnvCfg(ManagerBasedRLEnvCfg):
self.episode_length_s = 20.0 self.episode_length_s = 20.0
# simulation settings # simulation settings
self.sim.dt = 0.005 self.sim.dt = 0.005
self.sim.render_interval = self.decimation
self.sim.disable_contact_processing = True self.sim.disable_contact_processing = True
self.sim.physics_material = self.scene.terrain.physics_material self.sim.physics_material = self.scene.terrain.physics_material
# update sensor update periods # update sensor update periods
......
...@@ -282,6 +282,7 @@ class CabinetEnvCfg(ManagerBasedRLEnvCfg): ...@@ -282,6 +282,7 @@ class CabinetEnvCfg(ManagerBasedRLEnvCfg):
self.viewer.lookat = (0.8, 0.0, 0.5) self.viewer.lookat = (0.8, 0.0, 0.5)
# simulation settings # simulation settings
self.sim.dt = 1 / 60 # 60Hz self.sim.dt = 1 / 60 # 60Hz
self.sim.render_interval = self.decimation
self.sim.physx.bounce_threshold_velocity = 0.2 self.sim.physx.bounce_threshold_velocity = 0.2
self.sim.physx.bounce_threshold_velocity = 0.01 self.sim.physx.bounce_threshold_velocity = 0.01
self.sim.physx.friction_correlation_distance = 0.00625 self.sim.physx.friction_correlation_distance = 0.00625
...@@ -341,5 +341,6 @@ class InHandObjectEnvCfg(ManagerBasedRLEnvCfg): ...@@ -341,5 +341,6 @@ class InHandObjectEnvCfg(ManagerBasedRLEnvCfg):
self.episode_length_s = 20.0 self.episode_length_s = 20.0
# simulation settings # simulation settings
self.sim.dt = 1.0 / 120.0 self.sim.dt = 1.0 / 120.0
self.sim.render_interval = self.decimation
# change viewer settings # change viewer settings
self.viewer.eye = (2.0, 2.0, 2.0) self.viewer.eye = (2.0, 2.0, 2.0)
...@@ -213,6 +213,7 @@ class LiftEnvCfg(ManagerBasedRLEnvCfg): ...@@ -213,6 +213,7 @@ class LiftEnvCfg(ManagerBasedRLEnvCfg):
self.episode_length_s = 5.0 self.episode_length_s = 5.0
# simulation settings # simulation settings
self.sim.dt = 0.01 # 100Hz self.sim.dt = 0.01 # 100Hz
self.sim.render_interval = self.decimation
self.sim.physx.bounce_threshold_velocity = 0.2 self.sim.physx.bounce_threshold_velocity = 0.2
self.sim.physx.bounce_threshold_velocity = 0.01 self.sim.physx.bounce_threshold_velocity = 0.01
......
...@@ -141,6 +141,7 @@ class NavigationEnvCfg(ManagerBasedRLEnvCfg): ...@@ -141,6 +141,7 @@ class NavigationEnvCfg(ManagerBasedRLEnvCfg):
"""Post initialization.""" """Post initialization."""
self.sim.dt = LOW_LEVEL_ENV_CFG.sim.dt self.sim.dt = LOW_LEVEL_ENV_CFG.sim.dt
self.sim.render_interval = LOW_LEVEL_ENV_CFG.decimation
self.decimation = LOW_LEVEL_ENV_CFG.decimation * 10 self.decimation = LOW_LEVEL_ENV_CFG.decimation * 10
self.episode_length_s = self.commands.pose_command.resampling_time_range[1] self.episode_length_s = self.commands.pose_command.resampling_time_range[1]
......
...@@ -145,7 +145,7 @@ def main(): ...@@ -145,7 +145,7 @@ def main():
"""Main function.""" """Main function."""
# Initialize the simulation context # 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 # Set main camera
sim.set_camera_view(eye=[0.0, -0.5, 1.5], target=[0.0, -0.2, 0.5]) sim.set_camera_view(eye=[0.0, -0.5, 1.5], target=[0.0, -0.2, 0.5])
# design scene # design scene
......
...@@ -94,7 +94,7 @@ def define_markers() -> VisualizationMarkers: ...@@ -94,7 +94,7 @@ def define_markers() -> VisualizationMarkers:
def main(): def main():
"""Main function.""" """Main function."""
# Load kit helper # Load kit helper
sim = SimulationContext(sim_utils.SimulationCfg(dt=0.01, substeps=1)) sim = SimulationContext(sim_utils.SimulationCfg(dt=0.01))
# Set main camera # Set main camera
sim.set_camera_view([0.0, 18.0, 12.0], [0.0, 3.0, 0.0]) sim.set_camera_view([0.0, 18.0, 12.0], [0.0, 3.0, 0.0])
......
...@@ -154,7 +154,7 @@ def main(): ...@@ -154,7 +154,7 @@ def main():
"""Main function.""" """Main function."""
# Initialize the simulation context # 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 # Set main camera
sim.set_camera_view(eye=[2.5, 2.5, 2.5], target=[0.0, 0.0, 0.0]) sim.set_camera_view(eye=[2.5, 2.5, 2.5], target=[0.0, 0.0, 0.0])
# design scene # design scene
......
...@@ -171,7 +171,7 @@ def main(): ...@@ -171,7 +171,7 @@ def main():
"""Main function.""" """Main function."""
# Initialize the simulation context # 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 # Set main camera
sim.set_camera_view(eye=[2.5, 2.5, 2.5], target=[0.0, 0.0, 0.0]) sim.set_camera_view(eye=[2.5, 2.5, 2.5], target=[0.0, 0.0, 0.0])
# design scene # design scene
......
...@@ -38,7 +38,7 @@ def main(): ...@@ -38,7 +38,7 @@ def main():
"""Main function.""" """Main function."""
# Initialize the simulation context # Initialize the simulation context
sim_cfg = SimulationCfg(dt=0.01, substeps=1) sim_cfg = SimulationCfg(dt=0.01)
sim = SimulationContext(sim_cfg) sim = SimulationContext(sim_cfg)
# Set main camera # Set main camera
sim.set_camera_view([2.5, 2.5, 2.5], [0.0, 0.0, 0.0]) sim.set_camera_view([2.5, 2.5, 2.5], [0.0, 0.0, 0.0])
......
...@@ -70,7 +70,7 @@ def main(): ...@@ -70,7 +70,7 @@ def main():
"""Main function.""" """Main function."""
# Initialize the simulation context # Initialize the simulation context
sim_cfg = sim_utils.SimulationCfg(dt=0.01, substeps=1) sim_cfg = sim_utils.SimulationCfg(dt=0.01)
sim = sim_utils.SimulationContext(sim_cfg) sim = sim_utils.SimulationContext(sim_cfg)
# Set main camera # Set main camera
sim.set_camera_view([2.0, 0.0, 2.5], [-0.5, 0.0, 0.5]) sim.set_camera_view([2.0, 0.0, 2.5], [-0.5, 0.0, 0.5])
......
...@@ -51,7 +51,7 @@ def main(): ...@@ -51,7 +51,7 @@ def main():
print(f"[INFO] Logging experiment to directory: {log_dir_path}") print(f"[INFO] Logging experiment to directory: {log_dir_path}")
# Initialize the simulation context # Initialize the simulation context
sim_cfg = SimulationCfg(dt=0.01, substeps=1) sim_cfg = SimulationCfg(dt=0.01)
sim = SimulationContext(sim_cfg) sim = SimulationContext(sim_cfg)
# Set main camera # Set main camera
sim.set_camera_view([2.5, 2.5, 2.5], [0.0, 0.0, 0.0]) sim.set_camera_view([2.5, 2.5, 2.5], [0.0, 0.0, 0.0])
......
...@@ -83,7 +83,7 @@ def main(): ...@@ -83,7 +83,7 @@ def main():
"""Main function.""" """Main function."""
# Initialize the simulation context # Initialize the simulation context
sim_cfg = sim_utils.SimulationCfg(dt=0.01, substeps=1) sim_cfg = sim_utils.SimulationCfg(dt=0.01)
sim = sim_utils.SimulationContext(sim_cfg) sim = sim_utils.SimulationContext(sim_cfg)
# Set main camera # Set main camera
sim.set_camera_view([2.0, 0.0, 2.5], [-0.5, 0.0, 0.5]) sim.set_camera_view([2.0, 0.0, 2.5], [-0.5, 0.0, 0.5])
......
...@@ -156,7 +156,7 @@ def main(): ...@@ -156,7 +156,7 @@ def main():
"""Main function.""" """Main function."""
# Initialize the simulation context # 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) sim = sim_utils.SimulationContext(sim_cfg)
# Set main camera # Set main camera
sim.set_camera_view(eye=[3.5, 3.5, 3.5], target=[0.0, 0.0, 0.0]) sim.set_camera_view(eye=[3.5, 3.5, 3.5], target=[0.0, 0.0, 0.0])
......
...@@ -32,6 +32,9 @@ parser.add_argument("--max_iterations", type=int, default=None, help="RL Policy ...@@ -32,6 +32,9 @@ parser.add_argument("--max_iterations", type=int, default=None, help="RL Policy
AppLauncher.add_app_launcher_args(parser) AppLauncher.add_app_launcher_args(parser)
# parse the arguments # parse the arguments
args_cli = parser.parse_args() args_cli = parser.parse_args()
# always enable cameras to record video
if args_cli.video:
args_cli.enable_cameras = True
# launch omniverse app # launch omniverse app
app_launcher = AppLauncher(args_cli) app_launcher = AppLauncher(args_cli)
......
...@@ -33,6 +33,9 @@ cli_args.add_rsl_rl_args(parser) ...@@ -33,6 +33,9 @@ cli_args.add_rsl_rl_args(parser)
# append AppLauncher cli args # append AppLauncher cli args
AppLauncher.add_app_launcher_args(parser) AppLauncher.add_app_launcher_args(parser)
args_cli = parser.parse_args() args_cli = parser.parse_args()
# always enable cameras to record video
if args_cli.video:
args_cli.enable_cameras = True
# launch omniverse app # launch omniverse app
app_launcher = AppLauncher(args_cli) app_launcher = AppLauncher(args_cli)
......
...@@ -33,6 +33,9 @@ parser.add_argument("--max_iterations", type=int, default=None, help="RL Policy ...@@ -33,6 +33,9 @@ parser.add_argument("--max_iterations", type=int, default=None, help="RL Policy
AppLauncher.add_app_launcher_args(parser) AppLauncher.add_app_launcher_args(parser)
# parse the arguments # parse the arguments
args_cli = parser.parse_args() args_cli = parser.parse_args()
# always enable cameras to record video
if args_cli.video:
args_cli.enable_cameras = True
# launch omniverse app # launch omniverse app
app_launcher = AppLauncher(args_cli) app_launcher = AppLauncher(args_cli)
......
...@@ -35,6 +35,9 @@ AppLauncher.add_app_launcher_args(parser) ...@@ -35,6 +35,9 @@ AppLauncher.add_app_launcher_args(parser)
# parse the arguments # parse the arguments
args_cli = parser.parse_args() args_cli = parser.parse_args()
if args_cli.video:
args_cli.enable_cameras = True
# launch omniverse app # launch omniverse app
app_launcher = AppLauncher(args_cli) app_launcher = AppLauncher(args_cli)
simulation_app = app_launcher.app simulation_app = app_launcher.app
......
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