Unverified Commit 40e4591f authored by Pascal Roth's avatar Pascal Roth Committed by GitHub

Renames `RandomizationManager` to `EventManager` (#460)

# Description

Renames the `RandomizationManager` to `EventManager` for clarity as the
manager takes care of all kind of events that go beyond pure
randomization (such as resets).

Fixes #413

## Type of change

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

## Checklist

- [x] I have run the [`pre-commit` checks](https://pre-commit.com/) with
`./orbit.sh --format`
- [x] I have made corresponding changes to the documentation
- [x] My changes generate no new warnings
- [ ] I have added tests that prove my fix is effective or that my
feature works
- [x] I have run all the tests with `./orbit.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 8453d7e1
...@@ -19,10 +19,10 @@ Actions ...@@ -19,10 +19,10 @@ Actions
:show-inheritance: :show-inheritance:
:exclude-members: __init__, class_type :exclude-members: __init__, class_type
Randomization Events
------------- ------
.. automodule:: omni.isaac.orbit.envs.mdp.randomizations .. automodule:: omni.isaac.orbit.envs.mdp.events
:members: :members:
Commands Commands
......
...@@ -17,8 +17,8 @@ ...@@ -17,8 +17,8 @@
ActionManager ActionManager
ActionTerm ActionTerm
ActionTermCfg ActionTermCfg
RandomizationManager EventManager
RandomizationTermCfg EventTermCfg
CommandManager CommandManager
CommandTerm CommandTerm
CommandTermCfg CommandTermCfg
...@@ -82,9 +82,25 @@ Action Manager ...@@ -82,9 +82,25 @@ Action Manager
:members: :members:
:exclude-members: __init__ :exclude-members: __init__
Event Manager
-------------
.. autoclass:: EventManager
:members:
:inherited-members:
:show-inheritance:
.. autoclass:: EventTermCfg
:members:
:exclude-members: __init__
Randomization Manager Randomization Manager
--------------------- ---------------------
.. deprecated:: v0.3
The Randomization Manager is deprecated and will be removed in v0.4.
Please use the :class:`EventManager` class instead.
.. autoclass:: RandomizationManager .. autoclass:: RandomizationManager
:members: :members:
:inherited-members: :inherited-members:
......
...@@ -7,7 +7,7 @@ Creating a Base Environment ...@@ -7,7 +7,7 @@ Creating a Base Environment
.. currentmodule:: omni.isaac.orbit .. currentmodule:: omni.isaac.orbit
Environments bring together different aspects of the simulation such as Environments bring together different aspects of the simulation such as
the scene, observations and actions spaces, randomizations, etc. to create a the scene, observations and actions spaces, reset events etc. to create a
coherent interface for various applications. In Orbit, environments are coherent interface for various applications. In Orbit, environments are
implemented as :class:`envs.BaseEnv` and :class:`envs.RLTaskEnv` classes. implemented as :class:`envs.BaseEnv` and :class:`envs.RLTaskEnv` classes.
The two classes are very similar, but :class:`envs.RLTaskEnv` is useful for The two classes are very similar, but :class:`envs.RLTaskEnv` is useful for
...@@ -46,7 +46,8 @@ is composed of the following components: ...@@ -46,7 +46,8 @@ is composed of the following components:
* :class:`scene.InteractiveScene` - The scene that is used for the simulation. * :class:`scene.InteractiveScene` - The scene that is used for the simulation.
* :class:`managers.ActionManager` - The manager that handles actions. * :class:`managers.ActionManager` - The manager that handles actions.
* :class:`managers.ObservationManager` - The manager that handles observations. * :class:`managers.ObservationManager` - The manager that handles observations.
* :class:`managers.RandomizationManager` - The manager that handles randomizations. * :class:`managers.EventManager` - The manager that schedules operations (such as domain randomization)
at specified simulation events. For instance, at startup, on resets, or periodic intervals.
By configuring these components, the user can create different variations of the same environment By configuring these components, the user can create different variations of the same environment
with minimal effort. In this tutorial, we will go through the different components of the with minimal effort. In this tutorial, we will go through the different components of the
...@@ -110,40 +111,42 @@ default values for this tutorial. ...@@ -110,40 +111,42 @@ default values for this tutorial.
:language: python :language: python
:pyobject: ObservationsCfg :pyobject: ObservationsCfg
Defining randomizations Defining events
----------------------- ---------------
At this point, we have defined the scene, actions and observations for the cartpole environment. At this point, we have defined the scene, actions and observations for the cartpole environment.
The general idea for all these components is to define the configuration classes and then The general idea for all these components is to define the configuration classes and then
pass them to the corresponding managers. The randomization manager is no different. pass them to the corresponding managers. The event manager is no different.
The :class:`managers.RandomizationManager` class is responsible for randomizing everything related The :class:`managers.EventManager` class is responsible for events corresponding to changes
to the simulation state. This includes randomizing (or resetting) the scene, randomizing physical in the simulation state. This includes resetting (or randomizing) the scene, randomizing physical
properties (such as mass, friction, etc.), and visual properties (such as colors, textures, etc.). properties (such as mass, friction, etc.), and varying visual properties (such as colors, textures, etc.).
Each of these are specified through the :class:`managers.RandomizationTermCfg` class, which Each of these are specified through the :class:`managers.EventTermCfg` class, which
takes in the :attr:`managers.RandomizationTermCfg.func` that specifies the function or callable takes in the :attr:`managers.EventTermCfg.func` that specifies the function or callable
class that performs the randomization. Additionally, it expects the **mode** of randomization. class that performs the event.
The mode specifies when the randomization term should be applied. It is possible to specify
your own mode, but Orbit provides three modes out of the box:
* ``"startup"`` - Randomize only once at environment startup. Additionally, it expects the **mode** of the event. The mode specifies when the event term should be applied.
* ``"reset"`` - Randomize on every call to an environment's reset. It is possible to specify your own mode. For this, you'll need to adapt the :class:`~envs.BaseEnv` class.
* ``"interval"`` - Randomize at a given fixed interval. However, out of the box, Orbit provides three commonly used modes:
For this example, we randomize the pole's mass on startup. This is done only once since this operation * ``"startup"`` - Event that takes place only once at environment startup.
is expensive and we don't want to do it on every reset. We also randomize the initial joint state of * ``"reset"`` - Event that occurs on environment termination and reset.
the cartpole and the pole at every reset. * ``"interval"`` - Event that are executed at a given interval, i.e., periodically after a certain number of steps.
For this example, we define events that randomize the pole's mass on startup. This is done only once since this
operation is expensive and we don't want to do it on every reset. We also create an event to randomize the initial
joint state of the cartpole and the pole at every reset.
.. literalinclude:: ../../../../source/standalone/tutorials/03_envs/create_cartpole_base_env.py .. literalinclude:: ../../../../source/standalone/tutorials/03_envs/create_cartpole_base_env.py
:language: python :language: python
:pyobject: RandomizationCfg :pyobject: EventCfg
Tying it all together Tying it all together
--------------------- ---------------------
Having defined the scene and manager configurations, we can now define the environment configuration Having defined the scene and manager configurations, we can now define the environment configuration
through the :class:`envs.BaseEnvCfg` class. This class takes in the scene, action, observation and through the :class:`envs.BaseEnvCfg` class. This class takes in the scene, action, observation and
randomization configurations. event configurations.
In addition to these, it also takes in the :attr:`envs.BaseEnvCfg.sim` which defines the simulation In addition to these, it also takes in the :attr:`envs.BaseEnvCfg.sim` which defines the simulation
parameters such as the timestep, gravity, etc. This is initialized to the default values, but can parameters such as the timestep, gravity, etc. This is initialized to the default values, but can
......
...@@ -57,7 +57,7 @@ The Code Explained ...@@ -57,7 +57,7 @@ The Code Explained
~~~~~~~~~~~~~~~~~~ ~~~~~~~~~~~~~~~~~~
We already went through parts of the above in the :ref:`tutorial-create-base-env` tutorial to learn We already went through parts of the above in the :ref:`tutorial-create-base-env` tutorial to learn
about how to specify the scene, observations, actions and randomizations. Thus, in this tutorial, we about how to specify the scene, observations, actions and events. Thus, in this tutorial, we
will focus only on the RL components of the environment. will focus only on the RL components of the environment.
In Orbit, we provide various implementations of different terms in the :mod:`envs.mdp` module. We will use In Orbit, we provide various implementations of different terms in the :mod:`envs.mdp` module. We will use
......
[package] [package]
# Note: Semantic Versioning is used: https://semver.org/ # Note: Semantic Versioning is used: https://semver.org/
version = "0.14.1" version = "0.15.0"
# Description # Description
title = "ORBIT framework for Robot Learning" title = "ORBIT framework for Robot Learning"
......
Changelog Changelog
--------- ---------
0.15.0 (2024-03-17)
~~~~~~~~~~~~~~~~~~~
Deprecated
^^^^^^^^^^
* Renamed :class:`omni.isaac.orbit.managers.RandomizationManager` to :class:`omni.isaac.orbit.managers.EventManager`
class for clarification as the manager takes care of events such as reset in addition to pure randomizations.
* Renamed :class:`omni.isaac.orbit.managers.RandomizationTermCfg` to :class:`omni.isaac.orbit.managers.EventTermCfg`
for consistency with the class name change.
0.14.1 (2024-03-16) 0.14.1 (2024-03-16)
~~~~~~~~~~~~~~~~~~~ ~~~~~~~~~~~~~~~~~~~
......
...@@ -156,11 +156,11 @@ class Articulation(RigidObject): ...@@ -156,11 +156,11 @@ class Articulation(RigidObject):
However, this led to confusion with the link ordering as they were not ordered in the same way as the However, this led to confusion with the link ordering as they were not ordered in the same way as the
articulation view. articulation view.
Therefore, this attribute will be removed in v0.3.0. Please use the :attr:`root_physx_view` attribute Therefore, this attribute will be removed in v0.4.0. Please use the :attr:`root_physx_view` attribute
instead. instead.
""" """
dep_msg = "The attribute 'body_physx_view' will be removed in v0.3.0. Please use 'root_physx_view' instead." dep_msg = "The attribute 'body_physx_view' will be removed in v0.4.0. Please use 'root_physx_view' instead."
warnings.warn(dep_msg, DeprecationWarning) warnings.warn(dep_msg, DeprecationWarning)
carb.log_error(dep_msg) carb.log_error(dep_msg)
return self._body_physx_view return self._body_physx_view
......
...@@ -97,10 +97,10 @@ class RigidObject(AssetBase): ...@@ -97,10 +97,10 @@ class RigidObject(AssetBase):
.. deprecated:: v0.3.0 .. deprecated:: v0.3.0
The attribute 'body_physx_view' will be removed in v0.3.0. Please use :attr:`root_physx_view` instead. The attribute 'body_physx_view' will be removed in v0.4.0. Please use :attr:`root_physx_view` instead.
""" """
dep_msg = "The attribute 'body_physx_view' will be removed in v0.3.0. Please use 'root_physx_view' instead." dep_msg = "The attribute 'body_physx_view' will be removed in v0.4.0. Please use 'root_physx_view' instead."
warnings.warn(dep_msg, DeprecationWarning) warnings.warn(dep_msg, DeprecationWarning)
carb.log_error(dep_msg) carb.log_error(dep_msg)
return self.root_physx_view return self.root_physx_view
......
...@@ -12,7 +12,7 @@ from typing import Any, Dict ...@@ -12,7 +12,7 @@ from typing import Any, Dict
import omni.isaac.core.utils.torch as torch_utils import omni.isaac.core.utils.torch as torch_utils
from omni.isaac.orbit.managers import ActionManager, ObservationManager, RandomizationManager from omni.isaac.orbit.managers import ActionManager, EventManager, ObservationManager
from omni.isaac.orbit.scene import InteractiveScene from omni.isaac.orbit.scene import InteractiveScene
from omni.isaac.orbit.sim import SimulationContext from omni.isaac.orbit.sim import SimulationContext
from omni.isaac.orbit.utils.timer import Timer from omni.isaac.orbit.utils.timer import Timer
...@@ -64,10 +64,10 @@ class BaseEnv: ...@@ -64,10 +64,10 @@ class BaseEnv:
raw actions at different levels of abstraction. For example, in case of a robotic arm, the raw actions raw actions at different levels of abstraction. For example, in case of a robotic arm, the raw actions
can be joint torques, joint positions, or end-effector poses. Similarly for a mobile base, it can be can be joint torques, joint positions, or end-effector poses. Similarly for a mobile base, it can be
the joint torques, or the desired velocity of the floating base. the joint torques, or the desired velocity of the floating base.
* **Randomization Manager**: The randomization manager that randomizes different elements in the scene. * **Event Manager**: The event manager orchestrates operations triggered based on simulation events.
This includes resetting the scene to a default state or randomize the scene at different intervals This includes resetting the scene to a default state, applying random pushes to the robot at different intervals
of time. The randomization manager can be configured to randomize different elements of the scene of time, or randomizing properties such as mass and friction coefficients. This is useful for training
such as the masses of objects, friction coefficients, or apply random pushes to the robot. and evaluating the robot in a variety of scenarios.
The environment provides a unified interface for interacting with the simulation. However, it does not The environment provides a unified interface for interacting with the simulation. However, it does not
include task-specific quantities such as the reward function, or the termination conditions. These include task-specific quantities such as the reward function, or the termination conditions. These
...@@ -190,7 +190,7 @@ class BaseEnv: ...@@ -190,7 +190,7 @@ class BaseEnv:
"""Load the managers for the environment. """Load the managers for the environment.
This function is responsible for creating the various managers (action, observation, This function is responsible for creating the various managers (action, observation,
randomization, etc.) for the environment. Since the managers require access to physics handles, events, etc.) for the environment. Since the managers require access to physics handles,
they can only be created after the simulator is reset (i.e. played for the first time). they can only be created after the simulator is reset (i.e. played for the first time).
.. note:: .. note::
...@@ -209,9 +209,9 @@ class BaseEnv: ...@@ -209,9 +209,9 @@ class BaseEnv:
# -- observation manager # -- observation manager
self.observation_manager = ObservationManager(self.cfg.observations, self) self.observation_manager = ObservationManager(self.cfg.observations, self)
print("[INFO] Observation Manager:", self.observation_manager) print("[INFO] Observation Manager:", self.observation_manager)
# -- randomization manager # -- event manager
self.randomization_manager = RandomizationManager(self.cfg.randomization, self) self.event_manager = EventManager(self.cfg.events, self)
print("[INFO] Randomization Manager: ", self.randomization_manager) print("[INFO] Event Manager: ", self.event_manager)
""" """
Operations - MDP. Operations - MDP.
...@@ -270,9 +270,9 @@ class BaseEnv: ...@@ -270,9 +270,9 @@ class BaseEnv:
if self.sim.has_gui(): if self.sim.has_gui():
self.sim.render() self.sim.render()
# post-step: step interval randomization # post-step: step interval event
if "interval" in self.randomization_manager.available_modes: if "interval" in self.event_manager.available_modes:
self.randomization_manager.randomize(mode="interval", dt=self.step_dt) self.event_manager.apply(mode="interval", dt=self.step_dt)
# return observations and extras # return observations and extras
return self.observation_manager.compute(), self.extras return self.observation_manager.compute(), self.extras
...@@ -303,7 +303,7 @@ class BaseEnv: ...@@ -303,7 +303,7 @@ class BaseEnv:
# destructor is order-sensitive # destructor is order-sensitive
del self.action_manager del self.action_manager
del self.observation_manager del self.observation_manager
del self.randomization_manager del self.event_manager
del self.scene del self.scene
del self.viewport_camera_controller del self.viewport_camera_controller
# clear callbacks and instance # clear callbacks and instance
...@@ -327,9 +327,9 @@ class BaseEnv: ...@@ -327,9 +327,9 @@ class BaseEnv:
""" """
# reset the internal buffers of the scene elements # reset the internal buffers of the scene elements
self.scene.reset(env_ids) self.scene.reset(env_ids)
# randomize the MDP for environments that need a reset # apply events such as randomizations for environments that need a reset
if "reset" in self.randomization_manager.available_modes: if "reset" in self.event_manager.available_modes:
self.randomization_manager.randomize(env_ids=env_ids, mode="reset") self.event_manager.apply(env_ids=env_ids, mode="reset")
# iterate over all managers and reset them # iterate over all managers and reset them
# this returns a dictionary of information which is stored in the extras # this returns a dictionary of information which is stored in the extras
...@@ -341,6 +341,6 @@ class BaseEnv: ...@@ -341,6 +341,6 @@ class BaseEnv:
# -- action manager # -- action manager
info = self.action_manager.reset(env_ids) info = self.action_manager.reset(env_ids)
self.extras["log"].update(info) self.extras["log"].update(info)
# -- randomization manager # -- event manager
info = self.randomization_manager.reset(env_ids) info = self.event_manager.reset(env_ids)
self.extras["log"].update(info) self.extras["log"].update(info)
...@@ -11,11 +11,12 @@ configuring the environment instances, viewer settings, and simulation parameter ...@@ -11,11 +11,12 @@ configuring the environment instances, viewer settings, and simulation parameter
from __future__ import annotations from __future__ import annotations
import warnings
from dataclasses import MISSING from dataclasses import MISSING
from typing import Literal from typing import Literal
import omni.isaac.orbit.envs.mdp as mdp import omni.isaac.orbit.envs.mdp as mdp
from omni.isaac.orbit.managers import RandomizationTermCfg as RandTerm from omni.isaac.orbit.managers import EventTermCfg as EventTerm
from omni.isaac.orbit.scene import InteractiveSceneCfg from omni.isaac.orbit.scene import InteractiveSceneCfg
from omni.isaac.orbit.sim import SimulationCfg from omni.isaac.orbit.sim import SimulationCfg
from omni.isaac.orbit.utils import configclass from omni.isaac.orbit.utils import configclass
...@@ -67,14 +68,14 @@ class ViewerCfg: ...@@ -67,14 +68,14 @@ class ViewerCfg:
@configclass @configclass
class DefaultRandomizationManagerCfg: class DefaultEventManagerCfg:
"""Configuration of the default randomization manager. """Configuration of the default event manager.
This manager is used to reset the scene to a default state. The default state is specified This manager is used to reset the scene to a default state. The default state is specified
by the scene configuration. by the scene configuration.
""" """
reset_scene_to_default = RandTerm(func=mdp.reset_scene_to_default, mode="reset") reset_scene_to_default = EventTerm(func=mdp.reset_scene_to_default, mode="reset")
@configclass @configclass
...@@ -86,6 +87,7 @@ class BaseEnvCfg: ...@@ -86,6 +87,7 @@ class BaseEnvCfg:
"""Viewer configuration. Default is ViewerCfg().""" """Viewer configuration. Default is ViewerCfg()."""
sim: SimulationCfg = SimulationCfg() sim: SimulationCfg = SimulationCfg()
"""Physics simulation configuration. Default is SimulationCfg().""" """Physics simulation configuration. Default is SimulationCfg()."""
# ui settings # ui settings
ui_window_class_type: type | None = BaseEnvWindow ui_window_class_type: type | None = BaseEnvWindow
"""The class type of the UI window. Default is None. """The class type of the UI window. Default is None.
...@@ -100,15 +102,51 @@ class BaseEnvCfg: ...@@ -100,15 +102,51 @@ class BaseEnvCfg:
# general settings # general settings
decimation: int = MISSING decimation: int = MISSING
"""Number of control action updates @ sim dt per policy dt.""" """Number of control action updates @ sim dt per policy dt.
For instance, if the simulation dt is 0.01s and the policy dt is 0.1s, then the decimation is 10.
This means that the control action is updated every 10 simulation steps.
"""
# environment settings # environment settings
scene: InteractiveSceneCfg = MISSING scene: InteractiveSceneCfg = MISSING
"""Scene settings""" """Scene settings.
Please refer to the :class:`omni.isaac.orbit.scene.InteractiveSceneCfg` class for more details.
"""
observations: object = MISSING observations: object = MISSING
"""Observation space settings.""" """Observation space settings.
Please refer to the :class:`omni.isaac.orbit.managers.ObservationManager` class for more details.
"""
actions: object = MISSING actions: object = MISSING
"""Action space settings.""" """Action space settings.
randomization: object = DefaultRandomizationManagerCfg()
"""Randomization settings. Default is the default randomization manager, which resets Please refer to the :class:`omni.isaac.orbit.managers.ActionManager` class for more details.
the scene to its default state.""" """
events: object = DefaultEventManagerCfg()
"""Event settings. Defaults to the basic configuration that resets the scene to its default state.
Please refer to the :class:`omni.isaac.orbit.managers.EventManager` class for more details.
"""
randomization: object | None = None
"""Randomization settings. Default is None.
.. deprecated:: 0.3.0
This attribute is deprecated and will be removed in v0.4.0. Please use the :attr:`events`
attribute to configure the randomization settings.
"""
def __post_init__(self):
if self.randomization is not None:
warnings.warn(
"The 'randomization' attribute is deprecated and will be removed in a future release. "
"Please use the 'events' attribute to configure the randomization settings.",
DeprecationWarning,
)
self.events = self.randomization
...@@ -7,7 +7,7 @@ ...@@ -7,7 +7,7 @@
The functions can be provided to different managers that are responsible for the The functions can be provided to different managers that are responsible for the
different aspects of the MDP. These include the observation, reward, termination, different aspects of the MDP. These include the observation, reward, termination,
actions, randomization and curriculum managers. actions, events and curriculum managers.
The terms are defined under the ``envs`` module because they are used to define The terms are defined under the ``envs`` module because they are used to define
the environment. However, they are not part of the environment directly, but the environment. However, they are not part of the environment directly, but
...@@ -18,7 +18,7 @@ are used to define the environment through their managers. ...@@ -18,7 +18,7 @@ are used to define the environment through their managers.
from .actions import * # noqa: F401, F403 from .actions import * # noqa: F401, F403
from .commands import * # noqa: F401, F403 from .commands import * # noqa: F401, F403
from .curriculums import * # noqa: F401, F403 from .curriculums import * # noqa: F401, F403
from .events import * # noqa: F401, F403
from .observations import * # noqa: F401, F403 from .observations import * # noqa: F401, F403
from .randomizations import * # noqa: F401, F403
from .rewards import * # noqa: F401, F403 from .rewards import * # noqa: F401, F403
from .terminations import * # noqa: F401, F403 from .terminations import * # noqa: F401, F403
...@@ -3,13 +3,13 @@ ...@@ -3,13 +3,13 @@
# #
# SPDX-License-Identifier: BSD-3-Clause # SPDX-License-Identifier: BSD-3-Clause
"""Common functions that can be used to enable different randomizations. """Common functions that can be used to enable different events.
Randomization includes anything related to altering the simulation state. This includes changing the physics Events include anything related to altering the simulation state. This includes changing the physics
materials, applying external forces, and resetting the state of the asset. materials, applying external forces, and resetting the state of the asset.
The functions can be passed to the :class:`omni.isaac.orbit.managers.RandomizationTermCfg` object to enable The functions can be passed to the :class:`omni.isaac.orbit.managers.EventTermCfg` object to enable
the randomization introduced by the function. the event introduced by the function.
""" """
from __future__ import annotations from __future__ import annotations
...@@ -20,7 +20,7 @@ from typing import TYPE_CHECKING ...@@ -20,7 +20,7 @@ from typing import TYPE_CHECKING
from omni.isaac.orbit.assets import Articulation, RigidObject from omni.isaac.orbit.assets import Articulation, RigidObject
from omni.isaac.orbit.managers import SceneEntityCfg from omni.isaac.orbit.managers import SceneEntityCfg
from omni.isaac.orbit.managers.manager_base import ManagerTermBase from omni.isaac.orbit.managers.manager_base import ManagerTermBase
from omni.isaac.orbit.managers.manager_term_cfg import RandomizationTermCfg from omni.isaac.orbit.managers.manager_term_cfg import EventTermCfg
from omni.isaac.orbit.terrains import TerrainImporter from omni.isaac.orbit.terrains import TerrainImporter
from omni.isaac.orbit.utils.math import quat_from_euler_xyz, random_orientation, sample_uniform from omni.isaac.orbit.utils.math import quat_from_euler_xyz, random_orientation, sample_uniform
...@@ -333,7 +333,7 @@ def reset_robot_root_from_terrain( ...@@ -333,7 +333,7 @@ def reset_robot_root_from_terrain(
valid_poses: torch.Tensor = terrain.flat_patches.get("init_pos") valid_poses: torch.Tensor = terrain.flat_patches.get("init_pos")
if valid_poses is None: if valid_poses is None:
raise ValueError( raise ValueError(
"The randomization term 'reset_robot_root_from_terrain' requires valid flat patches under 'init_pos'." "The event term 'reset_robot_root_from_terrain' requires valid flat patches under 'init_pos'."
f" Found: {list(terrain.flat_patches.keys())}" f" Found: {list(terrain.flat_patches.keys())}"
) )
...@@ -441,7 +441,7 @@ class reset_joints_within_range(ManagerTermBase): ...@@ -441,7 +441,7 @@ class reset_joints_within_range(ManagerTermBase):
instead. instead.
""" """
def __init__(self, cfg: RandomizationTermCfg, env: BaseEnv): def __init__(self, cfg: EventTermCfg, env: BaseEnv):
# initialize the base class # initialize the base class
super().__init__(cfg, env) super().__init__(cfg, env)
......
...@@ -94,9 +94,9 @@ class RLTaskEnv(BaseEnv, gym.Env): ...@@ -94,9 +94,9 @@ class RLTaskEnv(BaseEnv, gym.Env):
# setup the action and observation spaces for Gym # setup the action and observation spaces for Gym
self._configure_gym_env_spaces() self._configure_gym_env_spaces()
# perform randomization at the start of the simulation # perform events at the start of the simulation
if "startup" in self.randomization_manager.available_modes: if "startup" in self.event_manager.available_modes:
self.randomization_manager.randomize(mode="startup") self.event_manager.apply(mode="startup")
# print the environment information # print the environment information
print("[INFO]: Completed setting up the environment...") print("[INFO]: Completed setting up the environment...")
...@@ -193,9 +193,9 @@ class RLTaskEnv(BaseEnv, gym.Env): ...@@ -193,9 +193,9 @@ class RLTaskEnv(BaseEnv, gym.Env):
self._reset_idx(reset_env_ids) self._reset_idx(reset_env_ids)
# -- update command # -- update command
self.command_manager.compute(dt=self.step_dt) self.command_manager.compute(dt=self.step_dt)
# -- step interval randomization # -- step interval events
if "interval" in self.randomization_manager.available_modes: if "interval" in self.event_manager.available_modes:
self.randomization_manager.randomize(mode="interval", dt=self.step_dt) self.event_manager.apply(mode="interval", dt=self.step_dt)
# -- compute observations # -- compute observations
# note: done after reset to get the correct observations for reset envs # note: done after reset to get the correct observations for reset envs
self.obs_buf = self.observation_manager.compute() self.obs_buf = self.observation_manager.compute()
...@@ -310,9 +310,9 @@ class RLTaskEnv(BaseEnv, gym.Env): ...@@ -310,9 +310,9 @@ class RLTaskEnv(BaseEnv, gym.Env):
self.curriculum_manager.compute(env_ids=env_ids) self.curriculum_manager.compute(env_ids=env_ids)
# reset the internal buffers of the scene elements # reset the internal buffers of the scene elements
self.scene.reset(env_ids) self.scene.reset(env_ids)
# randomize the MDP for environments that need a reset # apply events such as randomizations for environments that need a reset
if "reset" in self.randomization_manager.available_modes: if "reset" in self.event_manager.available_modes:
self.randomization_manager.randomize(env_ids=env_ids, mode="reset") self.event_manager.apply(env_ids=env_ids, mode="reset")
# iterate over all managers and reset them # iterate over all managers and reset them
# this returns a dictionary of information which is stored in the extras # this returns a dictionary of information which is stored in the extras
...@@ -333,8 +333,8 @@ class RLTaskEnv(BaseEnv, gym.Env): ...@@ -333,8 +333,8 @@ class RLTaskEnv(BaseEnv, gym.Env):
# -- command manager # -- command manager
info = self.command_manager.reset(env_ids) info = self.command_manager.reset(env_ids)
self.extras["log"].update(info) self.extras["log"].update(info)
# -- randomization manager # -- event manager
info = self.randomization_manager.reset(env_ids) info = self.event_manager.reset(env_ids)
self.extras["log"].update(info) self.extras["log"].update(info)
# -- termination manager # -- termination manager
info = self.termination_manager.reset(env_ids) info = self.termination_manager.reset(env_ids)
......
...@@ -44,14 +44,39 @@ class RLTaskEnvCfg(BaseEnvCfg): ...@@ -44,14 +44,39 @@ class RLTaskEnvCfg(BaseEnvCfg):
""" """
episode_length_s: float = MISSING episode_length_s: float = MISSING
"""Duration of an episode (in seconds).""" """Duration of an episode (in seconds).
Based on the decimation rate and physics time step, the episode length is calculated as:
.. code-block:: python
episode_length_steps = ceil(episode_length_s / (decimation_rate * physics_time_step))
For example, if the decimation rate is 10, the physics time step is 0.01, and the episode length is 10 seconds,
then the episode length in steps is 100.
"""
# environment settings # environment settings
rewards: object = MISSING rewards: object = MISSING
"""Reward settings.""" """Reward settings.
Please refer to the :class:`omni.isaac.orbit.managers.RewardManager` class for more details.
"""
terminations: object = MISSING terminations: object = MISSING
"""Termination settings.""" """Termination settings.
Please refer to the :class:`omni.isaac.orbit.managers.TerminationManager` class for more details.
"""
curriculum: object = MISSING curriculum: object = MISSING
"""Curriculum settings.""" """Curriculum settings.
Please refer to the :class:`omni.isaac.orbit.managers.CurriculumManager` class for more details.
"""
commands: object = MISSING commands: object = MISSING
"""Command settings.""" """Command settings.
Please refer to the :class:`omni.isaac.orbit.managers.CommandManager` class for more details.
"""
...@@ -5,19 +5,21 @@ ...@@ -5,19 +5,21 @@
"""Sub-module for environment managers. """Sub-module for environment managers.
The managers are used to handle various aspects of the environment such as randomization, curriculum, and The managers are used to handle various aspects of the environment such as randomization events, curriculum,
observations. Each manager implements a specific functionality for the environment. The managers are and observations. Each manager implements a specific functionality for the environment. The managers are
designed to be modular and can be easily extended to support new functionality. designed to be modular and can be easily extended to support new functionality.
""" """
from .action_manager import ActionManager, ActionTerm from .action_manager import ActionManager, ActionTerm
from .command_manager import CommandManager, CommandTerm from .command_manager import CommandManager, CommandTerm
from .curriculum_manager import CurriculumManager from .curriculum_manager import CurriculumManager
from .event_manager import EventManager, RandomizationManager
from .manager_base import ManagerBase, ManagerTermBase from .manager_base import ManagerBase, ManagerTermBase
from .manager_term_cfg import ( from .manager_term_cfg import (
ActionTermCfg, ActionTermCfg,
CommandTermCfg, CommandTermCfg,
CurriculumTermCfg, CurriculumTermCfg,
EventTermCfg,
ManagerTermBaseCfg, ManagerTermBaseCfg,
ObservationGroupCfg, ObservationGroupCfg,
ObservationTermCfg, ObservationTermCfg,
...@@ -26,7 +28,6 @@ from .manager_term_cfg import ( ...@@ -26,7 +28,6 @@ from .manager_term_cfg import (
TerminationTermCfg, TerminationTermCfg,
) )
from .observation_manager import ObservationManager from .observation_manager import ObservationManager
from .randomization_manager import RandomizationManager
from .reward_manager import RewardManager from .reward_manager import RewardManager
from .scene_entity_cfg import SceneEntityCfg from .scene_entity_cfg import SceneEntityCfg
from .termination_manager import TerminationManager from .termination_manager import TerminationManager
...@@ -8,6 +8,7 @@ ...@@ -8,6 +8,7 @@
from __future__ import annotations from __future__ import annotations
import torch import torch
import warnings
from collections.abc import Callable from collections.abc import Callable
from dataclasses import MISSING from dataclasses import MISSING
from typing import TYPE_CHECKING, Any from typing import TYPE_CHECKING, Any
...@@ -162,13 +163,13 @@ class ObservationGroupCfg: ...@@ -162,13 +163,13 @@ class ObservationGroupCfg:
## ##
# Randomization manager # Event manager
## ##
@configclass @configclass
class RandomizationTermCfg(ManagerTermBaseCfg): class EventTermCfg(ManagerTermBaseCfg):
"""Configuration for a randomization term.""" """Configuration for a event term."""
func: Callable[..., None] = MISSING func: Callable[..., None] = MISSING
"""The name of the function to be called. """The name of the function to be called.
...@@ -178,7 +179,7 @@ class RandomizationTermCfg(ManagerTermBaseCfg): ...@@ -178,7 +179,7 @@ class RandomizationTermCfg(ManagerTermBaseCfg):
""" """
mode: str = MISSING mode: str = MISSING
"""The mode in which the randomization term is applied. """The mode in which the event term is applied.
Note: Note:
The mode name ``"interval"`` is a special mode that is handled by the The mode name ``"interval"`` is a special mode that is handled by the
...@@ -189,14 +190,33 @@ class RandomizationTermCfg(ManagerTermBaseCfg): ...@@ -189,14 +190,33 @@ class RandomizationTermCfg(ManagerTermBaseCfg):
"""The range of time in seconds at which the term is applied. """The range of time in seconds at which the term is applied.
Based on this, the interval is sampled uniformly between the specified Based on this, the interval is sampled uniformly between the specified
interval range for each environment instance and the term is applied for range for each environment instance. The term is applied on the environment
the environment instances if the current time hits the interval time. instances where the current time hits the interval time.
Note: Note:
This is only used if the mode is ``"interval"``. This is only used if the mode is ``"interval"``.
""" """
@configclass
class RandomizationTermCfg(EventTermCfg):
"""Configuration for a randomization term.
.. deprecated:: v0.3.0
This class is deprecated and will be removed in v0.4.0. Please use :class:`EventTermCfg` instead.
"""
def __init__(self, *args, **kwargs):
super().__init__(*args, **kwargs)
# Deprecation warning.
warnings.warn(
"The RandomizationTermCfg has been renamed to EventTermCfg and will be removed in v0.4.0. Please use"
" EventTermCfg instead.",
DeprecationWarning,
)
## ##
# Reward manager. # Reward manager.
## ##
......
...@@ -335,7 +335,7 @@ class Camera(SensorBase): ...@@ -335,7 +335,7 @@ class Camera(SensorBase):
if env_ids is None: if env_ids is None:
env_ids = self._ALL_INDICES env_ids = self._ALL_INDICES
# reset the data # reset the data
# note: this recomputation is useful if one performs randomization on the camera poses. # note: this recomputation is useful if one performs events such as randomizations on the camera poses.
self._update_poses(env_ids) self._update_poses(env_ids)
self._update_intrinsic_matrices(env_ids) self._update_intrinsic_matrices(env_ids)
# Reset the frame count # Reset the frame count
......
...@@ -147,7 +147,7 @@ class RayCasterCamera(RayCaster): ...@@ -147,7 +147,7 @@ class RayCasterCamera(RayCaster):
if env_ids is None: if env_ids is None:
env_ids = slice(None) env_ids = slice(None)
# reset the data # reset the data
# note: this recomputation is useful if one performs randomization on the camera poses. # note: this recomputation is useful if one performs events such as randomizations on the camera poses.
pos_w, quat_w = self._compute_camera_world_poses(env_ids) pos_w, quat_w = self._compute_camera_world_poses(env_ids)
self._data.pos_w[env_ids] = pos_w self._data.pos_w[env_ids] = pos_w
self._data.quat_w_world[env_ids] = quat_w self._data.quat_w_world[env_ids] = quat_w
......
...@@ -5,7 +5,7 @@ ...@@ -5,7 +5,7 @@
""" """
This script demonstrates the environment concept that combines a scene with an action, This script demonstrates the environment concept that combines a scene with an action,
observation and randomization manager for a quadruped robot. observation and event manager for a quadruped robot.
A locomotion policy is loaded and used to control the robot. This shows how to use the A locomotion policy is loaded and used to control the robot. This shows how to use the
environment with a policy. environment with a policy.
...@@ -42,9 +42,9 @@ import omni.isaac.orbit.envs.mdp as mdp ...@@ -42,9 +42,9 @@ import omni.isaac.orbit.envs.mdp as mdp
import omni.isaac.orbit.sim as sim_utils import omni.isaac.orbit.sim as sim_utils
from omni.isaac.orbit.assets import ArticulationCfg, AssetBaseCfg from omni.isaac.orbit.assets import ArticulationCfg, AssetBaseCfg
from omni.isaac.orbit.envs import BaseEnv, BaseEnvCfg from omni.isaac.orbit.envs import BaseEnv, BaseEnvCfg
from omni.isaac.orbit.managers import EventTermCfg as EventTerm
from omni.isaac.orbit.managers import ObservationGroupCfg as ObsGroup from omni.isaac.orbit.managers import ObservationGroupCfg as ObsGroup
from omni.isaac.orbit.managers import ObservationTermCfg as ObsTerm from omni.isaac.orbit.managers import ObservationTermCfg as ObsTerm
from omni.isaac.orbit.managers import RandomizationTermCfg as RandTerm
from omni.isaac.orbit.managers import SceneEntityCfg from omni.isaac.orbit.managers import SceneEntityCfg
from omni.isaac.orbit.scene import InteractiveSceneCfg from omni.isaac.orbit.scene import InteractiveSceneCfg
from omni.isaac.orbit.sensors import RayCasterCfg, patterns from omni.isaac.orbit.sensors import RayCasterCfg, patterns
...@@ -155,10 +155,10 @@ class ObservationsCfg: ...@@ -155,10 +155,10 @@ class ObservationsCfg:
@configclass @configclass
class RandomizationCfg: class EventCfg:
"""Configuration for randomization.""" """Configuration for events."""
reset_base = RandTerm( reset_base = EventTerm(
func=mdp.reset_root_state_uniform, func=mdp.reset_root_state_uniform,
mode="reset", mode="reset",
params={ params={
...@@ -189,7 +189,7 @@ class QuadrupedEnvCfg(BaseEnvCfg): ...@@ -189,7 +189,7 @@ class QuadrupedEnvCfg(BaseEnvCfg):
# Basic settings # Basic settings
observations: ObservationsCfg = ObservationsCfg() observations: ObservationsCfg = ObservationsCfg()
actions: ActionsCfg = ActionsCfg() actions: ActionsCfg = ActionsCfg()
randomization: RandomizationCfg = RandomizationCfg() events: EventCfg = EventCfg()
def __post_init__(self): def __post_init__(self):
"""Post initialization.""" """Post initialization."""
......
...@@ -5,7 +5,7 @@ ...@@ -5,7 +5,7 @@
""" """
This script demonstrates the base environment concept that combines a scene with an action, This script demonstrates the base environment concept that combines a scene with an action,
observation and randomization manager for a floating cube. observation and event manager for a floating cube.
""" """
from __future__ import annotations from __future__ import annotations
...@@ -38,9 +38,9 @@ import omni.isaac.orbit.envs.mdp as mdp ...@@ -38,9 +38,9 @@ import omni.isaac.orbit.envs.mdp as mdp
import omni.isaac.orbit.sim as sim_utils import omni.isaac.orbit.sim as sim_utils
from omni.isaac.orbit.assets import AssetBaseCfg, RigidObject, RigidObjectCfg from omni.isaac.orbit.assets import AssetBaseCfg, RigidObject, RigidObjectCfg
from omni.isaac.orbit.envs import BaseEnv, BaseEnvCfg from omni.isaac.orbit.envs import BaseEnv, BaseEnvCfg
from omni.isaac.orbit.managers import EventTermCfg as EventTerm
from omni.isaac.orbit.managers import ObservationGroupCfg as ObsGroup from omni.isaac.orbit.managers import ObservationGroupCfg as ObsGroup
from omni.isaac.orbit.managers import ObservationTermCfg as ObsTerm from omni.isaac.orbit.managers import ObservationTermCfg as ObsTerm
from omni.isaac.orbit.managers import RandomizationTermCfg as RandTerm
from omni.isaac.orbit.managers import SceneEntityCfg from omni.isaac.orbit.managers import SceneEntityCfg
from omni.isaac.orbit.managers.action_manager import ActionTerm, ActionTermCfg from omni.isaac.orbit.managers.action_manager import ActionTerm, ActionTermCfg
from omni.isaac.orbit.scene import InteractiveSceneCfg from omni.isaac.orbit.scene import InteractiveSceneCfg
...@@ -188,10 +188,10 @@ class ObservationsCfg: ...@@ -188,10 +188,10 @@ class ObservationsCfg:
@configclass @configclass
class RandomizationCfg: class EventCfg:
"""Configuration for randomization.""" """Configuration for events."""
reset_base = RandTerm( reset_base = EventTerm(
func=mdp.reset_root_state_uniform, func=mdp.reset_root_state_uniform,
mode="reset", mode="reset",
params={ params={
...@@ -220,7 +220,7 @@ class CubeEnvCfg(BaseEnvCfg): ...@@ -220,7 +220,7 @@ class CubeEnvCfg(BaseEnvCfg):
# Basic settings # Basic settings
observations: ObservationsCfg = ObservationsCfg() observations: ObservationsCfg = ObservationsCfg()
actions: ActionsCfg = ActionsCfg() actions: ActionsCfg = ActionsCfg()
randomization: RandomizationCfg = RandomizationCfg() events: EventCfg = EventCfg()
def __post_init__(self): def __post_init__(self):
"""Post initialization.""" """Post initialization."""
......
...@@ -9,9 +9,9 @@ import omni.isaac.orbit.sim as sim_utils ...@@ -9,9 +9,9 @@ import omni.isaac.orbit.sim as sim_utils
from omni.isaac.orbit.actuators import ImplicitActuatorCfg from omni.isaac.orbit.actuators import ImplicitActuatorCfg
from omni.isaac.orbit.assets import ArticulationCfg, AssetBaseCfg from omni.isaac.orbit.assets import ArticulationCfg, AssetBaseCfg
from omni.isaac.orbit.envs import RLTaskEnvCfg from omni.isaac.orbit.envs import RLTaskEnvCfg
from omni.isaac.orbit.managers import EventTermCfg as EventTerm
from omni.isaac.orbit.managers import ObservationGroupCfg as ObsGroup from omni.isaac.orbit.managers import ObservationGroupCfg as ObsGroup
from omni.isaac.orbit.managers import ObservationTermCfg as ObsTerm from omni.isaac.orbit.managers import ObservationTermCfg as ObsTerm
from omni.isaac.orbit.managers import RandomizationTermCfg as RandTerm
from omni.isaac.orbit.managers import RewardTermCfg as RewTerm from omni.isaac.orbit.managers import RewardTermCfg as RewTerm
from omni.isaac.orbit.managers import SceneEntityCfg from omni.isaac.orbit.managers import SceneEntityCfg
from omni.isaac.orbit.managers import TerminationTermCfg as DoneTerm from omni.isaac.orbit.managers import TerminationTermCfg as DoneTerm
...@@ -142,16 +142,16 @@ class ObservationsCfg: ...@@ -142,16 +142,16 @@ class ObservationsCfg:
@configclass @configclass
class RandomizationCfg: class EventCfg:
"""Configuration for randomization.""" """Configuration for events."""
reset_base = RandTerm( reset_base = EventTerm(
func=mdp.reset_root_state_uniform, func=mdp.reset_root_state_uniform,
mode="reset", mode="reset",
params={"pose_range": {}, "velocity_range": {}}, params={"pose_range": {}, "velocity_range": {}},
) )
reset_robot_joints = RandTerm( reset_robot_joints = EventTerm(
func=mdp.reset_joints_by_offset, func=mdp.reset_joints_by_offset,
mode="reset", mode="reset",
params={ params={
...@@ -216,7 +216,7 @@ class AntEnvCfg(RLTaskEnvCfg): ...@@ -216,7 +216,7 @@ class AntEnvCfg(RLTaskEnvCfg):
# MDP settings # MDP settings
rewards: RewardsCfg = RewardsCfg() rewards: RewardsCfg = RewardsCfg()
terminations: TerminationsCfg = TerminationsCfg() terminations: TerminationsCfg = TerminationsCfg()
randomization: RandomizationCfg = RandomizationCfg() events: EventCfg = EventCfg()
curriculum: CurriculumCfg = CurriculumCfg() curriculum: CurriculumCfg = CurriculumCfg()
def __post_init__(self): def __post_init__(self):
......
...@@ -8,9 +8,9 @@ import math ...@@ -8,9 +8,9 @@ import math
import omni.isaac.orbit.sim as sim_utils import omni.isaac.orbit.sim as sim_utils
from omni.isaac.orbit.assets import ArticulationCfg, AssetBaseCfg from omni.isaac.orbit.assets import ArticulationCfg, AssetBaseCfg
from omni.isaac.orbit.envs import RLTaskEnvCfg from omni.isaac.orbit.envs import RLTaskEnvCfg
from omni.isaac.orbit.managers import EventTermCfg as EventTerm
from omni.isaac.orbit.managers import ObservationGroupCfg as ObsGroup from omni.isaac.orbit.managers import ObservationGroupCfg as ObsGroup
from omni.isaac.orbit.managers import ObservationTermCfg as ObsTerm from omni.isaac.orbit.managers import ObservationTermCfg as ObsTerm
from omni.isaac.orbit.managers import RandomizationTermCfg as RandTerm
from omni.isaac.orbit.managers import RewardTermCfg as RewTerm from omni.isaac.orbit.managers import RewardTermCfg as RewTerm
from omni.isaac.orbit.managers import SceneEntityCfg from omni.isaac.orbit.managers import SceneEntityCfg
from omni.isaac.orbit.managers import TerminationTermCfg as DoneTerm from omni.isaac.orbit.managers import TerminationTermCfg as DoneTerm
...@@ -96,11 +96,11 @@ class ObservationsCfg: ...@@ -96,11 +96,11 @@ class ObservationsCfg:
@configclass @configclass
class RandomizationCfg: class EventCfg:
"""Configuration for randomization.""" """Configuration for events."""
# reset # reset
reset_cart_position = RandTerm( reset_cart_position = EventTerm(
func=mdp.reset_joints_by_offset, func=mdp.reset_joints_by_offset,
mode="reset", mode="reset",
params={ params={
...@@ -110,7 +110,7 @@ class RandomizationCfg: ...@@ -110,7 +110,7 @@ class RandomizationCfg:
}, },
) )
reset_pole_position = RandTerm( reset_pole_position = EventTerm(
func=mdp.reset_joints_by_offset, func=mdp.reset_joints_by_offset,
mode="reset", mode="reset",
params={ params={
...@@ -183,7 +183,7 @@ class CartpoleEnvCfg(RLTaskEnvCfg): ...@@ -183,7 +183,7 @@ class CartpoleEnvCfg(RLTaskEnvCfg):
# Basic settings # Basic settings
observations: ObservationsCfg = ObservationsCfg() observations: ObservationsCfg = ObservationsCfg()
actions: ActionsCfg = ActionsCfg() actions: ActionsCfg = ActionsCfg()
randomization: RandomizationCfg = RandomizationCfg() events: EventCfg = EventCfg()
# MDP settings # MDP settings
curriculum: CurriculumCfg = CurriculumCfg() curriculum: CurriculumCfg = CurriculumCfg()
rewards: RewardsCfg = RewardsCfg() rewards: RewardsCfg = RewardsCfg()
......
...@@ -9,9 +9,9 @@ import omni.isaac.orbit.sim as sim_utils ...@@ -9,9 +9,9 @@ import omni.isaac.orbit.sim as sim_utils
from omni.isaac.orbit.actuators import ImplicitActuatorCfg from omni.isaac.orbit.actuators import ImplicitActuatorCfg
from omni.isaac.orbit.assets import ArticulationCfg, AssetBaseCfg from omni.isaac.orbit.assets import ArticulationCfg, AssetBaseCfg
from omni.isaac.orbit.envs import RLTaskEnvCfg from omni.isaac.orbit.envs import RLTaskEnvCfg
from omni.isaac.orbit.managers import EventTermCfg as EventTerm
from omni.isaac.orbit.managers import ObservationGroupCfg as ObsGroup from omni.isaac.orbit.managers import ObservationGroupCfg as ObsGroup
from omni.isaac.orbit.managers import ObservationTermCfg as ObsTerm from omni.isaac.orbit.managers import ObservationTermCfg as ObsTerm
from omni.isaac.orbit.managers import RandomizationTermCfg as RandTerm
from omni.isaac.orbit.managers import RewardTermCfg as RewTerm from omni.isaac.orbit.managers import RewardTermCfg as RewTerm
from omni.isaac.orbit.managers import SceneEntityCfg from omni.isaac.orbit.managers import SceneEntityCfg
from omni.isaac.orbit.managers import TerminationTermCfg as DoneTerm from omni.isaac.orbit.managers import TerminationTermCfg as DoneTerm
...@@ -166,16 +166,16 @@ class ObservationsCfg: ...@@ -166,16 +166,16 @@ class ObservationsCfg:
@configclass @configclass
class RandomizationCfg: class EventCfg:
"""Configuration for randomization.""" """Configuration for events."""
reset_base = RandTerm( reset_base = EventTerm(
func=mdp.reset_root_state_uniform, func=mdp.reset_root_state_uniform,
mode="reset", mode="reset",
params={"pose_range": {}, "velocity_range": {}}, params={"pose_range": {}, "velocity_range": {}},
) )
reset_robot_joints = RandTerm( reset_robot_joints = EventTerm(
func=mdp.reset_joints_by_offset, func=mdp.reset_joints_by_offset,
mode="reset", mode="reset",
params={ params={
...@@ -271,7 +271,7 @@ class HumanoidEnvCfg(RLTaskEnvCfg): ...@@ -271,7 +271,7 @@ class HumanoidEnvCfg(RLTaskEnvCfg):
# MDP settings # MDP settings
rewards: RewardsCfg = RewardsCfg() rewards: RewardsCfg = RewardsCfg()
terminations: TerminationsCfg = TerminationsCfg() terminations: TerminationsCfg = TerminationsCfg()
randomization: RandomizationCfg = RandomizationCfg() events: EventCfg = EventCfg()
curriculum: CurriculumCfg = CurriculumCfg() curriculum: CurriculumCfg = CurriculumCfg()
def __post_init__(self): def __post_init__(self):
......
...@@ -38,6 +38,6 @@ class AnymalBFlatEnvCfg_PLAY(AnymalBFlatEnvCfg): ...@@ -38,6 +38,6 @@ class AnymalBFlatEnvCfg_PLAY(AnymalBFlatEnvCfg):
self.scene.env_spacing = 2.5 self.scene.env_spacing = 2.5
# disable randomization for play # disable randomization for play
self.observations.policy.enable_corruption = False self.observations.policy.enable_corruption = False
# remove random pushing # remove random pushing event
self.randomization.base_external_force_torque = None self.events.base_external_force_torque = None
self.randomization.push_robot = None self.events.push_robot = None
...@@ -41,6 +41,6 @@ class AnymalBRoughEnvCfg_PLAY(AnymalBRoughEnvCfg): ...@@ -41,6 +41,6 @@ class AnymalBRoughEnvCfg_PLAY(AnymalBRoughEnvCfg):
# disable randomization for play # disable randomization for play
self.observations.policy.enable_corruption = False self.observations.policy.enable_corruption = False
# remove random pushing # remove random pushing event
self.randomization.base_external_force_torque = None self.events.base_external_force_torque = None
self.randomization.push_robot = None self.events.push_robot = None
...@@ -38,6 +38,6 @@ class AnymalCFlatEnvCfg_PLAY(AnymalCFlatEnvCfg): ...@@ -38,6 +38,6 @@ class AnymalCFlatEnvCfg_PLAY(AnymalCFlatEnvCfg):
self.scene.env_spacing = 2.5 self.scene.env_spacing = 2.5
# disable randomization for play # disable randomization for play
self.observations.policy.enable_corruption = False self.observations.policy.enable_corruption = False
# remove random pushing # remove random pushing event
self.randomization.base_external_force_torque = None self.events.base_external_force_torque = None
self.randomization.push_robot = None self.events.push_robot = None
...@@ -41,6 +41,6 @@ class AnymalCRoughEnvCfg_PLAY(AnymalCRoughEnvCfg): ...@@ -41,6 +41,6 @@ class AnymalCRoughEnvCfg_PLAY(AnymalCRoughEnvCfg):
# disable randomization for play # disable randomization for play
self.observations.policy.enable_corruption = False self.observations.policy.enable_corruption = False
# remove random pushing # remove random pushing event
self.randomization.base_external_force_torque = None self.events.base_external_force_torque = None
self.randomization.push_robot = None self.events.push_robot = None
...@@ -38,6 +38,6 @@ class AnymalDFlatEnvCfg_PLAY(AnymalDFlatEnvCfg): ...@@ -38,6 +38,6 @@ class AnymalDFlatEnvCfg_PLAY(AnymalDFlatEnvCfg):
self.scene.env_spacing = 2.5 self.scene.env_spacing = 2.5
# disable randomization for play # disable randomization for play
self.observations.policy.enable_corruption = False self.observations.policy.enable_corruption = False
# remove random pushing # remove random pushing event
self.randomization.base_external_force_torque = None self.events.base_external_force_torque = None
self.randomization.push_robot = None self.events.push_robot = None
...@@ -41,6 +41,6 @@ class AnymalDRoughEnvCfg_PLAY(AnymalDRoughEnvCfg): ...@@ -41,6 +41,6 @@ class AnymalDRoughEnvCfg_PLAY(AnymalDRoughEnvCfg):
# disable randomization for play # disable randomization for play
self.observations.policy.enable_corruption = False self.observations.policy.enable_corruption = False
# remove random pushing # remove random pushing event
self.randomization.base_external_force_torque = None self.events.base_external_force_torque = None
self.randomization.push_robot = None self.events.push_robot = None
...@@ -61,12 +61,12 @@ class CassieRoughEnvCfg(LocomotionVelocityRoughEnvCfg): ...@@ -61,12 +61,12 @@ class CassieRoughEnvCfg(LocomotionVelocityRoughEnvCfg):
# actions # actions
self.actions.joint_pos.scale = 0.5 self.actions.joint_pos.scale = 0.5
# randomizations # events
self.randomization.push_robot = None self.events.push_robot = None
self.randomization.add_base_mass = None self.events.add_base_mass = None
self.randomization.reset_robot_joints.params["position_range"] = (1.0, 1.0) self.events.reset_robot_joints.params["position_range"] = (1.0, 1.0)
self.randomization.base_external_force_torque.params["asset_cfg"].body_names = [".*pelvis"] self.events.base_external_force_torque.params["asset_cfg"].body_names = [".*pelvis"]
self.randomization.reset_base.params = { self.events.reset_base.params = {
"pose_range": {"x": (-0.5, 0.5), "y": (-0.5, 0.5), "yaw": (-3.14, 3.14)}, "pose_range": {"x": (-0.5, 0.5), "y": (-0.5, 0.5), "yaw": (-3.14, 3.14)},
"velocity_range": { "velocity_range": {
"x": (0.0, 0.0), "x": (0.0, 0.0),
......
...@@ -38,6 +38,6 @@ class UnitreeA1FlatEnvCfg_PLAY(UnitreeA1FlatEnvCfg): ...@@ -38,6 +38,6 @@ class UnitreeA1FlatEnvCfg_PLAY(UnitreeA1FlatEnvCfg):
self.scene.env_spacing = 2.5 self.scene.env_spacing = 2.5
# disable randomization for play # disable randomization for play
self.observations.policy.enable_corruption = False self.observations.policy.enable_corruption = False
# remove random pushing # remove random pushing event
self.randomization.base_external_force_torque = None self.events.base_external_force_torque = None
self.randomization.push_robot = None self.events.push_robot = None
...@@ -29,13 +29,13 @@ class UnitreeA1RoughEnvCfg(LocomotionVelocityRoughEnvCfg): ...@@ -29,13 +29,13 @@ class UnitreeA1RoughEnvCfg(LocomotionVelocityRoughEnvCfg):
# reduce action scale # reduce action scale
self.actions.joint_pos.scale = 0.25 self.actions.joint_pos.scale = 0.25
# randomization # event
self.randomization.push_robot = None self.events.push_robot = None
self.randomization.add_base_mass.params["mass_range"] = (-1.0, 3.0) self.events.add_base_mass.params["mass_range"] = (-1.0, 3.0)
self.randomization.add_base_mass.params["asset_cfg"].body_names = "trunk" self.events.add_base_mass.params["asset_cfg"].body_names = "trunk"
self.randomization.base_external_force_torque.params["asset_cfg"].body_names = "trunk" self.events.base_external_force_torque.params["asset_cfg"].body_names = "trunk"
self.randomization.reset_robot_joints.params["position_range"] = (1.0, 1.0) self.events.reset_robot_joints.params["position_range"] = (1.0, 1.0)
self.randomization.reset_base.params = { self.events.reset_base.params = {
"pose_range": {"x": (-0.5, 0.5), "y": (-0.5, 0.5), "yaw": (-3.14, 3.14)}, "pose_range": {"x": (-0.5, 0.5), "y": (-0.5, 0.5), "yaw": (-3.14, 3.14)},
"velocity_range": { "velocity_range": {
"x": (0.0, 0.0), "x": (0.0, 0.0),
...@@ -79,6 +79,6 @@ class UnitreeA1RoughEnvCfg_PLAY(UnitreeA1RoughEnvCfg): ...@@ -79,6 +79,6 @@ class UnitreeA1RoughEnvCfg_PLAY(UnitreeA1RoughEnvCfg):
# disable randomization for play # disable randomization for play
self.observations.policy.enable_corruption = False self.observations.policy.enable_corruption = False
# remove random pushing # remove random pushing event
self.randomization.base_external_force_torque = None self.events.base_external_force_torque = None
self.randomization.push_robot = None self.events.push_robot = None
...@@ -38,6 +38,6 @@ class UnitreeGo1FlatEnvCfg_PLAY(UnitreeGo1FlatEnvCfg): ...@@ -38,6 +38,6 @@ class UnitreeGo1FlatEnvCfg_PLAY(UnitreeGo1FlatEnvCfg):
self.scene.env_spacing = 2.5 self.scene.env_spacing = 2.5
# disable randomization for play # disable randomization for play
self.observations.policy.enable_corruption = False self.observations.policy.enable_corruption = False
# remove random pushing # remove random pushing event
self.randomization.base_external_force_torque = None self.events.base_external_force_torque = None
self.randomization.push_robot = None self.events.push_robot = None
...@@ -29,13 +29,13 @@ class UnitreeGo1RoughEnvCfg(LocomotionVelocityRoughEnvCfg): ...@@ -29,13 +29,13 @@ class UnitreeGo1RoughEnvCfg(LocomotionVelocityRoughEnvCfg):
# reduce action scale # reduce action scale
self.actions.joint_pos.scale = 0.25 self.actions.joint_pos.scale = 0.25
# randomization # event
self.randomization.push_robot = None self.events.push_robot = None
self.randomization.add_base_mass.params["mass_range"] = (-1.0, 3.0) self.events.add_base_mass.params["mass_range"] = (-1.0, 3.0)
self.randomization.add_base_mass.params["asset_cfg"].body_names = "trunk" self.events.add_base_mass.params["asset_cfg"].body_names = "trunk"
self.randomization.base_external_force_torque.params["asset_cfg"].body_names = "trunk" self.events.base_external_force_torque.params["asset_cfg"].body_names = "trunk"
self.randomization.reset_robot_joints.params["position_range"] = (1.0, 1.0) self.events.reset_robot_joints.params["position_range"] = (1.0, 1.0)
self.randomization.reset_base.params = { self.events.reset_base.params = {
"pose_range": {"x": (-0.5, 0.5), "y": (-0.5, 0.5), "yaw": (-3.14, 3.14)}, "pose_range": {"x": (-0.5, 0.5), "y": (-0.5, 0.5), "yaw": (-3.14, 3.14)},
"velocity_range": { "velocity_range": {
"x": (0.0, 0.0), "x": (0.0, 0.0),
...@@ -79,6 +79,6 @@ class UnitreeGo1RoughEnvCfg_PLAY(UnitreeGo1RoughEnvCfg): ...@@ -79,6 +79,6 @@ class UnitreeGo1RoughEnvCfg_PLAY(UnitreeGo1RoughEnvCfg):
# disable randomization for play # disable randomization for play
self.observations.policy.enable_corruption = False self.observations.policy.enable_corruption = False
# remove random pushing # remove random pushing event
self.randomization.base_external_force_torque = None self.events.base_external_force_torque = None
self.randomization.push_robot = None self.events.push_robot = None
...@@ -38,6 +38,6 @@ class UnitreeGo2FlatEnvCfg_PLAY(UnitreeGo2FlatEnvCfg): ...@@ -38,6 +38,6 @@ class UnitreeGo2FlatEnvCfg_PLAY(UnitreeGo2FlatEnvCfg):
self.scene.env_spacing = 2.5 self.scene.env_spacing = 2.5
# disable randomization for play # disable randomization for play
self.observations.policy.enable_corruption = False self.observations.policy.enable_corruption = False
# remove random pushing # remove random pushing event
self.randomization.base_external_force_torque = None self.events.base_external_force_torque = None
self.randomization.push_robot = None self.events.push_robot = None
...@@ -29,13 +29,13 @@ class UnitreeGo2RoughEnvCfg(LocomotionVelocityRoughEnvCfg): ...@@ -29,13 +29,13 @@ class UnitreeGo2RoughEnvCfg(LocomotionVelocityRoughEnvCfg):
# reduce action scale # reduce action scale
self.actions.joint_pos.scale = 0.25 self.actions.joint_pos.scale = 0.25
# randomization # event
self.randomization.push_robot = None self.events.push_robot = None
self.randomization.add_base_mass.params["mass_range"] = (-1.0, 3.0) self.events.add_base_mass.params["mass_range"] = (-1.0, 3.0)
self.randomization.add_base_mass.params["asset_cfg"].body_names = "base" self.events.add_base_mass.params["asset_cfg"].body_names = "base"
self.randomization.base_external_force_torque.params["asset_cfg"].body_names = "base" self.events.base_external_force_torque.params["asset_cfg"].body_names = "base"
self.randomization.reset_robot_joints.params["position_range"] = (1.0, 1.0) self.events.reset_robot_joints.params["position_range"] = (1.0, 1.0)
self.randomization.reset_base.params = { self.events.reset_base.params = {
"pose_range": {"x": (-0.5, 0.5), "y": (-0.5, 0.5), "yaw": (-3.14, 3.14)}, "pose_range": {"x": (-0.5, 0.5), "y": (-0.5, 0.5), "yaw": (-3.14, 3.14)},
"velocity_range": { "velocity_range": {
"x": (0.0, 0.0), "x": (0.0, 0.0),
...@@ -79,6 +79,6 @@ class UnitreeGo2RoughEnvCfg_PLAY(UnitreeGo2RoughEnvCfg): ...@@ -79,6 +79,6 @@ class UnitreeGo2RoughEnvCfg_PLAY(UnitreeGo2RoughEnvCfg):
# disable randomization for play # disable randomization for play
self.observations.policy.enable_corruption = False self.observations.policy.enable_corruption = False
# remove random pushing # remove random pushing event
self.randomization.base_external_force_torque = None self.events.base_external_force_torque = None
self.randomization.push_robot = None self.events.push_robot = None
...@@ -12,9 +12,9 @@ import omni.isaac.orbit.sim as sim_utils ...@@ -12,9 +12,9 @@ import omni.isaac.orbit.sim as sim_utils
from omni.isaac.orbit.assets import ArticulationCfg, AssetBaseCfg from omni.isaac.orbit.assets import ArticulationCfg, AssetBaseCfg
from omni.isaac.orbit.envs import RLTaskEnvCfg from omni.isaac.orbit.envs import RLTaskEnvCfg
from omni.isaac.orbit.managers import CurriculumTermCfg as CurrTerm from omni.isaac.orbit.managers import CurriculumTermCfg as CurrTerm
from omni.isaac.orbit.managers import EventTermCfg as EventTerm
from omni.isaac.orbit.managers import ObservationGroupCfg as ObsGroup from omni.isaac.orbit.managers import ObservationGroupCfg as ObsGroup
from omni.isaac.orbit.managers import ObservationTermCfg as ObsTerm from omni.isaac.orbit.managers import ObservationTermCfg as ObsTerm
from omni.isaac.orbit.managers import RandomizationTermCfg as RandTerm
from omni.isaac.orbit.managers import RewardTermCfg as RewTerm from omni.isaac.orbit.managers import RewardTermCfg as RewTerm
from omni.isaac.orbit.managers import SceneEntityCfg from omni.isaac.orbit.managers import SceneEntityCfg
from omni.isaac.orbit.managers import TerminationTermCfg as DoneTerm from omni.isaac.orbit.managers import TerminationTermCfg as DoneTerm
...@@ -148,11 +148,11 @@ class ObservationsCfg: ...@@ -148,11 +148,11 @@ class ObservationsCfg:
@configclass @configclass
class RandomizationCfg: class EventCfg:
"""Configuration for randomization.""" """Configuration for events."""
# startup # startup
physics_material = RandTerm( physics_material = EventTerm(
func=mdp.randomize_rigid_body_material, func=mdp.randomize_rigid_body_material,
mode="startup", mode="startup",
params={ params={
...@@ -164,14 +164,14 @@ class RandomizationCfg: ...@@ -164,14 +164,14 @@ class RandomizationCfg:
}, },
) )
add_base_mass = RandTerm( add_base_mass = EventTerm(
func=mdp.add_body_mass, func=mdp.add_body_mass,
mode="startup", mode="startup",
params={"asset_cfg": SceneEntityCfg("robot", body_names="base"), "mass_range": (-5.0, 5.0)}, params={"asset_cfg": SceneEntityCfg("robot", body_names="base"), "mass_range": (-5.0, 5.0)},
) )
# reset # reset
base_external_force_torque = RandTerm( base_external_force_torque = EventTerm(
func=mdp.apply_external_force_torque, func=mdp.apply_external_force_torque,
mode="reset", mode="reset",
params={ params={
...@@ -181,7 +181,7 @@ class RandomizationCfg: ...@@ -181,7 +181,7 @@ class RandomizationCfg:
}, },
) )
reset_base = RandTerm( reset_base = EventTerm(
func=mdp.reset_root_state_uniform, func=mdp.reset_root_state_uniform,
mode="reset", mode="reset",
params={ params={
...@@ -197,7 +197,7 @@ class RandomizationCfg: ...@@ -197,7 +197,7 @@ class RandomizationCfg:
}, },
) )
reset_robot_joints = RandTerm( reset_robot_joints = EventTerm(
func=mdp.reset_joints_by_scale, func=mdp.reset_joints_by_scale,
mode="reset", mode="reset",
params={ params={
...@@ -207,7 +207,7 @@ class RandomizationCfg: ...@@ -207,7 +207,7 @@ class RandomizationCfg:
) )
# interval # interval
push_robot = RandTerm( push_robot = EventTerm(
func=mdp.push_by_setting_velocity, func=mdp.push_by_setting_velocity,
mode="interval", mode="interval",
interval_range_s=(10.0, 15.0), interval_range_s=(10.0, 15.0),
...@@ -287,7 +287,7 @@ class LocomotionVelocityRoughEnvCfg(RLTaskEnvCfg): ...@@ -287,7 +287,7 @@ class LocomotionVelocityRoughEnvCfg(RLTaskEnvCfg):
# MDP settings # MDP settings
rewards: RewardsCfg = RewardsCfg() rewards: RewardsCfg = RewardsCfg()
terminations: TerminationsCfg = TerminationsCfg() terminations: TerminationsCfg = TerminationsCfg()
randomization: RandomizationCfg = RandomizationCfg() events: EventCfg = EventCfg()
curriculum: CurriculumCfg = CurriculumCfg() curriculum: CurriculumCfg = CurriculumCfg()
def __post_init__(self): def __post_init__(self):
......
...@@ -15,9 +15,9 @@ import omni.isaac.orbit.sim as sim_utils ...@@ -15,9 +15,9 @@ import omni.isaac.orbit.sim as sim_utils
from omni.isaac.orbit.actuators.actuator_cfg import ImplicitActuatorCfg from omni.isaac.orbit.actuators.actuator_cfg import ImplicitActuatorCfg
from omni.isaac.orbit.assets import ArticulationCfg, AssetBaseCfg from omni.isaac.orbit.assets import ArticulationCfg, AssetBaseCfg
from omni.isaac.orbit.envs import RLTaskEnvCfg from omni.isaac.orbit.envs import RLTaskEnvCfg
from omni.isaac.orbit.managers import EventTermCfg as EventTerm
from omni.isaac.orbit.managers import ObservationGroupCfg as ObsGroup from omni.isaac.orbit.managers import ObservationGroupCfg as ObsGroup
from omni.isaac.orbit.managers import ObservationTermCfg as ObsTerm from omni.isaac.orbit.managers import ObservationTermCfg as ObsTerm
from omni.isaac.orbit.managers import RandomizationTermCfg as RandTerm
from omni.isaac.orbit.managers import RewardTermCfg as RewTerm from omni.isaac.orbit.managers import RewardTermCfg as RewTerm
from omni.isaac.orbit.managers import SceneEntityCfg from omni.isaac.orbit.managers import SceneEntityCfg
from omni.isaac.orbit.managers import TerminationTermCfg as DoneTerm from omni.isaac.orbit.managers import TerminationTermCfg as DoneTerm
...@@ -174,10 +174,10 @@ class ObservationsCfg: ...@@ -174,10 +174,10 @@ class ObservationsCfg:
@configclass @configclass
class RandomizationCfg: class EventCfg:
"""Configuration for randomization.""" """Configuration for events."""
robot_physics_material = RandTerm( robot_physics_material = EventTerm(
func=mdp.randomize_rigid_body_material, func=mdp.randomize_rigid_body_material,
mode="startup", mode="startup",
params={ params={
...@@ -189,7 +189,7 @@ class RandomizationCfg: ...@@ -189,7 +189,7 @@ class RandomizationCfg:
}, },
) )
cabinet_physics_material = RandTerm( cabinet_physics_material = EventTerm(
func=mdp.randomize_rigid_body_material, func=mdp.randomize_rigid_body_material,
mode="startup", mode="startup",
params={ params={
...@@ -201,9 +201,9 @@ class RandomizationCfg: ...@@ -201,9 +201,9 @@ class RandomizationCfg:
}, },
) )
reset_all = RandTerm(func=mdp.reset_scene_to_default, mode="reset") reset_all = EventTerm(func=mdp.reset_scene_to_default, mode="reset")
reset_robot_joints = RandTerm( reset_robot_joints = EventTerm(
func=mdp.reset_joints_by_offset, func=mdp.reset_joints_by_offset,
mode="reset", mode="reset",
params={ params={
...@@ -276,7 +276,7 @@ class CabinetEnvCfg(RLTaskEnvCfg): ...@@ -276,7 +276,7 @@ class CabinetEnvCfg(RLTaskEnvCfg):
# MDP settings # MDP settings
rewards: RewardsCfg = RewardsCfg() rewards: RewardsCfg = RewardsCfg()
terminations: TerminationsCfg = TerminationsCfg() terminations: TerminationsCfg = TerminationsCfg()
randomization: RandomizationCfg = RandomizationCfg() events: EventCfg = EventCfg()
def __post_init__(self): def __post_init__(self):
"""Post initialization.""" """Post initialization."""
......
...@@ -12,9 +12,9 @@ import omni.isaac.orbit.sim as sim_utils ...@@ -12,9 +12,9 @@ import omni.isaac.orbit.sim as sim_utils
from omni.isaac.orbit.assets import ArticulationCfg, AssetBaseCfg, RigidObjectCfg from omni.isaac.orbit.assets import ArticulationCfg, AssetBaseCfg, RigidObjectCfg
from omni.isaac.orbit.envs import RLTaskEnvCfg from omni.isaac.orbit.envs import RLTaskEnvCfg
from omni.isaac.orbit.managers import CurriculumTermCfg as CurrTerm from omni.isaac.orbit.managers import CurriculumTermCfg as CurrTerm
from omni.isaac.orbit.managers import EventTermCfg as EventTerm
from omni.isaac.orbit.managers import ObservationGroupCfg as ObsGroup from omni.isaac.orbit.managers import ObservationGroupCfg as ObsGroup
from omni.isaac.orbit.managers import ObservationTermCfg as ObsTerm from omni.isaac.orbit.managers import ObservationTermCfg as ObsTerm
from omni.isaac.orbit.managers import RandomizationTermCfg as RandTerm
from omni.isaac.orbit.managers import RewardTermCfg as RewTerm from omni.isaac.orbit.managers import RewardTermCfg as RewTerm
from omni.isaac.orbit.managers import SceneEntityCfg from omni.isaac.orbit.managers import SceneEntityCfg
from omni.isaac.orbit.managers import TerminationTermCfg as DoneTerm from omni.isaac.orbit.managers import TerminationTermCfg as DoneTerm
...@@ -118,12 +118,12 @@ class ObservationsCfg: ...@@ -118,12 +118,12 @@ class ObservationsCfg:
@configclass @configclass
class RandomizationCfg: class EventCfg:
"""Configuration for randomization.""" """Configuration for events."""
reset_all = RandTerm(func=mdp.reset_scene_to_default, mode="reset") reset_all = EventTerm(func=mdp.reset_scene_to_default, mode="reset")
reset_object_position = RandTerm( reset_object_position = EventTerm(
func=mdp.reset_root_state_uniform, func=mdp.reset_root_state_uniform,
mode="reset", mode="reset",
params={ params={
...@@ -206,7 +206,7 @@ class LiftEnvCfg(RLTaskEnvCfg): ...@@ -206,7 +206,7 @@ class LiftEnvCfg(RLTaskEnvCfg):
# MDP settings # MDP settings
rewards: RewardsCfg = RewardsCfg() rewards: RewardsCfg = RewardsCfg()
terminations: TerminationsCfg = TerminationsCfg() terminations: TerminationsCfg = TerminationsCfg()
randomization: RandomizationCfg = RandomizationCfg() events: EventCfg = EventCfg()
curriculum: CurriculumCfg = CurriculumCfg() curriculum: CurriculumCfg = CurriculumCfg()
def __post_init__(self): def __post_init__(self):
......
...@@ -31,8 +31,8 @@ class UR10ReachEnvCfg(ReachEnvCfg): ...@@ -31,8 +31,8 @@ class UR10ReachEnvCfg(ReachEnvCfg):
# switch robot to ur10 # switch robot to ur10
self.scene.robot = UR10_CFG.replace(prim_path="{ENV_REGEX_NS}/Robot") self.scene.robot = UR10_CFG.replace(prim_path="{ENV_REGEX_NS}/Robot")
# override randomization # override events
self.randomization.reset_robot_joints.params["position_range"] = (0.75, 1.25) self.events.reset_robot_joints.params["position_range"] = (0.75, 1.25)
# override rewards # override rewards
self.rewards.end_effector_position_tracking.params["asset_cfg"].body_names = ["ee_link"] self.rewards.end_effector_position_tracking.params["asset_cfg"].body_names = ["ee_link"]
self.rewards.end_effector_orientation_tracking.params["asset_cfg"].body_names = ["ee_link"] self.rewards.end_effector_orientation_tracking.params["asset_cfg"].body_names = ["ee_link"]
......
...@@ -12,9 +12,9 @@ from omni.isaac.orbit.assets import ArticulationCfg, AssetBaseCfg ...@@ -12,9 +12,9 @@ from omni.isaac.orbit.assets import ArticulationCfg, AssetBaseCfg
from omni.isaac.orbit.envs import RLTaskEnvCfg from omni.isaac.orbit.envs import RLTaskEnvCfg
from omni.isaac.orbit.managers import ActionTermCfg as ActionTerm from omni.isaac.orbit.managers import ActionTermCfg as ActionTerm
from omni.isaac.orbit.managers import CurriculumTermCfg as CurrTerm from omni.isaac.orbit.managers import CurriculumTermCfg as CurrTerm
from omni.isaac.orbit.managers import EventTermCfg as EventTerm
from omni.isaac.orbit.managers import ObservationGroupCfg as ObsGroup from omni.isaac.orbit.managers import ObservationGroupCfg as ObsGroup
from omni.isaac.orbit.managers import ObservationTermCfg as ObsTerm from omni.isaac.orbit.managers import ObservationTermCfg as ObsTerm
from omni.isaac.orbit.managers import RandomizationTermCfg as RandTerm
from omni.isaac.orbit.managers import RewardTermCfg as RewTerm from omni.isaac.orbit.managers import RewardTermCfg as RewTerm
from omni.isaac.orbit.managers import SceneEntityCfg from omni.isaac.orbit.managers import SceneEntityCfg
from omni.isaac.orbit.managers import TerminationTermCfg as DoneTerm from omni.isaac.orbit.managers import TerminationTermCfg as DoneTerm
...@@ -115,10 +115,10 @@ class ObservationsCfg: ...@@ -115,10 +115,10 @@ class ObservationsCfg:
@configclass @configclass
class RandomizationCfg: class EventCfg:
"""Configuration for randomization.""" """Configuration for events."""
reset_robot_joints = RandTerm( reset_robot_joints = EventTerm(
func=mdp.reset_joints_by_scale, func=mdp.reset_joints_by_scale,
mode="reset", mode="reset",
params={ params={
...@@ -187,7 +187,7 @@ class ReachEnvCfg(RLTaskEnvCfg): ...@@ -187,7 +187,7 @@ class ReachEnvCfg(RLTaskEnvCfg):
# MDP settings # MDP settings
rewards: RewardsCfg = RewardsCfg() rewards: RewardsCfg = RewardsCfg()
terminations: TerminationsCfg = TerminationsCfg() terminations: TerminationsCfg = TerminationsCfg()
randomization: RandomizationCfg = RandomizationCfg() events: EventCfg = EventCfg()
curriculum: CurriculumCfg = CurriculumCfg() curriculum: CurriculumCfg = CurriculumCfg()
def __post_init__(self): def __post_init__(self):
......
...@@ -5,7 +5,7 @@ ...@@ -5,7 +5,7 @@
""" """
This script demonstrates how to create a simple environment with a cartpole. It combines the concepts of This script demonstrates how to create a simple environment with a cartpole. It combines the concepts of
scene, action, observation and randomization managers to create an environment. scene, action, observation and event managers to create an environment.
""" """
from __future__ import annotations from __future__ import annotations
...@@ -37,9 +37,9 @@ import torch ...@@ -37,9 +37,9 @@ import torch
import omni.isaac.orbit.envs.mdp as mdp import omni.isaac.orbit.envs.mdp as mdp
from omni.isaac.orbit.envs import BaseEnv, BaseEnvCfg from omni.isaac.orbit.envs import BaseEnv, BaseEnvCfg
from omni.isaac.orbit.managers import EventTermCfg as EventTerm
from omni.isaac.orbit.managers import ObservationGroupCfg as ObsGroup from omni.isaac.orbit.managers import ObservationGroupCfg as ObsGroup
from omni.isaac.orbit.managers import ObservationTermCfg as ObsTerm from omni.isaac.orbit.managers import ObservationTermCfg as ObsTerm
from omni.isaac.orbit.managers import RandomizationTermCfg as RandTerm
from omni.isaac.orbit.managers import SceneEntityCfg from omni.isaac.orbit.managers import SceneEntityCfg
from omni.isaac.orbit.utils import configclass from omni.isaac.orbit.utils import configclass
...@@ -74,11 +74,11 @@ class ObservationsCfg: ...@@ -74,11 +74,11 @@ class ObservationsCfg:
@configclass @configclass
class RandomizationCfg: class EventCfg:
"""Configuration for randomization.""" """Configuration for events."""
# on startup # on startup
add_pole_mass = RandTerm( add_pole_mass = EventTerm(
func=mdp.add_body_mass, func=mdp.add_body_mass,
mode="startup", mode="startup",
params={ params={
...@@ -88,7 +88,7 @@ class RandomizationCfg: ...@@ -88,7 +88,7 @@ class RandomizationCfg:
) )
# on reset # on reset
reset_cart_position = RandTerm( reset_cart_position = EventTerm(
func=mdp.reset_joints_by_offset, func=mdp.reset_joints_by_offset,
mode="reset", mode="reset",
params={ params={
...@@ -98,7 +98,7 @@ class RandomizationCfg: ...@@ -98,7 +98,7 @@ class RandomizationCfg:
}, },
) )
reset_pole_position = RandTerm( reset_pole_position = EventTerm(
func=mdp.reset_joints_by_offset, func=mdp.reset_joints_by_offset,
mode="reset", mode="reset",
params={ params={
...@@ -118,7 +118,7 @@ class CartpoleEnvCfg(BaseEnvCfg): ...@@ -118,7 +118,7 @@ class CartpoleEnvCfg(BaseEnvCfg):
# Basic settings # Basic settings
observations = ObservationsCfg() observations = ObservationsCfg()
actions = ActionsCfg() actions = ActionsCfg()
randomization = RandomizationCfg() events = EventCfg()
def __post_init__(self): def __post_init__(self):
"""Post initialization.""" """Post initialization."""
......
...@@ -48,9 +48,9 @@ import omni.isaac.orbit.sim as sim_utils ...@@ -48,9 +48,9 @@ import omni.isaac.orbit.sim as sim_utils
from omni.isaac.orbit.assets import AssetBaseCfg, RigidObject, RigidObjectCfg from omni.isaac.orbit.assets import AssetBaseCfg, RigidObject, RigidObjectCfg
from omni.isaac.orbit.envs import BaseEnv, BaseEnvCfg from omni.isaac.orbit.envs import BaseEnv, BaseEnvCfg
from omni.isaac.orbit.managers import ActionTerm, ActionTermCfg from omni.isaac.orbit.managers import ActionTerm, ActionTermCfg
from omni.isaac.orbit.managers import EventTermCfg as EventTerm
from omni.isaac.orbit.managers import ObservationGroupCfg as ObsGroup from omni.isaac.orbit.managers import ObservationGroupCfg as ObsGroup
from omni.isaac.orbit.managers import ObservationTermCfg as ObsTerm from omni.isaac.orbit.managers import ObservationTermCfg as ObsTerm
from omni.isaac.orbit.managers import RandomizationTermCfg as RandTerm
from omni.isaac.orbit.managers import SceneEntityCfg from omni.isaac.orbit.managers import SceneEntityCfg
from omni.isaac.orbit.scene import InteractiveSceneCfg from omni.isaac.orbit.scene import InteractiveSceneCfg
from omni.isaac.orbit.terrains import TerrainImporterCfg from omni.isaac.orbit.terrains import TerrainImporterCfg
...@@ -219,10 +219,10 @@ class ObservationsCfg: ...@@ -219,10 +219,10 @@ class ObservationsCfg:
@configclass @configclass
class RandomizationCfg: class EventCfg:
"""Configuration for randomization.""" """Configuration for events."""
reset_base = RandTerm( reset_base = EventTerm(
func=mdp.reset_root_state_uniform, func=mdp.reset_root_state_uniform,
mode="reset", mode="reset",
params={ params={
...@@ -251,7 +251,7 @@ class CubeEnvCfg(BaseEnvCfg): ...@@ -251,7 +251,7 @@ class CubeEnvCfg(BaseEnvCfg):
# Basic settings # Basic settings
observations: ObservationsCfg = ObservationsCfg() observations: ObservationsCfg = ObservationsCfg()
actions: ActionsCfg = ActionsCfg() actions: ActionsCfg = ActionsCfg()
randomization: RandomizationCfg = RandomizationCfg() events: EventCfg = EventCfg()
def __post_init__(self): def __post_init__(self):
"""Post initialization.""" """Post initialization."""
......
...@@ -48,9 +48,9 @@ import omni.isaac.orbit.envs.mdp as mdp ...@@ -48,9 +48,9 @@ import omni.isaac.orbit.envs.mdp as mdp
import omni.isaac.orbit.sim as sim_utils import omni.isaac.orbit.sim as sim_utils
from omni.isaac.orbit.assets import ArticulationCfg, AssetBaseCfg from omni.isaac.orbit.assets import ArticulationCfg, AssetBaseCfg
from omni.isaac.orbit.envs import BaseEnv, BaseEnvCfg from omni.isaac.orbit.envs import BaseEnv, BaseEnvCfg
from omni.isaac.orbit.managers import EventTermCfg as EventTerm
from omni.isaac.orbit.managers import ObservationGroupCfg as ObsGroup from omni.isaac.orbit.managers import ObservationGroupCfg as ObsGroup
from omni.isaac.orbit.managers import ObservationTermCfg as ObsTerm from omni.isaac.orbit.managers import ObservationTermCfg as ObsTerm
from omni.isaac.orbit.managers import RandomizationTermCfg as RandTerm
from omni.isaac.orbit.managers import SceneEntityCfg from omni.isaac.orbit.managers import SceneEntityCfg
from omni.isaac.orbit.scene import InteractiveSceneCfg from omni.isaac.orbit.scene import InteractiveSceneCfg
from omni.isaac.orbit.sensors import RayCasterCfg, patterns from omni.isaac.orbit.sensors import RayCasterCfg, patterns
...@@ -168,10 +168,10 @@ class ObservationsCfg: ...@@ -168,10 +168,10 @@ class ObservationsCfg:
@configclass @configclass
class RandomizationCfg: class EventCfg:
"""Configuration for randomization.""" """Configuration for events."""
reset_scene = RandTerm(func=mdp.reset_scene_to_default, mode="reset") reset_scene = EventTerm(func=mdp.reset_scene_to_default, mode="reset")
## ##
...@@ -188,7 +188,7 @@ class QuadrupedEnvCfg(BaseEnvCfg): ...@@ -188,7 +188,7 @@ class QuadrupedEnvCfg(BaseEnvCfg):
# Basic settings # Basic settings
observations: ObservationsCfg = ObservationsCfg() observations: ObservationsCfg = ObservationsCfg()
actions: ActionsCfg = ActionsCfg() actions: ActionsCfg = ActionsCfg()
randomization: RandomizationCfg = RandomizationCfg() events: EventCfg = EventCfg()
def __post_init__(self): def __post_init__(self):
"""Post initialization.""" """Post initialization."""
......
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