Unverified Commit bd4cd3b4 authored by David Hoeller's avatar David Hoeller Committed by GitHub

Adds a validity check for configclasses (#1214)

# Description

Added a mechanism to check for the validity of a configclass object.
A configclass object is valid if it contains no MISSING attributes.

## Type of change

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

## 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 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 6bc4d0a0
...@@ -2,12 +2,29 @@ name: Build & deploy docs ...@@ -2,12 +2,29 @@ name: Build & deploy docs
on: on:
push: push:
pull_request:
concurrency:
group: ${{ github.workflow }}-${{ github.ref }}
cancel-in-progress: true
jobs: jobs:
check-secrets:
name: Check secrets
runs-on: ubuntu-latest
outputs:
trigger-deploy: ${{ steps.trigger-deploy.outputs.defined }}
steps:
- id: trigger-deploy
env:
REPO_NAME: ${{ secrets.REPO_NAME }}
BRANCH_REF: ${{ secrets.BRANCH_REF }}
if: "${{ github.repository == env.REPO_NAME && github.ref == env.BRANCH_REF }}"
run: echo "defined=true" >> "$GITHUB_OUTPUT"
build-docs: build-docs:
name: Build Docs name: Build Docs
runs-on: ubuntu-latest runs-on: ubuntu-latest
needs: [check-secrets]
steps: steps:
- name: Checkout code - name: Checkout code
...@@ -24,8 +41,8 @@ jobs: ...@@ -24,8 +41,8 @@ jobs:
run: pip install -r requirements.txt run: pip install -r requirements.txt
- name: Check branch docs building - name: Check branch docs building
if: ${{ github.event_name == 'pull_request' }}
working-directory: ./docs working-directory: ./docs
if: needs.check-secrets.outputs.trigger-deploy != 'true'
run: make current-docs run: make current-docs
- name: Generate multi-version docs - name: Generate multi-version docs
...@@ -40,19 +57,6 @@ jobs: ...@@ -40,19 +57,6 @@ jobs:
name: docs-html name: docs-html
path: ./docs/_build path: ./docs/_build
check-secrets:
name: Check secrets
runs-on: ubuntu-latest
outputs:
trigger-deploy: ${{ steps.trigger-deploy.outputs.defined }}
steps:
- id: trigger-deploy
env:
REPO_NAME: ${{ secrets.REPO_NAME }}
BRANCH_REF: ${{ secrets.BRANCH_REF }}
if: "${{ github.repository == env.REPO_NAME && github.ref == env.BRANCH_REF }}"
run: echo "defined=true" >> "$GITHUB_OUTPUT"
deploy-docs: deploy-docs:
name: Deploy Docs name: Deploy Docs
runs-on: ubuntu-latest runs-on: ubuntu-latest
......
...@@ -262,7 +262,7 @@ html_sidebars = { ...@@ -262,7 +262,7 @@ html_sidebars = {
def skip_member(app, what, name, obj, skip, options): def skip_member(app, what, name, obj, skip, options):
# List the names of the functions you want to skip here # List the names of the functions you want to skip here
exclusions = ["from_dict", "to_dict", "replace", "copy", "__post_init__"] exclusions = ["from_dict", "to_dict", "replace", "copy", "validate", "__post_init__"]
if name in exclusions: if name in exclusions:
return True return True
return None return None
......
...@@ -36,7 +36,7 @@ For this tutorial, we use the cartpole environment defined in ``omni.isaac.lab_t ...@@ -36,7 +36,7 @@ For this tutorial, we use the cartpole environment defined in ``omni.isaac.lab_t
.. literalinclude:: ../../../../source/extensions/omni.isaac.lab_tasks/omni/isaac/lab_tasks/manager_based/classic/cartpole/cartpole_env_cfg.py .. literalinclude:: ../../../../source/extensions/omni.isaac.lab_tasks/omni/isaac/lab_tasks/manager_based/classic/cartpole/cartpole_env_cfg.py
:language: python :language: python
:emphasize-lines: 63-68, 124-149, 152-162, 165-169, 187-192 :emphasize-lines: 117-141, 144-154, 172-174
:linenos: :linenos:
The script for running the environment ``run_cartpole_rl_env.py`` is present in the The script for running the environment ``run_cartpole_rl_env.py`` is present in the
...@@ -117,13 +117,8 @@ For various goal-conditioned tasks, it is useful to specify the goals or command ...@@ -117,13 +117,8 @@ For various goal-conditioned tasks, it is useful to specify the goals or command
handled through the :class:`managers.CommandManager`. The command manager handles resampling and updating the handled through the :class:`managers.CommandManager`. The command manager handles resampling and updating the
commands at each step. It can also be used to provide the commands as an observation to the agent. commands at each step. It can also be used to provide the commands as an observation to the agent.
For this simple task, we do not use any commands. This is specified by using a command term with the For this simple task, we do not use any commands. Hence, we leave this attribute as its default value, which is None.
:class:`envs.mdp.NullCommandCfg` configuration. However, you can see an example of command definitions in the You can see an example of how to define a command manager in the other locomotion or manipulation tasks.
locomotion or manipulation tasks.
.. literalinclude:: ../../../../source/extensions/omni.isaac.lab_tasks/omni/isaac/lab_tasks/manager_based/classic/cartpole/cartpole_env_cfg.py
:language: python
:pyobject: CommandsCfg
Defining curriculum Defining curriculum
------------------- -------------------
...@@ -134,11 +129,6 @@ we provide a :class:`managers.CurriculumManager` class that can be used to defin ...@@ -134,11 +129,6 @@ we provide a :class:`managers.CurriculumManager` class that can be used to defin
In this tutorial we don't implement a curriculum for simplicity, but you can see an example of a In this tutorial we don't implement a curriculum for simplicity, but you can see an example of a
curriculum definition in the other locomotion or manipulation tasks. curriculum definition in the other locomotion or manipulation tasks.
We use a simple pass-through curriculum to define a curriculum manager that does not modify the environment.
.. literalinclude:: ../../../../source/extensions/omni.isaac.lab_tasks/omni/isaac/lab_tasks/manager_based/classic/cartpole/cartpole_env_cfg.py
:language: python
:pyobject: CurriculumCfg
Tying it all together Tying it all together
--------------------- ---------------------
......
[package] [package]
# Note: Semantic Versioning is used: https://semver.org/ # Note: Semantic Versioning is used: https://semver.org/
version = "0.26.0" version = "0.27.0"
# Description # Description
title = "Isaac Lab framework for Robot Learning" title = "Isaac Lab framework for Robot Learning"
......
Changelog Changelog
--------- ---------
0.27.0 (2024-10-14)
~~~~~~~~~~~~~~~~~~~
Added
^^^^^
* Added a method to :class:`~omni.isaac.lab.utils.configclass` to check for attributes with values of
type ``MISSING``. This is useful when the user wants to check if a certain attribute has been set or not.
* Added the configuration validation check inside the constructor of all the core classes
(such as sensor base, asset base, scene and environment base classes).
* Added support for environments without commands by leaving the attribute
:attr:`omni.isaac.lab.envs.ManagerBasedRLEnvCfg.commands` as None. Before, this had to be done using
the class :class:`omni.isaac.lab.command_generators.NullCommandGenerator`.
* Moved the ``meshes`` attribute in the :class:`omni.isaac.lab.sensors.RayCaster` class from class variable to instance variable.
This prevents the meshes to overwrite each other.
0.26.0 (2024-10-16) 0.26.0 (2024-10-16)
~~~~~~~~~~~~~~~~~~~ ~~~~~~~~~~~~~~~~~~~
......
...@@ -59,6 +59,8 @@ class AssetBase(ABC): ...@@ -59,6 +59,8 @@ class AssetBase(ABC):
Raises: Raises:
RuntimeError: If no prims found at input prim path or prim path expression. RuntimeError: If no prims found at input prim path or prim path expression.
""" """
# check that the config is valid
cfg.validate()
# store inputs # store inputs
self.cfg = cfg self.cfg = cfg
# flag for whether the asset is initialized # flag for whether the asset is initialized
......
...@@ -39,8 +39,9 @@ class AssetBaseCfg: ...@@ -39,8 +39,9 @@ class AssetBaseCfg:
Defaults to (1.0, 0.0, 0.0, 0.0). Defaults to (1.0, 0.0, 0.0, 0.0).
""" """
class_type: type[AssetBase] = MISSING class_type: type[AssetBase] = None
"""The associated asset class. """The associated asset class. Defaults to None, which means that the asset will be spawned
but cannot be interacted with via the asset class.
The class should inherit from :class:`omni.isaac.lab.assets.asset_base.AssetBase`. The class should inherit from :class:`omni.isaac.lab.assets.asset_base.AssetBase`.
""" """
......
...@@ -74,6 +74,8 @@ class DirectMARLEnv: ...@@ -74,6 +74,8 @@ class DirectMARLEnv:
RuntimeError: If a simulation context already exists. The environment must always create one RuntimeError: If a simulation context already exists. The environment must always create one
since it configures the simulation context and controls the simulation. since it configures the simulation context and controls the simulation.
""" """
# check that the config is valid
cfg.validate()
# store inputs to class # store inputs to class
self.cfg = cfg self.cfg = cfg
# store the render mode # store the render mode
......
...@@ -79,6 +79,8 @@ class DirectRLEnv(gym.Env): ...@@ -79,6 +79,8 @@ class DirectRLEnv(gym.Env):
RuntimeError: If a simulation context already exists. The environment must always create one RuntimeError: If a simulation context already exists. The environment must always create one
since it configures the simulation context and controls the simulation. since it configures the simulation context and controls the simulation.
""" """
# check that the config is valid
cfg.validate()
# store inputs to class # store inputs to class
self.cfg = cfg self.cfg = cfg
# store the render mode # store the render mode
......
...@@ -98,7 +98,7 @@ class DirectRLEnvCfg: ...@@ -98,7 +98,7 @@ class DirectRLEnvCfg:
Please refer to the :class:`omni.isaac.lab.scene.InteractiveSceneCfg` class for more details. Please refer to the :class:`omni.isaac.lab.scene.InteractiveSceneCfg` class for more details.
""" """
events: object = None events: object | None = None
"""Event settings. Defaults to None, in which case no events are applied through the event manager. """Event settings. Defaults to None, in which case no events are applied through the event manager.
Please refer to the :class:`omni.isaac.lab.managers.EventManager` class for more details. Please refer to the :class:`omni.isaac.lab.managers.EventManager` class for more details.
......
...@@ -69,6 +69,8 @@ class ManagerBasedEnv: ...@@ -69,6 +69,8 @@ class ManagerBasedEnv:
RuntimeError: If a simulation context already exists. The environment must always create one RuntimeError: If a simulation context already exists. The environment must always create one
since it configures the simulation context and controls the simulation. since it configures the simulation context and controls the simulation.
""" """
# check that the config is valid
cfg.validate()
# store inputs to class # store inputs to class
self.cfg = cfg self.cfg = cfg
# initialize internal variables # initialize internal variables
......
...@@ -67,14 +67,14 @@ class ManagerBasedRLEnvCfg(ManagerBasedEnvCfg): ...@@ -67,14 +67,14 @@ class ManagerBasedRLEnvCfg(ManagerBasedEnvCfg):
Please refer to the :class:`omni.isaac.lab.managers.TerminationManager` class for more details. Please refer to the :class:`omni.isaac.lab.managers.TerminationManager` class for more details.
""" """
curriculum: object = MISSING curriculum: object | None = None
"""Curriculum settings. """Curriculum settings. Defaults to None, in which case no curriculum is applied.
Please refer to the :class:`omni.isaac.lab.managers.CurriculumManager` class for more details. Please refer to the :class:`omni.isaac.lab.managers.CurriculumManager` class for more details.
""" """
commands: object = MISSING commands: object | None = None
"""Command settings. """Command settings. Defaults to None, in which case no commands are generated.
Please refer to the :class:`omni.isaac.lab.managers.CommandManager` class for more details. Please refer to the :class:`omni.isaac.lab.managers.CommandManager` class for more details.
""" """
...@@ -183,9 +183,11 @@ class EMAJointPositionToLimitsAction(JointPositionToLimitsAction): ...@@ -183,9 +183,11 @@ class EMAJointPositionToLimitsAction(JointPositionToLimitsAction):
# check if specific environment ids are provided # check if specific environment ids are provided
if env_ids is None: if env_ids is None:
env_ids = slice(None) env_ids = slice(None)
else:
env_ids = env_ids[:, None]
super().reset(env_ids) super().reset(env_ids)
# reset history to current joint positions # reset history to current joint positions
self._prev_applied_actions[env_ids, :] = self._asset.data.joint_pos[env_ids[:, None], self._joint_ids] self._prev_applied_actions[env_ids, :] = self._asset.data.joint_pos[env_ids, self._joint_ids]
def process_actions(self, actions: torch.Tensor): def process_actions(self, actions: torch.Tensor):
# apply affine transformations # apply affine transformations
......
...@@ -37,29 +37,46 @@ class UniformVelocityCommandCfg(CommandTermCfg): ...@@ -37,29 +37,46 @@ class UniformVelocityCommandCfg(CommandTermCfg):
asset_name: str = MISSING asset_name: str = MISSING
"""Name of the asset in the environment for which the commands are generated.""" """Name of the asset in the environment for which the commands are generated."""
heading_command: bool = MISSING
"""Whether to use heading command or angular velocity command. heading_command: bool = False
"""Whether to use heading command or angular velocity command. Defaults to False.
If True, the angular velocity command is computed from the heading error, where the If True, the angular velocity command is computed from the heading error, where the
target heading is sampled uniformly from provided range. Otherwise, the angular velocity target heading is sampled uniformly from provided range. Otherwise, the angular velocity
command is sampled uniformly from provided range. command is sampled uniformly from provided range.
""" """
heading_control_stiffness: float = MISSING
"""Scale factor to convert the heading error to angular velocity command.""" heading_control_stiffness: float = 1.0
rel_standing_envs: float = MISSING """Scale factor to convert the heading error to angular velocity command. Defaults to 1.0."""
"""Probability threshold for environments where the robots that are standing still."""
rel_heading_envs: float = MISSING rel_standing_envs: float = 0.0
"""Probability threshold for environments where the robots follow the heading-based angular velocity command """The sampled probability of environments that should be standing still. Defaults to 0.0."""
(the others follow the sampled angular velocity command)."""
rel_heading_envs: float = 1.0
"""The sampled probability of environments where the robots follow the heading-based angular velocity command
(the others follow the sampled angular velocity command). Defaults to 1.0.
This parameter is only used if :attr:`heading_command` is True.
"""
@configclass @configclass
class Ranges: class Ranges:
"""Uniform distribution ranges for the velocity commands.""" """Uniform distribution ranges for the velocity commands."""
lin_vel_x: tuple[float, float] = MISSING # min max [m/s] lin_vel_x: tuple[float, float] = MISSING
lin_vel_y: tuple[float, float] = MISSING # min max [m/s] """Range for the linear-x velocity command (in m/s)."""
ang_vel_z: tuple[float, float] = MISSING # min max [rad/s]
heading: tuple[float, float] = MISSING # min max [rad] lin_vel_y: tuple[float, float] = MISSING
"""Range for the linear-y velocity command (in m/s)."""
ang_vel_z: tuple[float, float] = MISSING
"""Range for the angular-z velocity command (in rad/s)."""
heading: tuple[float, float] | None = None
"""Range for the heading command (in rad). Defaults to None.
This parameter is only used if :attr:`~UniformVelocityCommandCfg.heading_command` is True.
"""
ranges: Ranges = MISSING ranges: Ranges = MISSING
"""Distribution ranges for the velocity commands.""" """Distribution ranges for the velocity commands."""
...@@ -91,15 +108,17 @@ class NormalVelocityCommandCfg(UniformVelocityCommandCfg): ...@@ -91,15 +108,17 @@ class NormalVelocityCommandCfg(UniformVelocityCommandCfg):
"""Normal distribution ranges for the velocity commands.""" """Normal distribution ranges for the velocity commands."""
mean_vel: tuple[float, float, float] = MISSING mean_vel: tuple[float, float, float] = MISSING
"""Mean velocity for the normal distribution. """Mean velocity for the normal distribution (in m/s).
The tuple contains the mean linear-x, linear-y, and angular-z velocity. The tuple contains the mean linear-x, linear-y, and angular-z velocity.
""" """
std_vel: tuple[float, float, float] = MISSING std_vel: tuple[float, float, float] = MISSING
"""Standard deviation for the normal distribution. """Standard deviation for the normal distribution (in m/s).
The tuple contains the standard deviation linear-x, linear-y, and angular-z velocity. The tuple contains the standard deviation linear-x, linear-y, and angular-z velocity.
""" """
zero_prob: tuple[float, float, float] = MISSING zero_prob: tuple[float, float, float] = MISSING
"""Probability of zero velocity for the normal distribution. """Probability of zero velocity for the normal distribution.
...@@ -118,6 +137,7 @@ class UniformPoseCommandCfg(CommandTermCfg): ...@@ -118,6 +137,7 @@ class UniformPoseCommandCfg(CommandTermCfg):
asset_name: str = MISSING asset_name: str = MISSING
"""Name of the asset in the environment for which the commands are generated.""" """Name of the asset in the environment for which the commands are generated."""
body_name: str = MISSING body_name: str = MISSING
"""Name of the body in the asset for which the commands are generated.""" """Name of the body in the asset for which the commands are generated."""
...@@ -131,12 +151,23 @@ class UniformPoseCommandCfg(CommandTermCfg): ...@@ -131,12 +151,23 @@ class UniformPoseCommandCfg(CommandTermCfg):
class Ranges: class Ranges:
"""Uniform distribution ranges for the pose commands.""" """Uniform distribution ranges for the pose commands."""
pos_x: tuple[float, float] = MISSING # min max [m] pos_x: tuple[float, float] = MISSING
pos_y: tuple[float, float] = MISSING # min max [m] """Range for the x position (in m)."""
pos_z: tuple[float, float] = MISSING # min max [m]
roll: tuple[float, float] = MISSING # min max [rad] pos_y: tuple[float, float] = MISSING
pitch: tuple[float, float] = MISSING # min max [rad] """Range for the y position (in m)."""
yaw: tuple[float, float] = MISSING # min max [rad]
pos_z: tuple[float, float] = MISSING
"""Range for the z position (in m)."""
roll: tuple[float, float] = MISSING
"""Range for the roll angle (in rad)."""
pitch: tuple[float, float] = MISSING
"""Range for the pitch angle (in rad)."""
yaw: tuple[float, float] = MISSING
"""Range for the yaw angle (in rad)."""
ranges: Ranges = MISSING ranges: Ranges = MISSING
"""Ranges for the commands.""" """Ranges for the commands."""
...@@ -175,8 +206,10 @@ class UniformPose2dCommandCfg(CommandTermCfg): ...@@ -175,8 +206,10 @@ class UniformPose2dCommandCfg(CommandTermCfg):
pos_x: tuple[float, float] = MISSING pos_x: tuple[float, float] = MISSING
"""Range for the x position (in m).""" """Range for the x position (in m)."""
pos_y: tuple[float, float] = MISSING pos_y: tuple[float, float] = MISSING
"""Range for the y position (in m).""" """Range for the y position (in m)."""
heading: tuple[float, float] = MISSING heading: tuple[float, float] = MISSING
"""Heading range for the position commands (in rad). """Heading range for the position commands (in rad).
......
...@@ -11,6 +11,8 @@ import torch ...@@ -11,6 +11,8 @@ import torch
from collections.abc import Sequence from collections.abc import Sequence
from typing import TYPE_CHECKING from typing import TYPE_CHECKING
import omni.log
import omni.isaac.lab.utils.math as math_utils import omni.isaac.lab.utils.math as math_utils
from omni.isaac.lab.assets import Articulation from omni.isaac.lab.assets import Articulation
from omni.isaac.lab.managers import CommandTerm from omni.isaac.lab.managers import CommandTerm
...@@ -49,10 +51,25 @@ class UniformVelocityCommand(CommandTerm): ...@@ -49,10 +51,25 @@ class UniformVelocityCommand(CommandTerm):
Args: Args:
cfg: The configuration of the command generator. cfg: The configuration of the command generator.
env: The environment. env: The environment.
Raises:
ValueError: If the heading command is active but the heading range is not provided.
""" """
# initialize the base class # initialize the base class
super().__init__(cfg, env) super().__init__(cfg, env)
# check configuration
if self.cfg.heading_command and self.cfg.ranges.heading is None:
raise ValueError(
"The velocity command has heading commands active (heading_command=True) but the `ranges.heading`"
" parameter is set to None."
)
if self.cfg.ranges.heading and not self.cfg.heading_command:
omni.log.warn(
f"The velocity command has the 'ranges.heading' attribute set to '{self.cfg.ranges.heading}'"
" but the heading command is not active. Consider setting the flag for the heading command to True."
)
# obtain the robot asset # obtain the robot asset
# -- robot # -- robot
self.robot: Articulation = env.scene[cfg.asset_name] self.robot: Articulation = env.scene[cfg.asset_name]
......
...@@ -181,12 +181,21 @@ class ActionManager(ManagerBase): ...@@ -181,12 +181,21 @@ class ActionManager(ManagerBase):
Args: Args:
cfg: The configuration object or dictionary (``dict[str, ActionTermCfg]``). cfg: The configuration object or dictionary (``dict[str, ActionTermCfg]``).
env: The environment instance. env: The environment instance.
Raises:
ValueError: If the configuration is None.
""" """
# check if config is None
if cfg is None:
raise ValueError("Action manager configuration is None. Please provide a valid configuration.")
# call the base class constructor (this prepares the terms)
super().__init__(cfg, env) super().__init__(cfg, env)
# create buffers to store actions # create buffers to store actions
self._action = torch.zeros((self.num_envs, self.total_action_dim), device=self.device) self._action = torch.zeros((self.num_envs, self.total_action_dim), device=self.device)
self._prev_action = torch.zeros_like(self._action) self._prev_action = torch.zeros_like(self._action)
# check if any term has debug visualization implemented
self.cfg.debug_vis = False self.cfg.debug_vis = False
for term in self._terms.values(): for term in self._terms.values():
self.cfg.debug_vis |= term.cfg.debug_vis self.cfg.debug_vis |= term.cfg.debug_vis
...@@ -334,8 +343,7 @@ class ActionManager(ManagerBase): ...@@ -334,8 +343,7 @@ class ActionManager(ManagerBase):
""" """
def _prepare_terms(self): def _prepare_terms(self):
"""Prepares a list of action terms.""" # create buffers to parse and store terms
# parse action terms from the config
self._term_names: list[str] = list() self._term_names: list[str] = list()
self._terms: dict[str, ActionTerm] = dict() self._terms: dict[str, ActionTerm] = dict()
...@@ -344,6 +352,7 @@ class ActionManager(ManagerBase): ...@@ -344,6 +352,7 @@ class ActionManager(ManagerBase):
cfg_items = self.cfg.items() cfg_items = self.cfg.items()
else: else:
cfg_items = self.cfg.__dict__.items() cfg_items = self.cfg.__dict__.items()
# parse action terms from the config
for term_name, term_cfg in cfg_items: for term_name, term_cfg in cfg_items:
# check if term config is None # check if term config is None
if term_cfg is None: if term_cfg is None:
......
...@@ -243,12 +243,17 @@ class CommandManager(ManagerBase): ...@@ -243,12 +243,17 @@ class CommandManager(ManagerBase):
cfg: The configuration object or dictionary (``dict[str, CommandTermCfg]``). cfg: The configuration object or dictionary (``dict[str, CommandTermCfg]``).
env: The environment instance. env: The environment instance.
""" """
# create buffers to parse and store terms
self._terms: dict[str, CommandTerm] = dict()
# call the base class constructor (this prepares the terms)
super().__init__(cfg, env) super().__init__(cfg, env)
# store the commands # store the commands
self._commands = dict() self._commands = dict()
self.cfg.debug_vis = False if self.cfg:
for term in self._terms.values(): self.cfg.debug_vis = False
self.cfg.debug_vis |= term.cfg.debug_vis for term in self._terms.values():
self.cfg.debug_vis |= term.cfg.debug_vis
def __str__(self) -> str: def __str__(self) -> str:
"""Returns: A string representation for the command manager.""" """Returns: A string representation for the command manager."""
...@@ -371,10 +376,6 @@ class CommandManager(ManagerBase): ...@@ -371,10 +376,6 @@ class CommandManager(ManagerBase):
""" """
def _prepare_terms(self): def _prepare_terms(self):
"""Prepares a list of command terms."""
# parse command terms from the config
self._terms: dict[str, CommandTerm] = dict()
# check if config is dict already # check if config is dict already
if isinstance(self.cfg, dict): if isinstance(self.cfg, dict):
cfg_items = self.cfg.items() cfg_items = self.cfg.items()
......
...@@ -44,7 +44,14 @@ class CurriculumManager(ManagerBase): ...@@ -44,7 +44,14 @@ class CurriculumManager(ManagerBase):
TypeError: If curriculum term is not of type :class:`CurriculumTermCfg`. TypeError: If curriculum term is not of type :class:`CurriculumTermCfg`.
ValueError: If curriculum term configuration does not satisfy its function signature. ValueError: If curriculum term configuration does not satisfy its function signature.
""" """
# create buffers to parse and store terms
self._term_names: list[str] = list()
self._term_cfgs: list[CurriculumTermCfg] = list()
self._class_term_cfgs: list[CurriculumTermCfg] = list()
# call the base class constructor (this will parse the terms config)
super().__init__(cfg, env) super().__init__(cfg, env)
# prepare logging # prepare logging
self._curriculum_state = dict() self._curriculum_state = dict()
for term_name in self._term_names: for term_name in self._term_names:
...@@ -136,11 +143,6 @@ class CurriculumManager(ManagerBase): ...@@ -136,11 +143,6 @@ class CurriculumManager(ManagerBase):
""" """
def _prepare_terms(self): def _prepare_terms(self):
# parse remaining curriculum terms and decimate their information
self._term_names: list[str] = list()
self._term_cfgs: list[CurriculumTermCfg] = list()
self._class_term_cfgs: list[CurriculumTermCfg] = list()
# check if config is dict already # check if config is dict already
if isinstance(self.cfg, dict): if isinstance(self.cfg, dict):
cfg_items = self.cfg.items() cfg_items = self.cfg.items()
......
...@@ -62,6 +62,12 @@ class EventManager(ManagerBase): ...@@ -62,6 +62,12 @@ class EventManager(ManagerBase):
cfg: A configuration object or dictionary (``dict[str, EventTermCfg]``). cfg: A configuration object or dictionary (``dict[str, EventTermCfg]``).
env: An environment object. env: An environment object.
""" """
# create buffers to parse and store terms
self._mode_term_names: dict[str, list[str]] = dict()
self._mode_term_cfgs: dict[str, list[EventTermCfg]] = dict()
self._mode_class_term_cfgs: dict[str, list[EventTermCfg]] = dict()
# call the base class (this will parse the terms config)
super().__init__(cfg, env) super().__init__(cfg, env)
def __str__(self) -> str: def __str__(self) -> str:
...@@ -294,11 +300,6 @@ class EventManager(ManagerBase): ...@@ -294,11 +300,6 @@ class EventManager(ManagerBase):
""" """
def _prepare_terms(self): def _prepare_terms(self):
"""Prepares a list of event functions."""
# parse remaining event terms and decimate their information
self._mode_term_names: dict[str, list[str]] = dict()
self._mode_term_cfgs: dict[str, list[EventTermCfg]] = dict()
self._mode_class_term_cfgs: dict[str, list[EventTermCfg]] = dict()
# buffer to store the time left for "interval" mode # buffer to store the time left for "interval" mode
# if interval is global, then it is a single value, otherwise it is per environment # if interval is global, then it is a single value, otherwise it is per environment
self._interval_term_time_left: list[torch.Tensor] = list() self._interval_term_time_left: list[torch.Tensor] = list()
......
...@@ -120,14 +120,15 @@ class ManagerBase(ABC): ...@@ -120,14 +120,15 @@ class ManagerBase(ABC):
"""Initialize the manager. """Initialize the manager.
Args: Args:
cfg: The configuration object. cfg: The configuration object. If None, the manager is initialized without any terms.
env: The environment instance. env: The environment instance.
""" """
# store the inputs # store the inputs
self.cfg = copy.deepcopy(cfg) self.cfg = copy.deepcopy(cfg)
self._env = env self._env = env
# parse config to create terms information # parse config to create terms information
self._prepare_terms() if self.cfg:
self._prepare_terms()
""" """
Properties. Properties.
......
...@@ -63,9 +63,15 @@ class ObservationManager(ManagerBase): ...@@ -63,9 +63,15 @@ class ObservationManager(ManagerBase):
env: The environment instance. env: The environment instance.
Raises: Raises:
ValueError: If the configuration is None.
RuntimeError: If the shapes of the observation terms in a group are not compatible for concatenation RuntimeError: If the shapes of the observation terms in a group are not compatible for concatenation
and the :attr:`~ObservationGroupCfg.concatenate_terms` attribute is set to True. and the :attr:`~ObservationGroupCfg.concatenate_terms` attribute is set to True.
""" """
# check that cfg is not None
if cfg is None:
raise ValueError("Observation manager configuration is None. Please provide a valid configuration.")
# call the base class constructor (this will parse the terms config)
super().__init__(cfg, env) super().__init__(cfg, env)
# compute combined vector for obs group # compute combined vector for obs group
......
...@@ -47,6 +47,12 @@ class RewardManager(ManagerBase): ...@@ -47,6 +47,12 @@ class RewardManager(ManagerBase):
cfg: The configuration object or dictionary (``dict[str, RewardTermCfg]``). cfg: The configuration object or dictionary (``dict[str, RewardTermCfg]``).
env: The environment instance. env: The environment instance.
""" """
# create buffers to parse and store terms
self._term_names: list[str] = list()
self._term_cfgs: list[RewardTermCfg] = list()
self._class_term_cfgs: list[RewardTermCfg] = list()
# call the base class constructor (this will parse the terms config)
super().__init__(cfg, env) super().__init__(cfg, env)
# prepare extra info to store individual reward term information # prepare extra info to store individual reward term information
self._episode_sums = dict() self._episode_sums = dict()
...@@ -185,12 +191,6 @@ class RewardManager(ManagerBase): ...@@ -185,12 +191,6 @@ class RewardManager(ManagerBase):
""" """
def _prepare_terms(self): def _prepare_terms(self):
"""Prepares a list of reward functions."""
# parse remaining reward terms and decimate their information
self._term_names: list[str] = list()
self._term_cfgs: list[RewardTermCfg] = list()
self._class_term_cfgs: list[RewardTermCfg] = list()
# check if config is dict already # check if config is dict already
if isinstance(self.cfg, dict): if isinstance(self.cfg, dict):
cfg_items = self.cfg.items() cfg_items = self.cfg.items()
......
...@@ -53,6 +53,12 @@ class TerminationManager(ManagerBase): ...@@ -53,6 +53,12 @@ class TerminationManager(ManagerBase):
cfg: The configuration object or dictionary (``dict[str, TerminationTermCfg]``). cfg: The configuration object or dictionary (``dict[str, TerminationTermCfg]``).
env: An environment object. env: An environment object.
""" """
# create buffers to parse and store terms
self._term_names: list[str] = list()
self._term_cfgs: list[TerminationTermCfg] = list()
self._class_term_cfgs: list[TerminationTermCfg] = list()
# call the base class constructor (this will parse the terms config)
super().__init__(cfg, env) super().__init__(cfg, env)
# prepare extra info to store individual termination term information # prepare extra info to store individual termination term information
self._term_dones = dict() self._term_dones = dict()
...@@ -219,12 +225,6 @@ class TerminationManager(ManagerBase): ...@@ -219,12 +225,6 @@ class TerminationManager(ManagerBase):
""" """
def _prepare_terms(self): def _prepare_terms(self):
"""Prepares a list of termination functions."""
# parse remaining termination terms and decimate their information
self._term_names: list[str] = list()
self._term_cfgs: list[TerminationTermCfg] = list()
self._class_term_cfgs: list[TerminationTermCfg] = list()
# check if config is dict already # check if config is dict already
if isinstance(self.cfg, dict): if isinstance(self.cfg, dict):
cfg_items = self.cfg.items() cfg_items = self.cfg.items()
......
...@@ -104,6 +104,8 @@ class InteractiveScene: ...@@ -104,6 +104,8 @@ class InteractiveScene:
Args: Args:
cfg: The configuration class for the scene. cfg: The configuration class for the scene.
""" """
# check that the config is valid
cfg.validate()
# store inputs # store inputs
self.cfg = cfg self.cfg = cfg
# initialize scene elements # initialize scene elements
......
...@@ -9,7 +9,7 @@ import numpy as np ...@@ -9,7 +9,7 @@ import numpy as np
import re import re
import torch import torch
from collections.abc import Sequence from collections.abc import Sequence
from typing import TYPE_CHECKING, ClassVar from typing import TYPE_CHECKING
import omni.log import omni.log
import omni.physics.tensors.impl.api as physx import omni.physics.tensors.impl.api as physx
...@@ -48,14 +48,6 @@ class RayCaster(SensorBase): ...@@ -48,14 +48,6 @@ class RayCaster(SensorBase):
cfg: RayCasterCfg cfg: RayCasterCfg
"""The configuration parameters.""" """The configuration parameters."""
meshes: ClassVar[dict[str, wp.Mesh]] = {}
"""The warp meshes available for raycasting.
The keys correspond to the prim path for the meshes, and values are the corresponding warp Mesh objects.
Note:
We store a global dictionary of all warp meshes to prevent re-loading the mesh for different ray-cast sensor instances.
"""
def __init__(self, cfg: RayCasterCfg): def __init__(self, cfg: RayCasterCfg):
"""Initializes the ray-caster object. """Initializes the ray-caster object.
...@@ -77,6 +69,8 @@ class RayCaster(SensorBase): ...@@ -77,6 +69,8 @@ class RayCaster(SensorBase):
super().__init__(cfg) super().__init__(cfg)
# Create empty variables for storing output data # Create empty variables for storing output data
self._data = RayCasterData() self._data = RayCasterData()
# the warp meshes used for raycasting.
self.meshes: dict[str, wp.Mesh] = {}
def __str__(self) -> str: def __str__(self) -> str:
"""Returns: A string containing information about the instance.""" """Returns: A string containing information about the instance."""
...@@ -84,7 +78,7 @@ class RayCaster(SensorBase): ...@@ -84,7 +78,7 @@ class RayCaster(SensorBase):
f"Ray-caster @ '{self.cfg.prim_path}': \n" f"Ray-caster @ '{self.cfg.prim_path}': \n"
f"\tview type : {self._view.__class__}\n" f"\tview type : {self._view.__class__}\n"
f"\tupdate period (s) : {self.cfg.update_period}\n" f"\tupdate period (s) : {self.cfg.update_period}\n"
f"\tnumber of meshes : {len(RayCaster.meshes)}\n" f"\tnumber of meshes : {len(self.meshes)}\n"
f"\tnumber of sensors : {self._view.count}\n" f"\tnumber of sensors : {self._view.count}\n"
f"\tnumber of rays/sensor: {self.num_rays}\n" f"\tnumber of rays/sensor: {self.num_rays}\n"
f"\ttotal number of rays : {self.num_rays * self._view.count}" f"\ttotal number of rays : {self.num_rays * self._view.count}"
...@@ -163,10 +157,6 @@ class RayCaster(SensorBase): ...@@ -163,10 +157,6 @@ class RayCaster(SensorBase):
# read prims to ray-cast # read prims to ray-cast
for mesh_prim_path in self.cfg.mesh_prim_paths: for mesh_prim_path in self.cfg.mesh_prim_paths:
# check if mesh already casted into warp mesh
if mesh_prim_path in RayCaster.meshes:
continue
# check if the prim is a plane - handle PhysX plane as a special case # check if the prim is a plane - handle PhysX plane as a special case
# if a plane exists then we need to create an infinite mesh that is a plane # if a plane exists then we need to create an infinite mesh that is a plane
mesh_prim = sim_utils.get_first_matching_child_prim( mesh_prim = sim_utils.get_first_matching_child_prim(
...@@ -197,10 +187,10 @@ class RayCaster(SensorBase): ...@@ -197,10 +187,10 @@ class RayCaster(SensorBase):
# print info # print info
omni.log.info(f"Created infinite plane mesh prim: {mesh_prim.GetPath()}.") omni.log.info(f"Created infinite plane mesh prim: {mesh_prim.GetPath()}.")
# add the warp mesh to the list # add the warp mesh to the list
RayCaster.meshes[mesh_prim_path] = wp_mesh self.meshes[mesh_prim_path] = wp_mesh
# throw an error if no meshes are found # throw an error if no meshes are found
if all([mesh_prim_path not in RayCaster.meshes for mesh_prim_path in self.cfg.mesh_prim_paths]): if all([mesh_prim_path not in self.meshes for mesh_prim_path in self.cfg.mesh_prim_paths]):
raise RuntimeError( raise RuntimeError(
f"No meshes found for ray-casting! Please check the mesh prim paths: {self.cfg.mesh_prim_paths}" f"No meshes found for ray-casting! Please check the mesh prim paths: {self.cfg.mesh_prim_paths}"
) )
...@@ -263,7 +253,7 @@ class RayCaster(SensorBase): ...@@ -263,7 +253,7 @@ class RayCaster(SensorBase):
ray_starts_w, ray_starts_w,
ray_directions_w, ray_directions_w,
max_dist=self.cfg.max_distance, max_dist=self.cfg.max_distance,
mesh=RayCaster.meshes[self.cfg.mesh_prim_paths[0]], mesh=self.meshes[self.cfg.mesh_prim_paths[0]],
)[0] )[0]
def _set_debug_vis_impl(self, debug_vis: bool): def _set_debug_vis_impl(self, debug_vis: bool):
......
...@@ -281,7 +281,7 @@ class RayCasterCamera(RayCaster): ...@@ -281,7 +281,7 @@ class RayCasterCamera(RayCaster):
self.ray_hits_w, ray_depth, ray_normal, _ = raycast_mesh( self.ray_hits_w, ray_depth, ray_normal, _ = raycast_mesh(
ray_starts_w, ray_starts_w,
ray_directions_w, ray_directions_w,
mesh=RayCasterCamera.meshes[self.cfg.mesh_prim_paths[0]], mesh=self.meshes[self.cfg.mesh_prim_paths[0]],
max_dist=1e6, max_dist=1e6,
return_distance=any( return_distance=any(
[name in self.cfg.data_types for name in ["distance_to_image_plane", "distance_to_camera"]] [name in self.cfg.data_types for name in ["distance_to_image_plane", "distance_to_camera"]]
......
...@@ -48,6 +48,8 @@ class SensorBase(ABC): ...@@ -48,6 +48,8 @@ class SensorBase(ABC):
# check that config is valid # check that config is valid
if cfg.history_length < 0: if cfg.history_length < 0:
raise ValueError(f"History length must be greater than 0! Received: {cfg.history_length}") raise ValueError(f"History length must be greater than 0! Received: {cfg.history_length}")
# check that the config is valid
cfg.validate()
# store inputs # store inputs
self.cfg = cfg self.cfg = cfg
# flag for whether the sensor is initialized # flag for whether the sensor is initialized
......
...@@ -114,6 +114,8 @@ class SimulationContext(_SimulationContext): ...@@ -114,6 +114,8 @@ class SimulationContext(_SimulationContext):
# store input # store input
if cfg is None: if cfg is None:
cfg = SimulationCfg() cfg = SimulationCfg()
# check that the config is valid
cfg.validate()
self.cfg = cfg self.cfg = cfg
# check that simulation is running # check that simulation is running
if stage_utils.get_current_stage() is None: if stage_utils.get_current_stage() is None:
......
...@@ -88,8 +88,12 @@ class SubTerrainBaseCfg: ...@@ -88,8 +88,12 @@ class SubTerrainBaseCfg:
is 0.7. is 0.7.
""" """
size: tuple[float, float] = MISSING size: tuple[float, float] = (10.0, 10.0)
"""The width (along x) and length (along y) of the terrain (in m).""" """The width (along x) and length (along y) of the terrain (in m). Defaults to (10.0, 10.0).
In case the :class:`~omni.isaac.lab.terrains.TerrainImporterCfg` is used, this parameter gets overridden by
:attr:`omni.isaac.lab.scene.TerrainImporterCfg.size` attribute.
"""
flat_patch_sampling: dict[str, FlatPatchSamplingCfg] | None = None flat_patch_sampling: dict[str, FlatPatchSamplingCfg] | None = None
"""Dictionary of configurations for sampling flat patches on the sub-terrain. Defaults to None, """Dictionary of configurations for sampling flat patches on the sub-terrain. Defaults to None,
......
...@@ -67,6 +67,8 @@ class TerrainImporter: ...@@ -67,6 +67,8 @@ class TerrainImporter:
ValueError: If terrain type is 'usd' and no configuration provided for ``usd_path``. ValueError: If terrain type is 'usd' and no configuration provided for ``usd_path``.
ValueError: If terrain type is 'usd' or 'plane' and no configuration provided for ``env_spacing``. ValueError: If terrain type is 'usd' or 'plane' and no configuration provided for ``env_spacing``.
""" """
# check that the config is valid
cfg.validate()
# store inputs # store inputs
self.cfg = cfg self.cfg = cfg
self.device = sim_utils.SimulationContext.instance().device # type: ignore self.device = sim_utils.SimulationContext.instance().device # type: ignore
......
...@@ -36,8 +36,12 @@ class TerrainImporterCfg: ...@@ -36,8 +36,12 @@ class TerrainImporterCfg:
All sub-terrains are imported relative to this prim path. All sub-terrains are imported relative to this prim path.
""" """
num_envs: int = MISSING num_envs: int = 1
"""The number of environment origins to consider.""" """The number of environment origins to consider. Defaults to 1.
In case, the :class:`~omni.isaac.lab.scene.InteractiveSceneCfg` is used, this parameter gets overridden by
:attr:`omni.isaac.lab.scene.InteractiveSceneCfg.num_envs` attribute.
"""
terrain_type: Literal["generator", "plane", "usd"] = "generator" terrain_type: Literal["generator", "plane", "usd"] = "generator"
"""The type of terrain to generate. Defaults to "generator". """The type of terrain to generate. Defaults to "generator".
......
...@@ -14,7 +14,7 @@ from typing import Any, ClassVar ...@@ -14,7 +14,7 @@ from typing import Any, ClassVar
from .dict import class_to_dict, update_class_from_dict from .dict import class_to_dict, update_class_from_dict
_CONFIGCLASS_METHODS = ["to_dict", "from_dict", "replace", "copy"] _CONFIGCLASS_METHODS = ["to_dict", "from_dict", "replace", "copy", "validate"]
"""List of class methods added at runtime to dataclass.""" """List of class methods added at runtime to dataclass."""
""" """
...@@ -98,6 +98,7 @@ def configclass(cls, **kwargs): ...@@ -98,6 +98,7 @@ def configclass(cls, **kwargs):
setattr(cls, "from_dict", _update_class_from_dict) setattr(cls, "from_dict", _update_class_from_dict)
setattr(cls, "replace", _replace_class_with_kwargs) setattr(cls, "replace", _replace_class_with_kwargs)
setattr(cls, "copy", _copy_class) setattr(cls, "copy", _copy_class)
setattr(cls, "validate", _validate)
# wrap around dataclass # wrap around dataclass
cls = dataclass(cls, **kwargs) cls = dataclass(cls, **kwargs)
# return wrapped class # return wrapped class
...@@ -240,6 +241,56 @@ def _add_annotation_types(cls): ...@@ -240,6 +241,56 @@ def _add_annotation_types(cls):
cls.__annotations__ = hints cls.__annotations__ = hints
def _validate(obj: object, prefix: str = "") -> list[str]:
"""Check the validity of configclass object.
This function checks if the object is a valid configclass object. A valid configclass object contains no MISSING
entries.
Args:
obj: The object to check.
prefix: The prefix to add to the missing fields. Defaults to ''.
Returns:
A list of missing fields.
Raises:
TypeError: When the object is not a valid configuration object.
"""
missing_fields = []
if type(obj) is type(MISSING):
missing_fields.append(prefix)
return missing_fields
elif isinstance(obj, (list, tuple)):
for index, item in enumerate(obj):
current_path = f"{prefix}[{index}]"
missing_fields.extend(_validate(item, prefix=current_path))
return missing_fields
elif isinstance(obj, dict):
obj_dict = obj
elif hasattr(obj, "__dict__"):
obj_dict = obj.__dict__
else:
return missing_fields
for key, value in obj_dict.items():
# disregard builtin attributes
if key.startswith("__"):
continue
current_path = f"{prefix}.{key}" if prefix else key
missing_fields.extend(_validate(value, prefix=current_path))
# raise an error only once at the top-level call
if prefix == "" and missing_fields:
formatted_message = "\n".join(f" - {field}" for field in missing_fields)
raise TypeError(
f"Missing values detected in object {obj.__class__.__name__} for the following"
f" fields:\n{formatted_message}\n"
)
return missing_fields
def _process_mutable_types(cls): def _process_mutable_types(cls):
"""Initialize all mutable elements through :obj:`dataclasses.Field` to avoid unnecessary complaints. """Initialize all mutable elements through :obj:`dataclasses.Field` to avoid unnecessary complaints.
......
...@@ -52,6 +52,7 @@ def get_empty_base_env_cfg(device: str = "cuda:0", num_envs: int = 1, env_spacin ...@@ -52,6 +52,7 @@ def get_empty_base_env_cfg(device: str = "cuda:0", num_envs: int = 1, env_spacin
action_spaces = {"agent_0": 1, "agent_1": 2} action_spaces = {"agent_0": 1, "agent_1": 2}
observation_spaces = {"agent_0": 3, "agent_1": 4} observation_spaces = {"agent_0": 3, "agent_1": 4}
state_space = -1 state_space = -1
episode_length_s = 100.0
return EmptyEnvCfg() return EmptyEnvCfg()
...@@ -72,10 +73,10 @@ class TestDirectMARLEnv(unittest.TestCase): ...@@ -72,10 +73,10 @@ class TestDirectMARLEnv(unittest.TestCase):
# create environment # create environment
env = DirectMARLEnv(cfg=get_empty_base_env_cfg(device=device)) env = DirectMARLEnv(cfg=get_empty_base_env_cfg(device=device))
except Exception as e: except Exception as e:
if "env" in locals(): if "env" in locals() and hasattr(env, "_is_closed"):
env.close() env.close()
else: else:
if hasattr(e, "obj") and hasattr(e.obj, "close"): if hasattr(e, "obj") and hasattr(e.obj, "_is_closed"):
e.obj.close() e.obj.close()
self.fail(f"Failed to set-up the DirectMARLEnv environment. Error: {e}") self.fail(f"Failed to set-up the DirectMARLEnv environment. Error: {e}")
......
...@@ -47,6 +47,7 @@ def create_manager_based_env(render_interval: int): ...@@ -47,6 +47,7 @@ def create_manager_based_env(render_interval: int):
"""Configuration for the test environment.""" """Configuration for the test environment."""
decimation: int = 4 decimation: int = 4
episode_length_s: float = 100.0
sim: SimulationCfg = SimulationCfg(dt=0.005, render_interval=render_interval) sim: SimulationCfg = SimulationCfg(dt=0.005, render_interval=render_interval)
scene: InteractiveSceneCfg = InteractiveSceneCfg(num_envs=1, env_spacing=1.0) scene: InteractiveSceneCfg = InteractiveSceneCfg(num_envs=1, env_spacing=1.0)
actions: EmptyManagerCfg = EmptyManagerCfg() actions: EmptyManagerCfg = EmptyManagerCfg()
...@@ -63,10 +64,13 @@ def create_manager_based_rl_env(render_interval: int): ...@@ -63,10 +64,13 @@ def create_manager_based_rl_env(render_interval: int):
"""Configuration for the test environment.""" """Configuration for the test environment."""
decimation: int = 4 decimation: int = 4
episode_length_s: float = 100.0
sim: SimulationCfg = SimulationCfg(dt=0.005, render_interval=render_interval) sim: SimulationCfg = SimulationCfg(dt=0.005, render_interval=render_interval)
scene: InteractiveSceneCfg = InteractiveSceneCfg(num_envs=1, env_spacing=1.0) scene: InteractiveSceneCfg = InteractiveSceneCfg(num_envs=1, env_spacing=1.0)
actions: EmptyManagerCfg = EmptyManagerCfg() actions: EmptyManagerCfg = EmptyManagerCfg()
observations: EmptyManagerCfg = EmptyManagerCfg() observations: EmptyManagerCfg = EmptyManagerCfg()
rewards: EmptyManagerCfg = EmptyManagerCfg()
terminations: EmptyManagerCfg = EmptyManagerCfg()
return ManagerBasedRLEnv(cfg=EnvCfg()) return ManagerBasedRLEnv(cfg=EnvCfg())
...@@ -81,6 +85,7 @@ def create_direct_rl_env(render_interval: int): ...@@ -81,6 +85,7 @@ def create_direct_rl_env(render_interval: int):
decimation: int = 4 decimation: int = 4
action_space: int = 0 action_space: int = 0
observation_space: int = 0 observation_space: int = 0
episode_length_s: float = 100.0
sim: SimulationCfg = SimulationCfg(dt=0.005, render_interval=render_interval) sim: SimulationCfg = SimulationCfg(dt=0.005, render_interval=render_interval)
scene: InteractiveSceneCfg = InteractiveSceneCfg(num_envs=1, env_spacing=1.0) scene: InteractiveSceneCfg = InteractiveSceneCfg(num_envs=1, env_spacing=1.0)
...@@ -140,10 +145,10 @@ class TestEnvRenderingLogic(unittest.TestCase): ...@@ -140,10 +145,10 @@ class TestEnvRenderingLogic(unittest.TestCase):
else: else:
env = create_direct_rl_env(render_interval) env = create_direct_rl_env(render_interval)
except Exception as e: except Exception as e:
if "env" in locals(): if "env" in locals() and hasattr(env, "_is_closed"):
env.close() env.close()
else: else:
if hasattr(e, "obj") and hasattr(e.obj, "close"): if hasattr(e, "obj") and hasattr(e.obj, "_is_closed"):
e.obj.close() e.obj.close()
self.fail(f"Failed to set-up the environment {env_type}. Error: {e}") self.fail(f"Failed to set-up the environment {env_type}. Error: {e}")
......
...@@ -134,6 +134,15 @@ class TestEventManager(unittest.TestCase): ...@@ -134,6 +134,15 @@ class TestEventManager(unittest.TestCase):
self.assertEqual(len(self.event_man.active_terms["reset"]), 1) self.assertEqual(len(self.event_man.active_terms["reset"]), 1)
self.assertEqual(len(self.event_man.active_terms["custom"]), 2) self.assertEqual(len(self.event_man.active_terms["custom"]), 2)
def test_config_empty(self):
"""Test the creation of reward manager with empty config."""
self.event_man = EventManager(None, self.env)
self.assertEqual(len(self.event_man.active_terms), 0)
# print the expected string
print()
print(self.event_man)
def test_invalid_event_func_module(self): def test_invalid_event_func_module(self):
"""Test the handling of invalid event function's module in string representation.""" """Test the handling of invalid event function's module in string representation."""
cfg = { cfg = {
......
...@@ -12,6 +12,7 @@ simulation_app = AppLauncher(headless=True).app ...@@ -12,6 +12,7 @@ simulation_app = AppLauncher(headless=True).app
"""Rest everything follows.""" """Rest everything follows."""
import torch
import unittest import unittest
from collections import namedtuple from collections import namedtuple
...@@ -123,6 +124,21 @@ class TestRewardManager(unittest.TestCase): ...@@ -123,6 +124,21 @@ class TestRewardManager(unittest.TestCase):
self.assertEqual(float(rewards[0]), expected_reward) self.assertEqual(float(rewards[0]), expected_reward)
self.assertEqual(tuple(rewards.shape), (self.env.num_envs,)) self.assertEqual(tuple(rewards.shape), (self.env.num_envs,))
def test_config_empty(self):
"""Test the creation of reward manager with empty config."""
self.rew_man = RewardManager(None, self.env)
self.assertEqual(len(self.rew_man.active_terms), 0)
# print the expected string
print()
print(self.rew_man)
# compute reward
rewards = self.rew_man.compute(dt=self.env.dt)
# check all rewards are zero
torch.testing.assert_close(rewards, torch.zeros_like(rewards))
def test_active_terms(self): def test_active_terms(self):
"""Test the correct reading of active terms.""" """Test the correct reading of active terms."""
cfg = { cfg = {
......
...@@ -40,7 +40,7 @@ class MySceneCfg(InteractiveSceneCfg): ...@@ -40,7 +40,7 @@ class MySceneCfg(InteractiveSceneCfg):
prim_path="/World/Robot", prim_path="/World/Robot",
spawn=sim_utils.UsdFileCfg(usd_path=f"{ISAAC_NUCLEUS_DIR}/Robots/Simple/revolute_articulation.usd"), spawn=sim_utils.UsdFileCfg(usd_path=f"{ISAAC_NUCLEUS_DIR}/Robots/Simple/revolute_articulation.usd"),
actuators={ actuators={
"joint": ImplicitActuatorCfg(), "joint": ImplicitActuatorCfg(joint_names_expr=[".*"], stiffness=100.0, damping=1.0),
}, },
) )
# rigid object # rigid object
......
...@@ -329,6 +329,45 @@ class NestedDictAndListCfg: ...@@ -329,6 +329,45 @@ class NestedDictAndListCfg:
list_1: list[EnvCfg] = [EnvCfg(), EnvCfg()] list_1: list[EnvCfg] = [EnvCfg(), EnvCfg()]
"""
Dummy configuration: Missing attributes
"""
@configclass
class MissingParentDemoCfg:
"""Dummy parent configuration with missing fields."""
a: int = MISSING
@configclass
class InsideClassCfg:
"""Inner dummy configuration."""
@configclass
class InsideInsideClassCfg:
"""Inner inner dummy configuration."""
a: str = MISSING
inside: str = MISSING
inside_dict = {"a": MISSING}
inside_nested_dict = {"a": {"b": "hello", "c": MISSING, "d": InsideInsideClassCfg()}}
inside_tuple = (10, MISSING, 20)
inside_list = [MISSING, MISSING, 2]
b: InsideClassCfg = InsideClassCfg()
@configclass
class MissingChildDemoCfg(MissingParentDemoCfg):
"""Dummy child configuration with missing fields."""
c: Callable = MISSING
d: int | None = None
e: dict = {}
""" """
Test solutions: Basic Test solutions: Basic
""" """
...@@ -404,6 +443,22 @@ functions_demo_cfg_for_updating = { ...@@ -404,6 +443,22 @@ functions_demo_cfg_for_updating = {
"func_in_dict": {"func": "__main__:dummy_function2"}, "func_in_dict": {"func": "__main__:dummy_function2"},
} }
"""
Test solutions: Missing attributes
"""
validity_expected_fields = [
"a",
"b.inside",
"b.inside_dict.a",
"b.inside_nested_dict.a.c",
"b.inside_nested_dict.a.d.a",
"b.inside_tuple[1]",
"b.inside_list[0]",
"b.inside_list[1]",
"c",
]
""" """
Test fixtures. Test fixtures.
""" """
...@@ -888,6 +943,22 @@ class TestConfigClass(unittest.TestCase): ...@@ -888,6 +943,22 @@ class TestConfigClass(unittest.TestCase):
self.assertEqual(md5_hash_1, md5_hash_2) self.assertEqual(md5_hash_1, md5_hash_2)
def test_validity(self):
"""Check that invalid configurations raise errors."""
cfg = MissingChildDemoCfg()
with self.assertRaises(TypeError) as context:
cfg.validate()
# check that the expected missing fields are in the error message
error_message = str(context.exception)
for elem in validity_expected_fields:
self.assertIn(elem, error_message)
# check that no more than the expected missing fields are in the error message
self.assertEqual(len(error_message.split("\n")) - 2, len(validity_expected_fields))
if __name__ == "__main__": if __name__ == "__main__":
run_tests() run_tests()
[package] [package]
# Note: Semantic Versioning is used: https://semver.org/ # Note: Semantic Versioning is used: https://semver.org/
version = "0.10.8" version = "0.10.9"
# Description # Description
title = "Isaac Lab Environments" title = "Isaac Lab Environments"
......
Changelog Changelog
--------- ---------
0.10.9 (2024-10-22)
~~~~~~~~~~~~~~~~~~~
Changed
^^^^^^^
* Sets curriculum and commands to None in manager-based environment configurations when not needed.
Earlier, this was done by making an empty configuration object, which is now unnecessary.
0.10.8 (2024-10-22) 0.10.8 (2024-10-22)
~~~~~~~~~~~~~~~~~~~ ~~~~~~~~~~~~~~~~~~~
......
...@@ -58,14 +58,6 @@ class MySceneCfg(InteractiveSceneCfg): ...@@ -58,14 +58,6 @@ class MySceneCfg(InteractiveSceneCfg):
## ##
@configclass
class CommandsCfg:
"""Command terms for the MDP."""
# no commands for this MDP
null = mdp.NullCommandCfg()
@configclass @configclass
class ActionsCfg: class ActionsCfg:
"""Action specifications for the MDP.""" """Action specifications for the MDP."""
...@@ -163,13 +155,6 @@ class TerminationsCfg: ...@@ -163,13 +155,6 @@ class TerminationsCfg:
torso_height = DoneTerm(func=mdp.root_height_below_minimum, params={"minimum_height": 0.31}) torso_height = DoneTerm(func=mdp.root_height_below_minimum, params={"minimum_height": 0.31})
@configclass
class CurriculumCfg:
"""Curriculum terms for the MDP."""
pass
@configclass @configclass
class AntEnvCfg(ManagerBasedRLEnvCfg): class AntEnvCfg(ManagerBasedRLEnvCfg):
"""Configuration for the MuJoCo-style Ant walking environment.""" """Configuration for the MuJoCo-style Ant walking environment."""
...@@ -179,13 +164,10 @@ class AntEnvCfg(ManagerBasedRLEnvCfg): ...@@ -179,13 +164,10 @@ class AntEnvCfg(ManagerBasedRLEnvCfg):
# Basic settings # Basic settings
observations: ObservationsCfg = ObservationsCfg() observations: ObservationsCfg = ObservationsCfg()
actions: ActionsCfg = ActionsCfg() actions: ActionsCfg = ActionsCfg()
commands: CommandsCfg = CommandsCfg()
# MDP settings # MDP settings
rewards: RewardsCfg = RewardsCfg() rewards: RewardsCfg = RewardsCfg()
terminations: TerminationsCfg = TerminationsCfg() terminations: TerminationsCfg = TerminationsCfg()
events: EventCfg = EventCfg() events: EventCfg = EventCfg()
curriculum: CurriculumCfg = CurriculumCfg()
def __post_init__(self): def __post_init__(self):
"""Post initialization.""" """Post initialization."""
......
...@@ -60,14 +60,6 @@ class CartpoleSceneCfg(InteractiveSceneCfg): ...@@ -60,14 +60,6 @@ class CartpoleSceneCfg(InteractiveSceneCfg):
## ##
@configclass
class CommandsCfg:
"""Command terms for the MDP."""
# no commands for this MDP
null = mdp.NullCommandCfg()
@configclass @configclass
class ActionsCfg: class ActionsCfg:
"""Action specifications for the MDP.""" """Action specifications for the MDP."""
...@@ -162,13 +154,6 @@ class TerminationsCfg: ...@@ -162,13 +154,6 @@ class TerminationsCfg:
) )
@configclass
class CurriculumCfg:
"""Configuration for the curriculum."""
pass
## ##
# Environment configuration # Environment configuration
## ##
...@@ -185,11 +170,8 @@ class CartpoleEnvCfg(ManagerBasedRLEnvCfg): ...@@ -185,11 +170,8 @@ class CartpoleEnvCfg(ManagerBasedRLEnvCfg):
actions: ActionsCfg = ActionsCfg() actions: ActionsCfg = ActionsCfg()
events: EventCfg = EventCfg() events: EventCfg = EventCfg()
# MDP settings # MDP settings
curriculum: CurriculumCfg = CurriculumCfg()
rewards: RewardsCfg = RewardsCfg() rewards: RewardsCfg = RewardsCfg()
terminations: TerminationsCfg = TerminationsCfg() terminations: TerminationsCfg = TerminationsCfg()
# No command generator
commands: CommandsCfg = CommandsCfg()
# Post initialization # Post initialization
def __post_init__(self) -> None: def __post_init__(self) -> None:
......
...@@ -102,14 +102,6 @@ class MySceneCfg(InteractiveSceneCfg): ...@@ -102,14 +102,6 @@ class MySceneCfg(InteractiveSceneCfg):
## ##
@configclass
class CommandsCfg:
"""Command terms for the MDP."""
# no commands for this MDP
null = mdp.NullCommandCfg()
@configclass @configclass
class ActionsCfg: class ActionsCfg:
"""Action specifications for the MDP.""" """Action specifications for the MDP."""
...@@ -248,13 +240,6 @@ class TerminationsCfg: ...@@ -248,13 +240,6 @@ class TerminationsCfg:
torso_height = DoneTerm(func=mdp.root_height_below_minimum, params={"minimum_height": 0.8}) torso_height = DoneTerm(func=mdp.root_height_below_minimum, params={"minimum_height": 0.8})
@configclass
class CurriculumCfg:
"""Curriculum terms for the MDP."""
pass
@configclass @configclass
class HumanoidEnvCfg(ManagerBasedRLEnvCfg): class HumanoidEnvCfg(ManagerBasedRLEnvCfg):
"""Configuration for the MuJoCo-style Humanoid walking environment.""" """Configuration for the MuJoCo-style Humanoid walking environment."""
...@@ -264,13 +249,10 @@ class HumanoidEnvCfg(ManagerBasedRLEnvCfg): ...@@ -264,13 +249,10 @@ class HumanoidEnvCfg(ManagerBasedRLEnvCfg):
# Basic settings # Basic settings
observations: ObservationsCfg = ObservationsCfg() observations: ObservationsCfg = ObservationsCfg()
actions: ActionsCfg = ActionsCfg() actions: ActionsCfg = ActionsCfg()
commands: CommandsCfg = CommandsCfg()
# MDP settings # MDP settings
rewards: RewardsCfg = RewardsCfg() rewards: RewardsCfg = RewardsCfg()
terminations: TerminationsCfg = TerminationsCfg() terminations: TerminationsCfg = TerminationsCfg()
events: EventCfg = EventCfg() events: EventCfg = EventCfg()
curriculum: CurriculumCfg = CurriculumCfg()
def __post_init__(self): def __post_init__(self):
"""Post initialization.""" """Post initialization."""
......
...@@ -293,13 +293,6 @@ class SpotTerminationsCfg: ...@@ -293,13 +293,6 @@ class SpotTerminationsCfg:
) )
@configclass
class SpotCurriculumCfg:
"""Curriculum terms for the MDP."""
pass
@configclass @configclass
class SpotFlatEnvCfg(LocomotionVelocityRoughEnvCfg): class SpotFlatEnvCfg(LocomotionVelocityRoughEnvCfg):
...@@ -312,7 +305,6 @@ class SpotFlatEnvCfg(LocomotionVelocityRoughEnvCfg): ...@@ -312,7 +305,6 @@ class SpotFlatEnvCfg(LocomotionVelocityRoughEnvCfg):
rewards: SpotRewardsCfg = SpotRewardsCfg() rewards: SpotRewardsCfg = SpotRewardsCfg()
terminations: SpotTerminationsCfg = SpotTerminationsCfg() terminations: SpotTerminationsCfg = SpotTerminationsCfg()
events: SpotEventCfg = SpotEventCfg() events: SpotEventCfg = SpotEventCfg()
curriculum: SpotCurriculumCfg = SpotCurriculumCfg()
# Viewer # Viewer
viewer = ViewerCfg(eye=(10.5, 10.5, 0.3), origin_type="world", env_index=0, asset_name="robot") viewer = ViewerCfg(eye=(10.5, 10.5, 0.3), origin_type="world", env_index=0, asset_name="robot")
......
...@@ -123,13 +123,6 @@ class CabinetSceneCfg(InteractiveSceneCfg): ...@@ -123,13 +123,6 @@ class CabinetSceneCfg(InteractiveSceneCfg):
## ##
@configclass
class CommandsCfg:
"""Command terms for the MDP."""
null_command = mdp.NullCommandCfg()
@configclass @configclass
class ActionsCfg: class ActionsCfg:
"""Action specifications for the MDP.""" """Action specifications for the MDP."""
...@@ -267,7 +260,6 @@ class CabinetEnvCfg(ManagerBasedRLEnvCfg): ...@@ -267,7 +260,6 @@ class CabinetEnvCfg(ManagerBasedRLEnvCfg):
# Basic settings # Basic settings
observations: ObservationsCfg = ObservationsCfg() observations: ObservationsCfg = ObservationsCfg()
actions: ActionsCfg = ActionsCfg() actions: ActionsCfg = ActionsCfg()
commands: CommandsCfg = CommandsCfg()
# MDP settings # MDP settings
rewards: RewardsCfg = RewardsCfg() rewards: RewardsCfg = RewardsCfg()
terminations: TerminationsCfg = TerminationsCfg() terminations: TerminationsCfg = TerminationsCfg()
......
...@@ -107,13 +107,6 @@ class CommandsCfg: ...@@ -107,13 +107,6 @@ class CommandsCfg:
) )
@configclass
class CurriculumCfg:
"""Curriculum terms for the MDP."""
pass
@configclass @configclass
class TerminationsCfg: class TerminationsCfg:
"""Termination terms for the MDP.""" """Termination terms for the MDP."""
...@@ -127,14 +120,16 @@ class TerminationsCfg: ...@@ -127,14 +120,16 @@ class TerminationsCfg:
@configclass @configclass
class NavigationEnvCfg(ManagerBasedRLEnvCfg): class NavigationEnvCfg(ManagerBasedRLEnvCfg):
"""Configuration for the navigation environment."""
# environment settings
scene: SceneEntityCfg = LOW_LEVEL_ENV_CFG.scene scene: SceneEntityCfg = LOW_LEVEL_ENV_CFG.scene
commands: CommandsCfg = CommandsCfg()
actions: ActionsCfg = ActionsCfg() actions: ActionsCfg = ActionsCfg()
observations: ObservationsCfg = ObservationsCfg() observations: ObservationsCfg = ObservationsCfg()
rewards: RewardsCfg = RewardsCfg()
events: EventCfg = EventCfg() events: EventCfg = EventCfg()
# mdp settings
curriculum: CurriculumCfg = CurriculumCfg() commands: CommandsCfg = CommandsCfg()
rewards: RewardsCfg = RewardsCfg()
terminations: TerminationsCfg = TerminationsCfg() terminations: TerminationsCfg = TerminationsCfg()
def __post_init__(self): def __post_init__(self):
......
...@@ -101,13 +101,20 @@ class TestEnvironmentDeterminism(unittest.TestCase): ...@@ -101,13 +101,20 @@ class TestEnvironmentDeterminism(unittest.TestCase):
"""Run random actions and obtain transition tuples after fixed number of steps.""" """Run random actions and obtain transition tuples after fixed number of steps."""
# create a new stage # create a new stage
omni.usd.get_context().new_stage() omni.usd.get_context().new_stage()
# parse configuration try:
env_cfg = parse_env_cfg(task_name, device=device, num_envs=num_envs) # parse configuration
# set seed env_cfg = parse_env_cfg(task_name, device=device, num_envs=num_envs)
env_cfg.seed = 42 # set seed
env_cfg.seed = 42
# create environment # create environment
env = gym.make(task_name, cfg=env_cfg) env = gym.make(task_name, cfg=env_cfg)
except Exception as e:
if "env" in locals() and hasattr(env, "_is_closed"):
env.close()
else:
if hasattr(e, "obj") and hasattr(e.obj, "_is_closed"):
e.obj.close()
self.fail(f"Failed to set-up the environment for task {task_name}. Error: {e}")
# disable control on stop # disable control on stop
env.unwrapped.sim._app_control_on_stop_handle = None # type: ignore env.unwrapped.sim._app_control_on_stop_handle = None # type: ignore
......
...@@ -100,10 +100,10 @@ class TestEnvironments(unittest.TestCase): ...@@ -100,10 +100,10 @@ class TestEnvironments(unittest.TestCase):
# create environment # create environment
env = gym.make(task_name, cfg=env_cfg) env = gym.make(task_name, cfg=env_cfg)
except Exception as e: except Exception as e:
if "env" in locals(): if "env" in locals() and hasattr(env, "_is_closed"):
env.close() env.close()
else: else:
if hasattr(e, "obj") and hasattr(e.obj, "close"): if hasattr(e, "obj") and hasattr(e.obj, "_is_closed"):
e.obj.close() e.obj.close()
self.fail(f"Failed to set-up the environment for task {task_name}. Error: {e}") self.fail(f"Failed to set-up the environment for task {task_name}. Error: {e}")
......
...@@ -39,7 +39,6 @@ class TestEnvironments(unittest.TestCase): ...@@ -39,7 +39,6 @@ class TestEnvironments(unittest.TestCase):
cls.registered_tasks.append(task_spec.id) cls.registered_tasks.append(task_spec.id)
# sort environments by name # sort environments by name
cls.registered_tasks.sort() cls.registered_tasks.sort()
cls.registered_tasks = ["Isaac-Shadow-Hand-Over-Direct-v0"]
# print all existing task names # print all existing task names
print(">>> All registered environments:", cls.registered_tasks) print(">>> All registered environments:", cls.registered_tasks)
...@@ -97,10 +96,10 @@ class TestEnvironments(unittest.TestCase): ...@@ -97,10 +96,10 @@ class TestEnvironments(unittest.TestCase):
# create environment # create environment
env: DirectMARLEnv = gym.make(task_name, cfg=env_cfg) env: DirectMARLEnv = gym.make(task_name, cfg=env_cfg)
except Exception as e: except Exception as e:
if "env" in locals(): if "env" in locals() and hasattr(env, "_is_closed"):
env.close() env.close()
else: else:
if hasattr(e, "obj") and hasattr(e.obj, "close"): if hasattr(e, "obj") and hasattr(e.obj, "_is_closed"):
e.obj.close() e.obj.close()
self.fail(f"Failed to set-up the environment for task {task_name}. Error: {e}") self.fail(f"Failed to set-up the environment for task {task_name}. Error: {e}")
......
...@@ -69,10 +69,10 @@ class TestRlGamesVecEnvWrapper(unittest.TestCase): ...@@ -69,10 +69,10 @@ class TestRlGamesVecEnvWrapper(unittest.TestCase):
# wrap environment # wrap environment
env = RlGamesVecEnvWrapper(env, "cuda:0", 100, 100) env = RlGamesVecEnvWrapper(env, "cuda:0", 100, 100)
except Exception as e: except Exception as e:
if "env" in locals(): if "env" in locals() and hasattr(env, "_is_closed"):
env.close() env.close()
else: else:
if hasattr(e, "obj") and hasattr(e.obj, "close"): if hasattr(e, "obj") and hasattr(e.obj, "_is_closed"):
e.obj.close() e.obj.close()
self.fail(f"Failed to set-up the environment for task {task_name}. Error: {e}") self.fail(f"Failed to set-up the environment for task {task_name}. Error: {e}")
......
...@@ -69,10 +69,10 @@ class TestRslRlVecEnvWrapper(unittest.TestCase): ...@@ -69,10 +69,10 @@ class TestRslRlVecEnvWrapper(unittest.TestCase):
# wrap environment # wrap environment
env = RslRlVecEnvWrapper(env) env = RslRlVecEnvWrapper(env)
except Exception as e: except Exception as e:
if "env" in locals(): if "env" in locals() and hasattr(env, "_is_closed"):
env.close() env.close()
else: else:
if hasattr(e, "obj") and hasattr(e.obj, "close"): if hasattr(e, "obj") and hasattr(e.obj, "_is_closed"):
e.obj.close() e.obj.close()
self.fail(f"Failed to set-up the environment for task {task_name}. Error: {e}") self.fail(f"Failed to set-up the environment for task {task_name}. Error: {e}")
......
...@@ -70,10 +70,10 @@ class TestStableBaselines3VecEnvWrapper(unittest.TestCase): ...@@ -70,10 +70,10 @@ class TestStableBaselines3VecEnvWrapper(unittest.TestCase):
# wrap environment # wrap environment
env = Sb3VecEnvWrapper(env) env = Sb3VecEnvWrapper(env)
except Exception as e: except Exception as e:
if "env" in locals(): if "env" in locals() and hasattr(env, "_is_closed"):
env.close() env.close()
else: else:
if hasattr(e, "obj") and hasattr(e.obj, "close"): if hasattr(e, "obj") and hasattr(e.obj, "_is_closed"):
e.obj.close() e.obj.close()
self.fail(f"Failed to set-up the environment for task {task_name}. Error: {e}") self.fail(f"Failed to set-up the environment for task {task_name}. Error: {e}")
......
...@@ -68,10 +68,10 @@ class TestSKRLVecEnvWrapper(unittest.TestCase): ...@@ -68,10 +68,10 @@ class TestSKRLVecEnvWrapper(unittest.TestCase):
# wrap environment # wrap environment
env = SkrlVecEnvWrapper(env) env = SkrlVecEnvWrapper(env)
except Exception as e: except Exception as e:
if "env" in locals(): if "env" in locals() and hasattr(env, "_is_closed"):
env.close() env.close()
else: else:
if hasattr(e, "obj") and hasattr(e.obj, "close"): if hasattr(e, "obj") and hasattr(e.obj, "_is_closed"):
e.obj.close() e.obj.close()
self.fail(f"Failed to set-up the environment for task {task_name}. Error: {e}") self.fail(f"Failed to set-up the environment for task {task_name}. Error: {e}")
# reset environment # reset environment
......
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