From 7a4b6d2be5823d03f91a448751947a68add0a285 Mon Sep 17 00:00:00 2001 From: matthewtrepte Date: Tue, 5 May 2026 13:13:43 -0700 Subject: [PATCH 01/51] Add Debug Visualization Markers to Newton Based Visualizers (#5473) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit # Description Extend debug Visualization Markers, which are supported in the Kit Visualizer, to the Newton Visualizers. These Visualization Markers are various shapes and models which can be added to envs for debugging / showing extra information. Also added filtering for partial visualization (when we filtered which envs are shown the in the visualizer, we also filter the markers) For general USD mesh marker support in Newton, a followup PR will be required, once a Newton API for general USD -> Newton Mesh conversion is added (see https://github.com/newton-physics/newton/issues/2667) Checked velocity arrows, dexcubes, raycasts, frames, goal markers ## Type of change - New feature (non-breaking change which adds functionality) - Documentation update ## Screenshots Please attach before and after screenshots of the change if applicable. ## Checklist - [ ] I have read and understood the [contribution guidelines](https://isaac-sim.github.io/IsaacLab/main/source/refs/contributing.html) - [ ] I have run the [`pre-commit` checks](https://pre-commit.com/) with `./isaaclab.sh --format` - [ ] I have made corresponding changes to the documentation - [ ] My changes generate no new warnings - [ ] I have added tests that prove my fix is effective or that my feature works - [ ] I have updated the changelog and the corresponding version in the extension's `config/extension.toml` file - [ ] I have added my name to the `CONTRIBUTORS.md` or my name already exists there --------- Signed-off-by: matthewtrepte --- docs/source/features/visualization.rst | 26 +- .../mtrepte-expand_viz_markers-2.skip | 0 source/isaaclab/isaaclab/assets/asset_base.py | 27 +- .../isaaclab/managers/action_manager.py | 23 +- .../isaaclab/managers/command_manager.py | 26 +- .../isaaclab/markers/vis_marker_registry.py | 66 +++ .../isaaclab/markers/visualization_markers.py | 486 +++++++--------- .../isaaclab/isaaclab/sensors/sensor_base.py | 29 +- .../isaaclab/sim/simulation_context.py | 7 + .../test_simulation_context_visualizers.py | 344 ++++++++++++ .../kit/kit_visualization_markers.py | 221 ++++++++ .../kit/kit_visualizer.py | 2 +- .../newton/newton_visualization_markers.py | 531 ++++++++++++++++++ .../newton/newton_visualizer.py | 17 +- .../rerun/rerun_visualizer.py | 32 +- .../viser/viser_visualizer.py | 35 +- 16 files changed, 1490 insertions(+), 382 deletions(-) create mode 100644 source/isaaclab/changelog.d/mtrepte-expand_viz_markers-2.skip create mode 100644 source/isaaclab/isaaclab/markers/vis_marker_registry.py create mode 100644 source/isaaclab_visualizers/isaaclab_visualizers/kit/kit_visualization_markers.py create mode 100644 source/isaaclab_visualizers/isaaclab_visualizers/newton/newton_visualization_markers.py diff --git a/docs/source/features/visualization.rst b/docs/source/features/visualization.rst index 4efbf2470698..c68816c0da00 100644 --- a/docs/source/features/visualization.rst +++ b/docs/source/features/visualization.rst @@ -22,16 +22,16 @@ Isaac Lab supports four visualizer backends, each optimized for different use ca - Key Features * - **Omniverse** - High-fidelity, Isaac Sim integration - - USD, visual markers, live plots + - USD, visualization markers, live plots * - **Newton** - Fast iteration - - Low overhead, visual markers + - Low overhead, visualization markers * - **Rerun** - Remote viewing, replay - - Webviewer, time scrubbing, recording export + - Webviewer, time scrubbing, recording export, visualization markers * - **Viser** - Web-based remote visualization, sharing, recording - - Warp-based rendering, browser-based, share URL + - Warp-based rendering, browser-based, share URL, visualization markers *The following visualizers are shown training the Isaac-Velocity-Flat-Anymal-D-v0 environment.* @@ -284,9 +284,9 @@ Omniverse Visualizer **Main Features:** - Native USD stage integration -- Visualization markers for debugging (arrows, frames, points, etc.) - Live plots for monitoring training metrics - Full Isaac Sim rendering capabilities and tooling +- Visualization markers for debugging (arrows, frames, object targets, etc.) **Core Configuration:** @@ -316,10 +316,10 @@ Newton Visualizer **Main Features:** - Lightweight OpenGL rendering with low overhead -- Visualization markers (joints, contacts, springs, COM) - Simulation and rendering pause controls - Adjustable update frequency for performance tuning - Some customizable rendering options (shadows, sky, wireframe) +- Visualization markers (joints, contacts, springs, COM, debug markers) **Interactive Controls:** @@ -388,6 +388,7 @@ Rerun Visualizer - Metadata logging and filtering - Recording to .rrd files for offline replay (.rrd files can be opened with ctrl+O from the web viewer) - Timeline scrubbing and playback controls of recordings +- Visualization debug markers **Core Configuration:** @@ -432,6 +433,7 @@ server, allowing you to view and interact with the scene from any browser. - Optional public share URL for remote viewing - Recording to ``.viser`` format for replay - Environment filtering to control which environments are rendered +- Visualization debug markers **Launch with Viser:** @@ -464,7 +466,7 @@ server, allowing you to view and interact with the scene from any browser. .. note:: - The Viser visualizer does not currently support markers or live plots. + The Viser visualizer does not currently support live plots. Performance Note @@ -497,15 +499,9 @@ the num of environments can be overwritten and decreased using ``--num_envs``: The FPS control in the Rerun visualizer UI may not affect the visualization frame rate in all configurations. -**Newton Visualizer Contact and Center of Mass Markers** +**Live Plots** -Contact and center of mass markers are not yet supported in the Newton visualizer. This will be addressed in a future release. - - -**Viser Visualizer Markers and Live Plots** - -The Viser visualizer does not currently support visualization markers or live plots. For these features, use the -Omniverse or Newton visualizers. +Currently, live plots are only available in the Kit Visualizer. **Viser Visualizer Renderer Requirement** diff --git a/source/isaaclab/changelog.d/mtrepte-expand_viz_markers-2.skip b/source/isaaclab/changelog.d/mtrepte-expand_viz_markers-2.skip new file mode 100644 index 000000000000..e69de29bb2d1 diff --git a/source/isaaclab/isaaclab/assets/asset_base.py b/source/isaaclab/isaaclab/assets/asset_base.py index a7da0d36fe12..b72788083ad3 100644 --- a/source/isaaclab/isaaclab/assets/asset_base.py +++ b/source/isaaclab/isaaclab/assets/asset_base.py @@ -205,16 +205,13 @@ def set_debug_vis(self, debug_vis: bool) -> bool: if debug_vis: if self._debug_vis_handle is None: sim_ctx = SimulationContext.instance() - if "physx" in sim_ctx.physics_manager.__name__.lower(): - import omni.kit.app - - app_interface = omni.kit.app.get_app_interface() - self._debug_vis_handle = app_interface.get_post_update_event_stream().create_subscription_to_pop( - lambda event, obj=weakref.proxy(self): obj._debug_vis_callback(event) - ) + if sim_ctx is not None: + self._debug_vis_handle = sim_ctx.vis_marker_registry.add_debug_vis_callback(self) else: - if self._debug_vis_handle is not None: - self._debug_vis_handle.unsubscribe() + sim_ctx = SimulationContext.instance() + if sim_ctx is not None: + sim_ctx.vis_marker_registry.clear_debug_vis_callback(self) + else: self._debug_vis_handle = None # return success return True @@ -404,8 +401,10 @@ def _initialize_callback(self, event): def _invalidate_initialize_callback(self, event): """Invalidates the scene elements.""" self._is_initialized = False - if self._debug_vis_handle is not None: - self._debug_vis_handle.unsubscribe() + sim_ctx = SimulationContext.instance() + if sim_ctx is not None: + sim_ctx.vis_marker_registry.clear_debug_vis_callback(self) + else: self._debug_vis_handle = None def _on_prim_deletion(self, event) -> None: @@ -435,6 +434,8 @@ def _clear_callbacks(self) -> None: if self._prim_deletion_handle is not None: self._prim_deletion_handle.deregister() self._prim_deletion_handle = None - if self._debug_vis_handle is not None: - self._debug_vis_handle.unsubscribe() + sim_ctx = SimulationContext.instance() + if sim_ctx is not None: + sim_ctx.vis_marker_registry.clear_debug_vis_callback(self) + else: self._debug_vis_handle = None diff --git a/source/isaaclab/isaaclab/managers/action_manager.py b/source/isaaclab/isaaclab/managers/action_manager.py index 7d49d0245d7b..d711596e5f5a 100644 --- a/source/isaaclab/isaaclab/managers/action_manager.py +++ b/source/isaaclab/isaaclab/managers/action_manager.py @@ -9,7 +9,6 @@ import inspect import re -import weakref from abc import abstractmethod from collections.abc import Sequence from typing import TYPE_CHECKING, Any @@ -17,11 +16,6 @@ import torch from prettytable import PrettyTable -from isaaclab.utils.version import has_kit - -if has_kit(): - import omni.kit.app - from isaaclab.envs.utils.io_descriptors import GenericActionIODescriptor from .manager_base import ManagerBase, ManagerTermBase @@ -66,9 +60,11 @@ def __init__(self, cfg: ActionTermCfg, env: ManagerBasedEnv): def __del__(self): """Unsubscribe from the callbacks.""" - if self._debug_vis_handle: - self._debug_vis_handle.unsubscribe() - self._debug_vis_handle = None + env = getattr(self, "_env", None) + sim = getattr(env, "sim", None) + registry = getattr(sim, "vis_marker_registry", None) + if registry is not None: + registry.clear_debug_vis_callback(self) """ Properties. @@ -135,15 +131,10 @@ def set_debug_vis(self, debug_vis: bool) -> bool: if debug_vis: # create a subscriber for the post update event if it doesn't exist if self._debug_vis_handle is None: - app_interface = omni.kit.app.get_app_interface() - self._debug_vis_handle = app_interface.get_post_update_event_stream().create_subscription_to_pop( - lambda event, obj=weakref.proxy(self): obj._debug_vis_callback(event) - ) + self._debug_vis_handle = self._env.sim.vis_marker_registry.add_debug_vis_callback(self) else: # remove the subscriber if it exists - if self._debug_vis_handle is not None: - self._debug_vis_handle.unsubscribe() - self._debug_vis_handle = None + self._env.sim.vis_marker_registry.clear_debug_vis_callback(self) # return success return True diff --git a/source/isaaclab/isaaclab/managers/command_manager.py b/source/isaaclab/isaaclab/managers/command_manager.py index f92dbd2799f3..9493fc81fbcf 100644 --- a/source/isaaclab/isaaclab/managers/command_manager.py +++ b/source/isaaclab/isaaclab/managers/command_manager.py @@ -8,7 +8,6 @@ from __future__ import annotations import inspect -import weakref from abc import abstractmethod from collections.abc import Sequence from typing import TYPE_CHECKING @@ -16,17 +15,12 @@ import torch from prettytable import PrettyTable -from isaaclab.utils.version import has_kit - from .manager_base import ManagerBase, ManagerTermBase from .manager_term_cfg import CommandTermCfg if TYPE_CHECKING: from isaaclab.envs import ManagerBasedRLEnv -if has_kit(): - import omni.kit.app - class CommandTerm(ManagerTermBase): """The base class for implementing a command term. @@ -65,9 +59,11 @@ def __init__(self, cfg: CommandTermCfg, env: ManagerBasedRLEnv): def __del__(self): """Unsubscribe from the callbacks.""" - if self._debug_vis_handle: - self._debug_vis_handle.unsubscribe() - self._debug_vis_handle = None + env = getattr(self, "_env", None) + sim = getattr(env, "sim", None) + registry = getattr(sim, "vis_marker_registry", None) + if registry is not None: + registry.clear_debug_vis_callback(self) """ Properties @@ -106,18 +102,12 @@ def set_debug_vis(self, debug_vis: bool) -> bool: # toggle debug visualization objects self._set_debug_vis_impl(debug_vis) # toggle debug visualization handles - if debug_vis and has_kit(): - # create a subscriber for the post update event if it doesn't exist + if debug_vis: if self._debug_vis_handle is None: - app_interface = omni.kit.app.get_app_interface() - self._debug_vis_handle = app_interface.get_post_update_event_stream().create_subscription_to_pop( - lambda event, obj=weakref.proxy(self): obj._debug_vis_callback(event) - ) + self._debug_vis_handle = self._env.sim.vis_marker_registry.add_debug_vis_callback(self) else: # remove the subscriber if it exists - if self._debug_vis_handle is not None: - self._debug_vis_handle.unsubscribe() - self._debug_vis_handle = None + self._env.sim.vis_marker_registry.clear_debug_vis_callback(self) # return success return True diff --git a/source/isaaclab/isaaclab/markers/vis_marker_registry.py b/source/isaaclab/isaaclab/markers/vis_marker_registry.py new file mode 100644 index 000000000000..a50d26713971 --- /dev/null +++ b/source/isaaclab/isaaclab/markers/vis_marker_registry.py @@ -0,0 +1,66 @@ +# Copyright (c) 2022-2026, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md). +# All rights reserved. +# +# SPDX-License-Identifier: BSD-3-Clause + +"""Registry for visualization marker state.""" + +from __future__ import annotations + +import weakref +from collections.abc import Callable +from typing import Any + + +class VisMarkerRegistry: + """Tracks visualization marker callbacks and active marker groups.""" + + def __init__(self): + self._callbacks: dict[str, Callable[[Any], None]] = {} + self._groups: dict[str, Any] = {} + + def add_callback(self, name: str, callback: Callable[[Any], None]) -> str: + """Register a callback invoked before marker-capable visualizers step each render tick.""" + self._callbacks[name] = callback + return name + + def add_debug_vis_callback(self, owner: Any) -> str: + """Register an owner's debug visualization callback. + + Args: + owner: Object implementing ``_debug_vis_callback(event)``. + + Returns: + Callback identifier that can be passed to :meth:`remove_callback`. + """ + callback_id = f"visualization_marker:{type(owner).__name__}:{id(owner)}" + owner_ref = weakref.proxy(owner) + return self.add_callback(callback_id, lambda event: owner_ref._debug_vis_callback(event)) + + def clear_debug_vis_callback(self, owner: Any) -> None: + """Clear an owner's registered debug visualization callback, if any.""" + callback_id = getattr(owner, "_debug_vis_handle", None) + if callback_id is not None: + self.remove_callback(callback_id) + owner._debug_vis_handle = None + + def remove_callback(self, callback_id: str) -> None: + """Remove a visualization marker callback if it exists.""" + self._callbacks.pop(callback_id, None) + + def dispatch_callbacks(self, event: Any = None) -> None: + """Invoke all registered visualization marker callbacks.""" + for callback in list(self._callbacks.values()): + callback(event) + + def set_group(self, group_id: str, state: Any) -> None: + """Set or replace one visualization marker group state.""" + self._groups[group_id] = state + + def remove_group(self, group_id: str) -> None: + """Remove one visualization marker group state if present.""" + self._groups.pop(group_id, None) + + def get_groups(self) -> dict[str, Any]: + """Return all active visualization marker groups.""" + return self._groups diff --git a/source/isaaclab/isaaclab/markers/visualization_markers.py b/source/isaaclab/isaaclab/markers/visualization_markers.py index 8c8504958c22..2e418bbecade 100644 --- a/source/isaaclab/isaaclab/markers/visualization_markers.py +++ b/source/isaaclab/isaaclab/markers/visualization_markers.py @@ -3,20 +3,15 @@ # # SPDX-License-Identifier: BSD-3-Clause -"""A class to coordinate groups of visual markers (such as spheres, frames or arrows) -using `UsdGeom.PointInstancer`_ class. +"""Backend-agnostic facade for coordinating groups of visual markers. -The class :class:`VisualizationMarkers` is used to create a group of visual markers and -visualize them in the viewport. The markers are represented as :class:`UsdGeom.PointInstancer` prims -in the USD stage. The markers are created as prototypes in the :class:`UsdGeom.PointInstancer` prim -and are instanced in the :class:`UsdGeom.PointInstancer` prim. The markers can be visualized by -passing the indices of the marker prototypes and their translations, orientations and scales. -The marker prototypes can be configured with the :class:`VisualizationMarkersCfg` class. - -.. _UsdGeom.PointInstancer: https://graphics.pixar.com/usd/dev/api/class_usd_geom_point_instancer.html +The :class:`VisualizationMarkers` class is used to create a group of visual +markers and visualize them through the active visualizer backends. The marker +prototypes are configured with :class:`VisualizationMarkersCfg`, and individual +marker instances can be updated by passing prototype indices and their +translations, orientations, and scales. """ -# needed to import for allowing type-hinting: np.ndarray | torch.Tensor | None from __future__ import annotations import logging @@ -24,54 +19,48 @@ import numpy as np import torch -from pxr import Gf, Sdf, Usd, UsdGeom, UsdPhysics, Vt - import isaaclab.sim as sim_utils -from isaaclab.utils.version import has_kit from .visualization_markers_cfg import VisualizationMarkersCfg -# import logger logger = logging.getLogger(__name__) class VisualizationMarkers: - """A class to coordinate groups of visual markers (loaded from USD). - - This class allows visualization of different UI markers in the scene, such as points and frames. - The class wraps around the `UsdGeom.PointInstancer`_ for efficient handling of objects - in the stage via instancing the created marker prototype prims. - - A marker prototype prim is a reusable template prim used for defining variations of objects - in the scene. For example, a sphere prim can be used as a marker prototype prim to create - multiple sphere prims in the scene at different locations. Thus, prototype prims are useful - for creating multiple instances of the same prim in the scene. - - The class parses the configuration to create different the marker prototypes into the stage. Each marker - prototype prim is created as a child of the :class:`UsdGeom.PointInstancer` prim. The prim path for the - marker prim is resolved using the key of the marker in the :attr:`VisualizationMarkersCfg.markers` - dictionary. The marker prototypes are created using the :meth:`isaaclab.sim.utils.prims.create_prim` - function, and then instanced using :class:`UsdGeom.PointInstancer` prim to allow creating multiple - instances of the marker prims. - - Switching between different marker prototypes is possible by calling the :meth:`visualize` method with - the prototype indices corresponding to the marker prototype. The prototype indices are based on the order - in the :attr:`VisualizationMarkersCfg.markers` dictionary. For example, if the dictionary has two markers, - "marker1" and "marker2", then their prototype indices are 0 and 1 respectively. The prototype indices - can be passed as a list or array of integers. + """Coordinate groups of visual markers across active visualizer backends. + + This class allows visualization of different UI markers in the scene, such + as points, frames, arrows, and shapes. Marker prototypes are reusable + templates that define variations of objects to visualize. For example, a + sphere marker prototype can be used to create many sphere marker instances + at different locations. + + The class parses the configuration to create the marker prototypes in each + active backend. The marker prototype name comes from the key in the + :attr:`VisualizationMarkersCfg.markers` dictionary, and prototype indices + are based on the dictionary order. For example, if the dictionary has two + markers, ``"marker1"`` and ``"marker2"``, their prototype indices are 0 + and 1 respectively. These indices can be passed to :meth:`visualize` as a + list or array of integers. + + Switching between marker prototypes is possible by calling + :meth:`visualize` with the corresponding prototype indices. The marker + transforms are updated only for the arguments that are provided; omitted + translations, orientations, scales, or marker indices are left unchanged + when supported by the active backend. Usage: - The following snippet shows how to create 24 sphere markers with a radius of 1.0 at random translations - within the range [-1.0, 1.0]. The first 12 markers will be colored red and the rest will be colored green. + The following snippet creates 24 sphere markers at random translations. + The first 12 markers use the first prototype and the rest use the + second prototype. .. code-block:: python + import numpy as np + import isaaclab.sim as sim_utils - from isaaclab.markers import VisualizationMarkersCfg, VisualizationMarkers + from isaaclab.markers import VisualizationMarkers, VisualizationMarkersCfg - # Create the markers configuration - # This creates two marker prototypes, "marker1" and "marker2" which are spheres with a radius of 1.0. - # The color of "marker1" is red and the color of "marker2" is green. cfg = VisualizationMarkersCfg( prim_path="/World/Visuals/testMarkers", markers={ @@ -79,48 +68,35 @@ class VisualizationMarkers: radius=1.0, visual_material=sim_utils.PreviewSurfaceCfg(diffuse_color=(1.0, 0.0, 0.0)), ), - "marker2": VisualizationMarkersCfg.SphereCfg( + "marker2": sim_utils.SphereCfg( radius=1.0, visual_material=sim_utils.PreviewSurfaceCfg(diffuse_color=(0.0, 1.0, 0.0)), ), }, ) - # Create the markers instance - # This will create a UsdGeom.PointInstancer prim at the given path along with the marker prototypes. - marker = VisualizationMarkers(cfg) - # Set position of the marker - # -- randomly sample translations between -1.0 and 1.0 + marker = VisualizationMarkers(cfg) marker_translations = np.random.uniform(-1.0, 1.0, (24, 3)) - # -- this will create 24 markers at the given translations - # note: the markers will all be `marker1` since the marker indices are not given + + # This creates 24 markers using the first prototype because marker + # indices are not given. marker.visualize(translations=marker_translations) - # alter the markers based on their prototypes indices - # first 12 markers will be marker1 and the rest will be marker2 - # 0 -> marker1, 1 -> marker2 + # 0 -> marker1, 1 -> marker2. Since translations are omitted here, + # only the marker prototypes are changed. marker_indices = [0] * 12 + [1] * 12 - # this will change the marker prototypes at the given indices - # note: the translations of the markers will not be changed from the previous call - # since the translations are not given. marker.visualize(marker_indices=marker_indices) - # alter the markers based on their prototypes indices and translations + # Update both marker prototypes and translations. marker.visualize(marker_indices=marker_indices, translations=marker_translations) - .. _UsdGeom.PointInstancer: https://graphics.pixar.com/usd/dev/api/class_usd_geom_point_instancer.html - + The public API intentionally remains the historical marker API: + :meth:`set_visibility`, :meth:`is_visible`, and :meth:`visualize`. Backend + details are delegated to Kit and Newton marker implementations. """ def __init__(self, cfg: VisualizationMarkersCfg): - """Initialize the class. - - When the class is initialized, the :class:`UsdGeom.PointInstancer` is created into the stage - and the marker prims are registered into it. - - .. note:: - If a prim already exists at the given path, the function will find the next free path - and create the :class:`UsdGeom.PointInstancer` prim there. + """Initialize visualization marker backends from the active simulation context. Args: cfg: The configuration for the markers. @@ -128,28 +104,18 @@ def __init__(self, cfg: VisualizationMarkersCfg): Raises: ValueError: When no markers are provided in the :obj:`cfg`. """ - # get next free path for the prim - prim_path = sim_utils.get_next_free_prim_path(cfg.prim_path) - # create a new prim - self.stage = sim_utils.get_current_stage() - self._instancer_manager = UsdGeom.PointInstancer.Define(self.stage, prim_path) - # store inputs - self.prim_path = prim_path + if len(cfg.markers) == 0: + raise ValueError(f"The `cfg.markers` cannot be empty. Received: {cfg.markers}") + self.cfg = cfg - # check if any markers is provided - if len(self.cfg.markers) == 0: - raise ValueError(f"The `cfg.markers` cannot be empty. Received: {self.cfg.markers}") - - # create a child prim for the marker - self._add_markers_prototypes(self.cfg.markers) - # Note: We need to do this the first time to initialize the instancer. - # Otherwise, the instancer will not be "created" and the function `GetInstanceIndices()` will fail. - self._instancer_manager.GetProtoIndicesAttr().Set(list(range(self.num_prototypes))) - self._instancer_manager.GetPositionsAttr().Set([Gf.Vec3f(0.0)] * self.num_prototypes) - self._count = self.num_prototypes + self.prim_path = cfg.prim_path + self._count = len(cfg.markers) + self._is_visible = True + self._backends: list[object] = [] + self._ensure_backends_initialized() def __str__(self) -> str: - """Return: A string representation of the class.""" + """Return a string representation of the marker group.""" msg = f"VisualizationMarkers(prim_path={self.prim_path})" msg += f"\n\tCount: {self.count}" msg += f"\n\tNumber of prototypes: {self.num_prototypes}" @@ -158,10 +124,6 @@ def __str__(self) -> str: msg += f"\n\t\t[Index: {index}]: {name}: {marker.to_dict()}" return msg - """ - Properties. - """ - @property def num_prototypes(self) -> int: """The number of marker prototypes available.""" @@ -170,35 +132,20 @@ def num_prototypes(self) -> int: @property def count(self) -> int: """The total number of marker instances.""" - # TODO: Update this when the USD API is available (Isaac Sim 2023.1) - # return self._instancer_manager.GetInstanceCount() return self._count - """ - Operations. - """ - def set_visibility(self, visible: bool): - """Sets the visibility of the markers. - - The method does this through the USD API. - - Args: - visible: flag to set the visibility. - """ - imageable = UsdGeom.Imageable(self._instancer_manager) - if visible: - imageable.MakeVisible() - else: - imageable.MakeInvisible() + """Set marker visibility for all initialized backends.""" + self._is_visible = visible + self._ensure_backends_initialized() + for backend in self._backends: + backend.set_visibility(visible) def is_visible(self) -> bool: - """Checks the visibility of the markers. - - Returns: - True if the markers are visible, False otherwise. - """ - return self._instancer_manager.GetVisibilityAttr().Get() != UsdGeom.Tokens.invisible + """Return whether the marker group is visible.""" + if self._backends: + return any(backend.is_visible() for backend in self._backends) + return self._is_visible def visualize( self, @@ -207,187 +154,158 @@ def visualize( scales: np.ndarray | torch.Tensor | None = None, marker_indices: list[int] | np.ndarray | torch.Tensor | None = None, ): - """Update markers in the viewport. + """Update markers in all initialized visualizer backends. .. note:: - If the prim `PointInstancer` is hidden in the stage, the function will simply return - without updating the markers. This helps in unnecessary computation when the markers - are not visible. - - Whenever updating the markers, the input arrays must have the same number of elements - in the first dimension. If the number of elements is different, the `UsdGeom.PointInstancer` - will raise an error complaining about the mismatch. - - Additionally, the function supports dynamic update of the markers. This means that the - number of markers can change between calls. For example, if you have 24 points that you - want to visualize, you can pass 24 translations, orientations, and scales. If you want to - visualize only 12 points, you can pass 12 translations, orientations, and scales. The - function will automatically update the number of markers in the scene. - - The function will also update the marker prototypes based on their prototype indices. For instance, - if you have two marker prototypes, and you pass the following marker indices: [0, 1, 0, 1], the function - will update the first and third markers with the first prototype, and the second and fourth markers - with the second prototype. This is useful when you want to visualize different markers in the same - scene. The list of marker indices must have the same number of elements as the translations, orientations, - or scales. If the number of elements is different, the function will raise an error. + If the markers are hidden, the function returns without updating + backend marker state. This avoids unnecessary work while debug + visualization is disabled. - .. caution:: - This function will update all the markers instanced from the prototypes. That means - if you have 24 markers, you will need to pass 24 translations, orientations, and scales. + Whenever updating the markers, the input arrays must have the same + number of elements in the first dimension. Backends generally require + all per-marker arrays to describe the same number of marker instances. + + The function supports dynamic updates of the marker count. For example, + if you have 24 points to visualize, you can pass 24 translations, + orientations, and scales. If you later want to visualize only 12 + points, you can pass arrays with 12 rows and the backends will update + the number of marker instances. - If you want to update only a subset of the markers, you will need to handle the indices - yourself and pass the complete arrays to this function. + The function also updates marker prototypes based on prototype indices. + For instance, if there are two marker prototypes and you pass marker + indices ``[0, 1, 0, 1]``, the first and third markers use the first + prototype and the second and fourth markers use the second prototype. + + .. caution:: + This function updates all markers instanced from the prototypes. If + you want to update only a subset of markers, handle the indexing + externally and pass complete arrays to this function. Args: - translations: Translations w.r.t. parent prim frame. Shape is (M, 3). - Defaults to None, which means left unchanged. - orientations: Quaternion orientations (x, y, z, w) w.r.t. parent prim frame. Shape is (M, 4). - Defaults to None, which means left unchanged. - scales: Scale applied before any rotation is applied. Shape is (M, 3). - Defaults to None, which means left unchanged. - marker_indices: Decides which marker prototype to visualize. Shape is (M). - Defaults to None, which means left unchanged provided that the total number of markers - is the same as the previous call. If the number of markers is different, the function - will update the number of markers in the scene. + translations: Translations w.r.t. parent prim frame. Shape is + (M, 3). Defaults to None, which means left unchanged. + orientations: Quaternion orientations (x, y, z, w) w.r.t. parent + prim frame. Shape is (M, 4). Defaults to None, which means left + unchanged. + scales: Scale applied before any rotation is applied. Shape is + (M, 3). Defaults to None, which means left unchanged. + marker_indices: Decides which marker prototype to visualize. Shape + is (M). Defaults to None, which means left unchanged provided + that the total number of markers is the same as the previous + call. If the number of markers is different, the function will + update the number of markers. Raises: ValueError: When input arrays do not follow the expected shapes. ValueError: When the function is called with all None arguments. """ - # check if it is visible (if not then let's not waste time) + self._ensure_backends_initialized() + # If markers are hidden, do not spend time normalizing or dispatching + # marker state to the active backends. if not self.is_visible(): return - # check if we have any markers to visualize - num_markers = 0 - # resolve inputs - # -- position - if translations is not None: - if isinstance(translations, torch.Tensor): - translations = translations.detach().cpu().numpy() - # check that shape is correct - if translations.shape[1] != 3 or len(translations.shape) != 2: - raise ValueError(f"Expected `translations` to have shape (M, 3). Received: {translations.shape}.") - # apply translations - self._instancer_manager.GetPositionsAttr().Set(Vt.Vec3fArray.FromNumpy(translations)) - # update number of markers - num_markers = translations.shape[0] - # -- orientation - if orientations is not None: - if isinstance(orientations, torch.Tensor): - orientations = orientations.detach().cpu().numpy() - # check that shape is correct - if orientations.shape[1] != 4 or len(orientations.shape) != 2: - raise ValueError(f"Expected `orientations` to have shape (M, 4). Received: {orientations.shape}.") - # apply orientations (already in xyzw format expected by USD) - self._instancer_manager.GetOrientationsAttr().Set(Vt.QuathArray.FromNumpy(orientations)) - # update number of markers - num_markers = orientations.shape[0] - # -- scales - if scales is not None: - if isinstance(scales, torch.Tensor): - scales = scales.detach().cpu().numpy() - # check that shape is correct - if scales.shape[1] != 3 or len(scales.shape) != 2: - raise ValueError(f"Expected `scales` to have shape (M, 3). Received: {scales.shape}.") - # apply scales - self._instancer_manager.GetScalesAttr().Set(Vt.Vec3fArray.FromNumpy(scales)) - # update number of markers - num_markers = scales.shape[0] - # -- status - if marker_indices is not None or num_markers != self._count: - # apply marker indices - if marker_indices is not None: - if isinstance(marker_indices, torch.Tensor): - marker_indices = marker_indices.detach().cpu().numpy() - elif isinstance(marker_indices, list): - marker_indices = np.array(marker_indices) - # check that shape is correct - if len(marker_indices.shape) != 1: - raise ValueError(f"Expected `marker_indices` to have shape (M,). Received: {marker_indices.shape}.") - # apply proto indices - self._instancer_manager.GetProtoIndicesAttr().Set(Vt.IntArray.FromNumpy(marker_indices)) - # update number of markers - num_markers = marker_indices.shape[0] - else: - # check that number of markers is not zero - if num_markers == 0: - raise ValueError("Number of markers cannot be zero! Hint: The function was called with no inputs?") - # set all markers to be the first prototype - self._instancer_manager.GetProtoIndicesAttr().Set([0] * num_markers) - # set number of markers - self._count = num_markers - - """ - Helper functions. - """ - - def _add_markers_prototypes(self, markers_cfg: dict[str, sim_utils.SpawnerCfg]): - """Adds markers prototypes to the scene and sets the markers instancer to use them.""" - # add markers based on config - for name, cfg in markers_cfg.items(): - # resolve prim path - marker_prim_path = f"{self.prim_path}/{name}" - # create a child prim for the marker - marker_prim = cfg.func(prim_path=marker_prim_path, cfg=cfg) - # make the asset uninstanceable (in case it is) - # point instancer defines its own prototypes so if an asset is already instanced, this doesn't work. - self._process_prototype_prim(marker_prim) - # add child reference to point instancer - self._instancer_manager.GetPrototypesRel().AddTarget(marker_prim_path) - # check that we loaded all the prototypes - prototypes = self._instancer_manager.GetPrototypesRel().GetTargets() - if len(prototypes) != len(markers_cfg): - raise RuntimeError( - f"Failed to load all the prototypes. Expected: {len(markers_cfg)}. Received: {len(prototypes)}." - ) - def _process_prototype_prim(self, prim: Usd.Prim): - """Process a prim and its descendants to make them suitable for defining prototypes. + norm_translations = self._to_tensor(translations, expected_width=3, name="translations") + norm_orientations = self._to_tensor(orientations, expected_width=4, name="orientations") + norm_scales = self._to_tensor(scales, expected_width=3, name="scales") + norm_marker_indices = self._to_index_tensor(marker_indices) + target_device = self._resolve_target_device( + norm_translations, norm_orientations, norm_scales, norm_marker_indices + ) + if norm_translations is not None: + norm_translations = norm_translations.to(device=target_device) + if norm_orientations is not None: + norm_orientations = norm_orientations.to(device=target_device) + if norm_scales is not None: + norm_scales = norm_scales.to(device=target_device) + if norm_marker_indices is not None: + norm_marker_indices = norm_marker_indices.to(device=target_device) - Point instancer defines its own prototypes so if an asset is already instanced, this doesn't work. - This function checks if the prim at the specified prim path and its descendants are instanced. - If so, it makes the respective prim uninstanceable by disabling instancing on the prim. - - Additionally, it makes the prim invisible to secondary rays. This is useful when we do not want - to see the marker prims on camera images. + num_markers = 0 + for value in (norm_translations, norm_orientations, norm_scales, norm_marker_indices): + if value is not None: + num_markers = value.shape[0] + + if norm_marker_indices is None and num_markers != 0 and num_markers != self._count: + norm_marker_indices = torch.zeros(num_markers, dtype=torch.int32, device=target_device) + elif norm_marker_indices is None and num_markers == 0: + if all(value is None for value in (norm_translations, norm_orientations, norm_scales)): + raise ValueError("Number of markers cannot be zero! Hint: The function was called with no inputs?") + num_markers = self._count + + for backend in self._backends: + backend.visualize(norm_translations, norm_orientations, norm_scales, norm_marker_indices) + + if num_markers != 0: + self._count = num_markers + + def __del__(self): + for backend in getattr(self, "_backends", []): + if hasattr(backend, "close"): + backend.close() + + def _ensure_backends_initialized(self) -> None: + sim = sim_utils.SimulationContext.instance() + if sim is None: + self._ensure_kit_backend() + return - Args: - prim: The prim to check. - """ - # check if prim is valid - if not prim.IsValid(): - raise ValueError(f"Prim at path '{prim.GetPrimAtPath()}' is not valid.") - # iterate over all prims under prim-path - all_prims = [prim] - while len(all_prims) > 0: - # get current prim - child_prim = all_prims.pop(0) - # check if it is physics body -> if so, remove it - if child_prim.HasAPI(UsdPhysics.ArticulationRootAPI): - child_prim.RemoveAPI(UsdPhysics.ArticulationRootAPI) - child_prim.RemoveAppliedSchema("PhysxArticulationAPI") - if child_prim.HasAPI(UsdPhysics.RigidBodyAPI): - child_prim.RemoveAPI(UsdPhysics.RigidBodyAPI) - child_prim.RemoveAppliedSchema("PhysxRigidBodyAPI") - if child_prim.IsA(UsdPhysics.Joint): - child_prim.GetAttribute("physics:jointEnabled").Set(False) - # check if prim is instanced -> if so, make it uninstanceable - if child_prim.IsInstance(): - child_prim.SetInstanceable(False) - # check if prim is a mesh -> if so, make it invisible to secondary rays - if child_prim.IsA(UsdGeom.Gprim): - # invisible to secondary rays such as depth images - sim_utils.change_prim_property( - prop_path=f"{child_prim.GetPrimPath().pathString}.primvars:invisibleToSecondaryRays", - value=True, - stage=prim.GetStage(), - type_to_create_if_not_exist=Sdf.ValueTypeNames.Bool, - ) - # add children to list - all_prims += child_prim.GetChildren() - - # remove any physics on the markers because they are only for visualization! - if has_kit(): - import omni.physx.scripts.utils as physx_utils - - physx_utils.removeRigidBodySubtree(prim) + if any(viz.supports_markers() and viz.pumps_app_update() and viz.cfg.enable_markers for viz in sim.visualizers): + self._ensure_kit_backend() + if any( + viz.supports_markers() and not viz.pumps_app_update() and viz.cfg.enable_markers for viz in sim.visualizers + ): + self._ensure_newton_backend() + + def _ensure_kit_backend(self) -> None: + """Create the Kit marker backend if it is not already active.""" + from isaaclab_visualizers.kit.kit_visualization_markers import KitVisualizationMarkers + + if not any(isinstance(backend, KitVisualizationMarkers) for backend in self._backends): + self._backends.append(KitVisualizationMarkers(self.cfg, visible=self._is_visible)) + + def _ensure_newton_backend(self) -> None: + """Create the Newton-family marker backend if it is not already active.""" + from isaaclab_visualizers.newton.newton_visualization_markers import NewtonVisualizationMarkers + + if not any(isinstance(backend, NewtonVisualizationMarkers) for backend in self._backends): + self._backends.append(NewtonVisualizationMarkers(self.cfg, visible=self._is_visible)) + + def _resolve_target_device(self, *values: torch.Tensor | None) -> torch.device: + for value in values: + if value is not None: + return value.device + for backend in self._backends: + if hasattr(backend, "infer_device"): + return backend.infer_device() + return torch.device("cpu") + + @staticmethod + def _to_tensor( + value: np.ndarray | torch.Tensor | None, + expected_width: int, + name: str, + ) -> torch.Tensor | None: + if value is None: + return None + if isinstance(value, np.ndarray): + tensor = torch.from_numpy(value) + else: + tensor = value.detach() + if tensor.ndim != 2 or tensor.shape[1] != expected_width: + raise ValueError(f"Expected `{name}` to have shape (M, {expected_width}). Received: {tuple(tensor.shape)}.") + return tensor.to(dtype=torch.float32) + + @staticmethod + def _to_index_tensor(value: list[int] | np.ndarray | torch.Tensor | None) -> torch.Tensor | None: + if value is None: + return None + if isinstance(value, list): + tensor = torch.tensor(value) + elif isinstance(value, np.ndarray): + tensor = torch.from_numpy(value) + else: + tensor = value.detach() + if tensor.ndim != 1: + raise ValueError(f"Expected `marker_indices` to have shape (M,). Received: {tuple(tensor.shape)}.") + return tensor.to(dtype=torch.int32) diff --git a/source/isaaclab/isaaclab/sensors/sensor_base.py b/source/isaaclab/isaaclab/sensors/sensor_base.py index 3b15d8a0171e..728a708b4448 100644 --- a/source/isaaclab/isaaclab/sensors/sensor_base.py +++ b/source/isaaclab/isaaclab/sensors/sensor_base.py @@ -23,7 +23,6 @@ import isaaclab.sim as sim_utils from isaaclab.physics import PhysicsEvent, PhysicsManager -from isaaclab.utils.version import has_kit from .kernels import reset_envs_kernel, update_outdated_envs_kernel, update_timestamp_kernel @@ -151,17 +150,15 @@ def set_debug_vis(self, debug_vis: bool) -> bool: if debug_vis: # create a subscriber for the post update event if it doesn't exist if self._debug_vis_handle is None: - if has_kit(): - import omni.kit.app # noqa: PLC0415 - - app_interface = omni.kit.app.get_app_interface() - self._debug_vis_handle = app_interface.get_post_update_event_stream().create_subscription_to_pop( - lambda event, obj=weakref.proxy(self): obj._debug_vis_callback(event) - ) + sim_ctx = sim_utils.SimulationContext.instance() + if sim_ctx is not None: + self._debug_vis_handle = sim_ctx.vis_marker_registry.add_debug_vis_callback(self) else: # remove the subscriber if it exists - if self._debug_vis_handle is not None: - self._debug_vis_handle.unsubscribe() + sim_ctx = sim_utils.SimulationContext.instance() + if sim_ctx is not None: + sim_ctx.vis_marker_registry.clear_debug_vis_callback(self) + else: self._debug_vis_handle = None # return success return True @@ -323,8 +320,10 @@ def _initialize_callback(self, event): def _invalidate_initialize_callback(self, event): """Invalidates the scene elements.""" self._is_initialized = False - if self._debug_vis_handle is not None: - self._debug_vis_handle.unsubscribe() + sim_ctx = sim_utils.SimulationContext.instance() + if sim_ctx is not None: + sim_ctx.vis_marker_registry.clear_debug_vis_callback(self) + else: self._debug_vis_handle = None def _on_prim_deletion(self, event) -> None: @@ -358,8 +357,10 @@ def _clear_callbacks(self) -> None: self._prim_deletion_handle.deregister() self._prim_deletion_handle = None # Clear debug visualization - if self._debug_vis_handle is not None: - self._debug_vis_handle.unsubscribe() + sim_ctx = sim_utils.SimulationContext.instance() + if sim_ctx is not None: + sim_ctx.vis_marker_registry.clear_debug_vis_callback(self) + else: self._debug_vis_handle = None """ diff --git a/source/isaaclab/isaaclab/sim/simulation_context.py b/source/isaaclab/isaaclab/sim/simulation_context.py index 89be3163359f..d5ef6f64e9c5 100644 --- a/source/isaaclab/isaaclab/sim/simulation_context.py +++ b/source/isaaclab/isaaclab/sim/simulation_context.py @@ -22,6 +22,7 @@ import isaaclab.sim.utils.stage as stage_utils from isaaclab.app.settings_manager import SettingsManager from isaaclab.envs.utils.recording_hooks import run_recording_hooks_after_visualizers +from isaaclab.markers.vis_marker_registry import VisMarkerRegistry from isaaclab.physics import BaseSceneDataProvider, PhysicsManager, SceneDataProvider from isaaclab.physics.scene_data_requirements import ( SceneDataRequirement, @@ -191,6 +192,7 @@ def __init__(self, cfg: SimulationCfg | None = None): self._xr_enabled = bool(self.get_setting("/isaaclab/xr/enabled")) # Note: has_rtx_sensors is NOT cached because it changes when Camera sensors are created self._pending_camera_view: tuple[tuple[float, float, float], tuple[float, float, float]] | None = None + self.vis_marker_registry = VisMarkerRegistry() # Simulation state self._is_playing = False @@ -753,6 +755,11 @@ def update_visualizers(self, dt: float, skip_app_pumping: bool = False) -> None: self.update_scene_data_provider() + # Marker callbacks update VisualizationMarkers state; visualizer step() + # consumes that state later in this method. + if any(viz.supports_markers() for viz in self._visualizers): + self.vis_marker_registry.dispatch_callbacks() + visualizers_to_remove = [] for viz in self._visualizers: try: diff --git a/source/isaaclab/test/sim/test_simulation_context_visualizers.py b/source/isaaclab/test/sim/test_simulation_context_visualizers.py index 1f86f32872c9..3b7ca93dcfa3 100644 --- a/source/isaaclab/test/sim/test_simulation_context_visualizers.py +++ b/source/isaaclab/test/sim/test_simulation_context_visualizers.py @@ -7,14 +7,21 @@ from __future__ import annotations +import sys from typing import Any, cast +import isaaclab_visualizers.kit.kit_visualizer as kit_visualizer +import isaaclab_visualizers.newton.newton_visualization_markers as newton_markers import isaaclab_visualizers.rerun.rerun_visualizer as rerun_visualizer import isaaclab_visualizers.viser.viser_visualizer as viser_visualizer +import numpy as np import pytest +import torch +from isaaclab_visualizers.kit.kit_visualizer_cfg import KitVisualizerCfg from isaaclab_visualizers.rerun.rerun_visualizer_cfg import RerunVisualizerCfg from isaaclab_visualizers.viser.viser_visualizer_cfg import ViserVisualizerCfg +from isaaclab.markers.vis_marker_registry import VisMarkerRegistry from isaaclab.sim.simulation_context import SimulationContext @@ -94,6 +101,9 @@ def requires_forward_before_step(self): def pumps_app_update(self): return self._pumps_app_update + def supports_markers(self): + return False + def _make_context(visualizers, provider=None): ctx = object.__new__(SimulationContext) @@ -168,6 +178,26 @@ def test_update_visualizers_handles_training_pause_loop(): assert viz.step_calls == [0.0, 0.2] +def test_vis_marker_registry_dispatch_allows_callback_mutation(): + registry = VisMarkerRegistry() + calls = [] + + def _remove_other_callback(event): + calls.append(("remove_other", event)) + registry.remove_callback("other") + + def _other_callback(event): + calls.append(("other", event)) + + registry.add_callback("remove_other", _remove_other_callback) + registry.add_callback("other", _other_callback) + + registry.dispatch_callbacks("tick") + + assert calls == [("remove_other", "tick"), ("other", "tick")] + assert "other" not in registry._callbacks + + class _DummyViserSceneDataProvider: def __init__(self): self._metadata = {"num_envs": 4} @@ -229,6 +259,214 @@ def _fake_create_viewer(self, record_to_viser: str | None, metadata: dict | None assert viewer.calls[2] == ("end_frame",) +def test_viser_visualizer_marker_render_failure_does_not_interrupt_state_updates( + monkeypatch: pytest.MonkeyPatch, caplog: pytest.LogCaptureFixture +): + provider = _DummyViserSceneDataProvider() + viewer = _DummyViserViewer() + marker_calls = [] + + def _fake_create_viewer(self, record_to_viser: str | None, metadata: dict | None = None): + self._viewer = viewer + + def _raise_marker_render(*args, **kwargs): + marker_calls.append((args, kwargs)) + raise RuntimeError("marker overlay failed") + + monkeypatch.setattr(viser_visualizer.ViserVisualizer, "_create_viewer", _fake_create_viewer) + monkeypatch.setattr(viser_visualizer, "render_newton_visualization_markers", _raise_marker_render) + + visualizer = viser_visualizer.ViserVisualizer(ViserVisualizerCfg()) + visualizer.initialize(cast(Any, provider)) + + with caplog.at_level("WARNING"): + visualizer.step(0.25) + + assert marker_calls + assert viewer.calls[0][0] == "begin_frame" + assert viewer.calls[1] == ("log_state", {"state_call": 2}) + assert viewer.calls[2] == ("end_frame",) + assert "Marker rendering failed; continuing body updates" in caplog.text + + +def test_newton_marker_mesh_registration_is_per_viewer(monkeypatch: pytest.MonkeyPatch): + marker = object.__new__(newton_markers.NewtonVisualizationMarkers) + marker._registered_meshes = set() + + class _FakeMesh: + vertices = np.zeros((1, 3), dtype=np.float32) + indices = np.zeros((3,), dtype=np.int32) + normals = np.zeros((0, 3), dtype=np.float32) + uvs = np.zeros((0, 2), dtype=np.float32) + + class _FakeViewer: + def __init__(self): + self.meshes = [] + + def log_mesh(self, name, vertices, indices, **kwargs): + self.meshes.append((name, vertices, indices, kwargs)) + + monkeypatch.setattr(newton_markers, "_create_mesh", lambda cfg: _FakeMesh()) + monkeypatch.setattr(newton_markers.wp, "array", lambda value, dtype=None: value) + + spec = newton_markers._NewtonMarkerSpec(renderer="mesh", mesh_type="box", mesh_params={"size": (1.0, 1.0, 1.0)}) + viewer_a = _FakeViewer() + viewer_b = _FakeViewer() + + marker._ensure_mesh_registered(viewer_a, "/Visuals/marker/meshes/arrow", spec) + marker._ensure_mesh_registered(viewer_a, "/Visuals/marker/meshes/arrow", spec) + marker._ensure_mesh_registered(viewer_b, "/Visuals/marker/meshes/arrow", spec) + + assert len(viewer_a.meshes) == 1 + assert len(viewer_b.meshes) == 1 + + +class _FakeNewtonMarkerMesh: + vertices = np.zeros((1, 3), dtype=np.float32) + indices = np.zeros((3,), dtype=np.int32) + normals = np.zeros((0, 3), dtype=np.float32) + uvs = np.zeros((0, 2), dtype=np.float32) + + +class _FakeNewtonMarkerViewer: + def __init__(self): + self.meshes = [] + self.instances = [] + self.lines = [] + + def log_mesh(self, name, vertices, indices, **kwargs): + self.meshes.append((name, vertices, indices, kwargs)) + + def log_instances(self, batch_name, mesh_name, xforms, scales, colors, materials, hidden=False): + self.instances.append( + { + "batch_name": batch_name, + "mesh_name": mesh_name, + "xforms": xforms, + "scales": scales, + "colors": colors, + "materials": materials, + "hidden": hidden, + } + ) + + def log_lines(self, batch_name, starts, ends, colors, width=None, hidden=False): + self.lines.append( + { + "batch_name": batch_name, + "starts": starts, + "ends": ends, + "colors": colors, + "width": width, + "hidden": hidden, + } + ) + + +def _make_newton_marker_for_render( + *, + marker_names: list[str], + translations: torch.Tensor, + marker_indices: torch.Tensor | None = None, + visible: bool = True, +): + marker = object.__new__(newton_markers.NewtonVisualizationMarkers) + marker_cfg_type = type("MarkerCfg", (), {"visual_material": None}) + marker.cfg = type("Cfg", (), {"markers": {name: marker_cfg_type() for name in marker_names}})() + marker.group_id = "/Visuals/marker::test" + marker.visible = visible + marker.translations = translations + marker.orientations = torch.tensor([[0.0, 0.0, 0.0, 1.0]], dtype=torch.float32).repeat(translations.shape[0], 1) + marker.scales = torch.ones((translations.shape[0], 3), dtype=torch.float32) + marker.marker_indices = marker_indices + marker.count = translations.shape[0] + marker._registered_meshes = set() + marker._warned_unsupported = set() + return marker + + +def _patch_newton_marker_render_deps(monkeypatch: pytest.MonkeyPatch) -> None: + specs = { + "arrow": newton_markers._NewtonMarkerSpec( + renderer="mesh", + mesh_type="box", + mesh_params={"size": (1.0, 1.0, 1.0)}, + color=(1.0, 1.0, 1.0), + texture=np.zeros((2, 2, 3), dtype=np.uint8), + ), + "sphere": newton_markers._NewtonMarkerSpec(renderer="mesh", mesh_type="sphere", mesh_params={"radius": 1.0}), + "frame": newton_markers._NewtonMarkerSpec(renderer="frame"), + } + + monkeypatch.setattr(newton_markers, "_create_mesh", lambda cfg: _FakeNewtonMarkerMesh()) + monkeypatch.setattr(newton_markers.wp, "array", lambda value, dtype=None: value) + monkeypatch.setattr(newton_markers, "_resolve_newton_marker_cfg", lambda name, marker_cfg, cfg: specs[name]) + + +def test_newton_marker_render_filters_visible_envs(monkeypatch: pytest.MonkeyPatch): + _patch_newton_marker_render_deps(monkeypatch) + translations = torch.arange(8, dtype=torch.float32).unsqueeze(1).repeat(1, 3) + marker = _make_newton_marker_for_render( + marker_names=["arrow"], + translations=translations, + marker_indices=torch.zeros(8, dtype=torch.int32), + ) + viewer = _FakeNewtonMarkerViewer() + + marker.render(viewer, visible_env_ids=[1, 3], num_envs=4) + + assert len(viewer.instances) == 1 + assert viewer.instances[0]["hidden"] is False + assert viewer.instances[0]["xforms"][:, 0].tolist() == [1.0, 3.0, 5.0, 7.0] + + +def test_newton_marker_render_routes_instances_by_prototype(monkeypatch: pytest.MonkeyPatch): + _patch_newton_marker_render_deps(monkeypatch) + translations = torch.arange(4, dtype=torch.float32).unsqueeze(1).repeat(1, 3) + marker = _make_newton_marker_for_render( + marker_names=["arrow", "sphere"], + translations=translations, + marker_indices=torch.tensor([0, 1, 0, 1], dtype=torch.int32), + ) + viewer = _FakeNewtonMarkerViewer() + + marker.render(viewer, visible_env_ids=None, num_envs=4) + + visible_instances = [call for call in viewer.instances if not call["hidden"]] + assert [call["batch_name"] for call in visible_instances] == [ + "/Visuals/marker::test/arrow", + "/Visuals/marker::test/sphere", + ] + assert [call["xforms"].shape[0] for call in visible_instances] == [2, 2] + assert visible_instances[0]["materials"][:, 3].tolist() == [1.0, 1.0] + assert visible_instances[1]["materials"][:, 3].tolist() == [0.0, 0.0] + + +def test_newton_marker_render_hides_unselected_prototypes(monkeypatch: pytest.MonkeyPatch): + _patch_newton_marker_render_deps(monkeypatch) + marker = _make_newton_marker_for_render( + marker_names=["arrow", "sphere", "frame"], + translations=torch.zeros((3, 3), dtype=torch.float32), + marker_indices=torch.zeros(3, dtype=torch.int32), + ) + viewer = _FakeNewtonMarkerViewer() + + marker.render(viewer, visible_env_ids=None, num_envs=3) + + hidden_instances = [call for call in viewer.instances if call["hidden"]] + assert [call["batch_name"] for call in hidden_instances] == ["/Visuals/marker::test/sphere"] + assert viewer.lines == [ + { + "batch_name": "/Visuals/marker::test/frame", + "starts": None, + "ends": None, + "colors": None, + "width": None, + "hidden": True, + } + ] + + @pytest.mark.parametrize( ("cfg_max_visible_envs", "expected_visible"), [ @@ -385,6 +623,112 @@ def get_camera_transforms(self): assert captured["set_world_offsets"] == (0.0, 0.0, 0.0) +def test_rerun_visualizer_marker_failure_still_ends_frame(monkeypatch: pytest.MonkeyPatch): + class _FakeRerunViewer: + def __init__(self): + self.calls = [] + + def is_paused(self): + return False + + def begin_frame(self, sim_time): + self.calls.append(("begin_frame", sim_time)) + + def log_state(self, state): + self.calls.append(("log_state", state)) + + def end_frame(self): + self.calls.append(("end_frame",)) + + class _DummyRerunSceneDataProvider: + def get_metadata(self) -> dict: + return {"num_envs": 4} + + def get_newton_state(self): + return {"ok": True} + + def get_camera_transforms(self): + return {} + + def _raise_marker_render(*args, **kwargs): + raise RuntimeError("marker render failed") + + monkeypatch.setattr(rerun_visualizer, "render_newton_visualization_markers", _raise_marker_render) + + visualizer = rerun_visualizer.RerunVisualizer(RerunVisualizerCfg()) + viewer = _FakeRerunViewer() + visualizer._is_initialized = True + visualizer._is_closed = False + visualizer._viewer = viewer + visualizer._scene_data_provider = _DummyRerunSceneDataProvider() + visualizer._resolved_visible_env_ids = None + + with pytest.raises(RuntimeError, match="marker render failed"): + visualizer.step(0.25) + + assert [call[0] for call in viewer.calls] == ["begin_frame", "log_state", "end_frame"] + + +def test_kit_visualizer_default_camera_source_does_not_require_camera_prim(monkeypatch: pytest.MonkeyPatch): + """Default ``--viz kit`` should work for envs without a camera prim.""" + + class _FakeViewportApi: + def __init__(self): + self.set_active_camera_calls = [] + + def get_active_camera(self): + return "/OmniverseKit_Persp" + + def set_active_camera(self, camera_path): + self.set_active_camera_calls.append(camera_path) + + class _FakeViewportWindow: + def __init__(self): + self.viewport_api = _FakeViewportApi() + + class _FakeStage: + def GetPrimAtPath(self, path): + raise AssertionError(f"default Kit visualizer should not look up camera prims: {path}") + + class _FakeProvider: + def get_usd_stage(self): + return _FakeStage() + + viewport_window = _FakeViewportWindow() + viewport_utility = type( + "ViewportUtility", + (), + { + "create_viewport_window": staticmethod(lambda **kwargs: viewport_window), + "get_active_viewport_window": staticmethod(lambda: viewport_window), + }, + ) + monkeypatch.setitem(sys.modules, "omni", type(sys)("omni")) + monkeypatch.setitem(sys.modules, "omni.kit", type(sys)("omni.kit")) + monkeypatch.setitem(sys.modules, "omni.kit.viewport", type(sys)("omni.kit.viewport")) + monkeypatch.setitem(sys.modules, "omni.kit.viewport.utility", viewport_utility) + monkeypatch.setitem(sys.modules, "omni.ui", type("OmniUi", (), {"DockPosition": object})()) + + applied_camera_poses = [] + monkeypatch.setattr( + kit_visualizer.KitVisualizer, + "_set_viewport_camera", + lambda self, eye, target: applied_camera_poses.append((tuple(eye), tuple(target))), + ) + + cfg = KitVisualizerCfg() + visualizer = kit_visualizer.KitVisualizer(cfg) + visualizer._scene_data_provider = _FakeProvider() + visualizer._runtime_headless = False + + visualizer._setup_viewport() + + assert cfg.cam_source == "cfg" + assert applied_camera_poses == [(cfg.eye, cfg.lookat)] + assert viewport_window.viewport_api.set_active_camera_calls == [] + assert visualizer._controlled_camera_path == "/OmniverseKit_Persp" + + def test_get_cli_visualizer_types_handles_non_string_setting_without_crashing(): ctx = object.__new__(SimulationContext) ctx.get_setting = lambda name: {"types": "newton,kit"} if name == "/isaaclab/visualizer/types" else None diff --git a/source/isaaclab_visualizers/isaaclab_visualizers/kit/kit_visualization_markers.py b/source/isaaclab_visualizers/isaaclab_visualizers/kit/kit_visualization_markers.py new file mode 100644 index 000000000000..c9f55b413e03 --- /dev/null +++ b/source/isaaclab_visualizers/isaaclab_visualizers/kit/kit_visualization_markers.py @@ -0,0 +1,221 @@ +# Copyright (c) 2022-2026, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md). +# All rights reserved. +# +# SPDX-License-Identifier: BSD-3-Clause + +"""Kit/USD implementation for :class:`VisualizationMarkers`. + +This backend represents markers as :class:`UsdGeom.PointInstancer` prims in the +USD stage. Marker prototypes are created as child prims of the point instancer +and are instanced efficiently through prototype indices. + +.. _UsdGeom.PointInstancer: https://graphics.pixar.com/usd/dev/api/class_usd_geom_point_instancer.html +""" + +from __future__ import annotations + +import logging + +import torch + +import isaaclab.sim as sim_utils +from isaaclab.markers.visualization_markers_cfg import VisualizationMarkersCfg +from isaaclab.utils.version import has_kit + +logger = logging.getLogger(__name__) + + +class KitVisualizationMarkers: + """USD PointInstancer backend for visualization markers. + + This class wraps around the `UsdGeom.PointInstancer`_ for efficient + handling of objects in the USD stage by instancing the created marker + prototype prims. + + A marker prototype prim is a reusable template prim used for defining + variations of objects in the scene. For example, a sphere prim can be used + as a marker prototype prim to create multiple sphere prims at different + locations. The marker prim path is resolved using the marker name from the + :attr:`VisualizationMarkersCfg.markers` dictionary. + + .. _UsdGeom.PointInstancer: https://graphics.pixar.com/usd/dev/api/class_usd_geom_point_instancer.html + """ + + def __init__(self, cfg: VisualizationMarkersCfg, visible: bool = True): + """Initialize the USD point instancer and register marker prototypes. + + When this backend is initialized, the :class:`UsdGeom.PointInstancer` + is created in the stage and the marker prims are registered into it. + + .. note:: + If a prim already exists at the requested path, the next free path + is used for the :class:`UsdGeom.PointInstancer` prim. + """ + self.cfg = cfg + self.stage = sim_utils.get_current_stage() + # Resolve the next free prim path before creating the point instancer. + self.prim_path = sim_utils.get_next_free_prim_path(cfg.prim_path) + self._is_visible = visible + self._count = len(cfg.markers) + + from pxr import Gf, UsdGeom # noqa: PLC0415 + + self._instancer_manager = UsdGeom.PointInstancer.Define(self.stage, self.prim_path) + self._add_markers_prototypes(self.cfg.markers) + # Note: We need to do this the first time to initialize the instancer. + # Otherwise, the instancer is not fully "created" and USD instance + # queries such as GetInstanceIndices() can fail. + self._instancer_manager.GetProtoIndicesAttr().Set(list(range(len(self.cfg.markers)))) + self._instancer_manager.GetPositionsAttr().Set([Gf.Vec3f(0.0)] * len(self.cfg.markers)) + self.set_visibility(visible) + + @property + def count(self) -> int: + return self._count + + def set_visibility(self, visible: bool) -> None: + """Set USD PointInstancer visibility. + + The method does this through the USD API. + """ + from pxr import UsdGeom # noqa: PLC0415 + + self._is_visible = visible + imageable = UsdGeom.Imageable(self._instancer_manager) + if visible: + imageable.MakeVisible() + else: + imageable.MakeInvisible() + + def is_visible(self) -> bool: + """Return USD PointInstancer visibility.""" + from pxr import UsdGeom # noqa: PLC0415 + + return self._instancer_manager.GetVisibilityAttr().Get() != UsdGeom.Tokens.invisible + + def visualize( + self, + translations: torch.Tensor | None, + orientations: torch.Tensor | None, + scales: torch.Tensor | None, + marker_indices: torch.Tensor | None, + ) -> None: + """Write marker transforms to USD PointInstancer attributes. + + Args: + translations: Translations w.r.t. parent prim frame. Shape is + (M, 3). + orientations: Quaternion orientations (x, y, z, w) w.r.t. parent + prim frame. Shape is (M, 4). + scales: Scale applied before any rotation is applied. Shape is + (M, 3). + marker_indices: Decides which marker prototype to visualize. Shape + is (M). + """ + from pxr import Vt # noqa: PLC0415 + + num_markers = 0 + if translations is not None: + translations_np = translations.detach().cpu().numpy() + # Apply translations. + self._instancer_manager.GetPositionsAttr().Set(Vt.Vec3fArray.FromNumpy(translations_np)) + num_markers = translations_np.shape[0] + if orientations is not None: + orientations_np = orientations.detach().cpu().numpy() + # Apply orientations. USD expects quaternion data in xyzw format. + self._instancer_manager.GetOrientationsAttr().Set(Vt.QuathArray.FromNumpy(orientations_np)) + num_markers = orientations_np.shape[0] + if scales is not None: + scales_np = scales.detach().cpu().numpy() + # Apply scales. + self._instancer_manager.GetScalesAttr().Set(Vt.Vec3fArray.FromNumpy(scales_np)) + num_markers = scales_np.shape[0] + if marker_indices is not None or num_markers != self._count: + if marker_indices is not None: + marker_indices_np = marker_indices.detach().cpu().numpy() + # Apply prototype indices. + self._instancer_manager.GetProtoIndicesAttr().Set(Vt.IntArray.FromNumpy(marker_indices_np)) + num_markers = marker_indices_np.shape[0] + elif num_markers != 0: + # Set all markers to the first prototype when the marker count + # changes and explicit marker indices are not provided. + self._instancer_manager.GetProtoIndicesAttr().Set([0] * num_markers) + if num_markers != 0: + self._count = num_markers + + def _add_markers_prototypes(self, markers_cfg: dict[str, sim_utils.SpawnerCfg]) -> None: + """Add marker prototypes to the scene and register them with the point instancer.""" + # Add markers based on config. + for name, cfg in markers_cfg.items(): + # Resolve prim path from the marker name. + marker_prim_path = f"{self.prim_path}/{name}" + # Create a child prim for the marker. + marker_prim = cfg.func(prim_path=marker_prim_path, cfg=cfg) + # Make the asset uninstanceable in case it is already instanced. + # Point instancer defines its own prototypes, so already-instanced + # assets cannot be used directly. + self._process_prototype_prim(marker_prim) + # Add child reference to point instancer. + self._instancer_manager.GetPrototypesRel().AddTarget(marker_prim_path) + + # Check that all prototypes were loaded. + prototypes = self._instancer_manager.GetPrototypesRel().GetTargets() + if len(prototypes) != len(markers_cfg): + raise RuntimeError( + f"Failed to load all the prototypes. Expected: {len(markers_cfg)}. Received: {len(prototypes)}." + ) + + def _process_prototype_prim(self, prim) -> None: + """Process a prim and its descendants to make them suitable for prototypes. + + Point instancer defines its own prototypes, so if an asset is already + instanced, this does not work. This function checks if the prim and its + descendants are instanced. If so, it makes the respective prim + uninstanceable by disabling instancing on the prim. + + Additionally, it makes the prim invisible to secondary rays. This is + useful when marker prims should not appear in camera images. + + Args: + prim: The prim to process. + """ + from pxr import Sdf, UsdGeom, UsdPhysics # noqa: PLC0415 + + if not prim.IsValid(): + raise ValueError(f"Prim at path '{prim.GetPrimAtPath()}' is not valid.") + + # Iterate over all prims under the marker prim path. + all_prims = [prim] + while len(all_prims) > 0: + child_prim = all_prims.pop(0) + # Remove physics from marker prototypes because they are only for + # visualization. + if child_prim.HasAPI(UsdPhysics.ArticulationRootAPI): + child_prim.RemoveAPI(UsdPhysics.ArticulationRootAPI) + child_prim.RemoveAppliedSchema("PhysxArticulationAPI") + if child_prim.HasAPI(UsdPhysics.RigidBodyAPI): + child_prim.RemoveAPI(UsdPhysics.RigidBodyAPI) + child_prim.RemoveAppliedSchema("PhysxRigidBodyAPI") + if child_prim.IsA(UsdPhysics.Joint): + child_prim.GetAttribute("physics:jointEnabled").Set(False) + # Point instancer defines its own instancing, so nested instances + # must be made uninstanceable. + if child_prim.IsInstance(): + child_prim.SetInstanceable(False) + # Make renderable prims invisible to secondary rays such as depth + # images. + if child_prim.IsA(UsdGeom.Gprim): + sim_utils.change_prim_property( + prop_path=f"{child_prim.GetPrimPath().pathString}.primvars:invisibleToSecondaryRays", + value=True, + stage=prim.GetStage(), + type_to_create_if_not_exist=Sdf.ValueTypeNames.Bool, + ) + all_prims += child_prim.GetChildren() + + # Remove any remaining physics on the markers because they are only for + # visualization. + if has_kit(): + import omni.physx.scripts.utils as physx_utils # noqa: PLC0415 + + physx_utils.removeRigidBodySubtree(prim) diff --git a/source/isaaclab_visualizers/isaaclab_visualizers/kit/kit_visualizer.py b/source/isaaclab_visualizers/isaaclab_visualizers/kit/kit_visualizer.py index ced2935897ae..701a21c79984 100644 --- a/source/isaaclab_visualizers/isaaclab_visualizers/kit/kit_visualizer.py +++ b/source/isaaclab_visualizers/isaaclab_visualizers/kit/kit_visualizer.py @@ -172,7 +172,7 @@ def is_training_paused(self) -> bool: def supports_markers(self) -> bool: """Kit viewport supports marker visualization through Omni UI rendering.""" - return True + return bool(self.cfg.enable_markers) def supports_live_plots(self) -> bool: """Kit backend can host live plot widgets via viewport UI panels.""" diff --git a/source/isaaclab_visualizers/isaaclab_visualizers/newton/newton_visualization_markers.py b/source/isaaclab_visualizers/isaaclab_visualizers/newton/newton_visualization_markers.py new file mode 100644 index 000000000000..9d222ed71a61 --- /dev/null +++ b/source/isaaclab_visualizers/isaaclab_visualizers/newton/newton_visualization_markers.py @@ -0,0 +1,531 @@ +# Copyright (c) 2022-2026, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md). +# All rights reserved. +# +# SPDX-License-Identifier: BSD-3-Clause + +"""Newton-family implementation for :class:`VisualizationMarkers`.""" + +from __future__ import annotations + +import logging +from dataclasses import dataclass +from typing import Any, Literal + +import numpy as np +import torch +import warp as wp +from newton import Axis, Mesh + +import isaaclab.sim as sim_utils +from isaaclab.markers.visualization_markers_cfg import VisualizationMarkersCfg +from isaaclab.utils.assets import ISAAC_NUCLEUS_DIR +from isaaclab.utils.math import quat_apply + +logger = logging.getLogger(__name__) + +_OMNIPBR_DEFAULTS = { + "diffuse_color_constant": (0.2, 0.2, 0.2), + "diffuse_tint": (1.0, 1.0, 1.0), +} +_UNBOUND_DEFAULT_FALLBACK_GRAY = (0.18, 0.18, 0.18) +_DEX_CUBE_TEXTURE_URL = f"{ISAAC_NUCLEUS_DIR}/Props/Blocks/DexCube/Materials/dex_cube_mod.png" + + +@dataclass(frozen=True) +class _NewtonMarkerSpec: + renderer: Literal["mesh", "frame", "none"] + mesh_type: Literal["arrow", "box", "textured_box", "sphere", "cylinder", "capsule", "cone"] | None = None + mesh_params: dict[str, float | tuple[float, float, float]] | None = None + scale: tuple[float, float, float] | None = None + color: tuple[float, float, float] | None = None + texture: Any | None = None + + +@dataclass(frozen=True) +class _MeshData: + vertices: np.ndarray + indices: np.ndarray + normals: np.ndarray + uvs: np.ndarray + + +def render_newton_visualization_markers(viewer, visible_env_ids: list[int] | None, num_envs: int) -> None: + """Render all active Newton visualization marker groups into a Newton-family viewer.""" + sim = sim_utils.SimulationContext.instance() + if sim is None: + return + + for marker in sim.vis_marker_registry.get_groups().values(): + if isinstance(marker, NewtonVisualizationMarkers): + marker.render(viewer, visible_env_ids=visible_env_ids, num_envs=num_envs) + + +class NewtonVisualizationMarkers: + """Newton-family backend for visualization markers.""" + + def __init__(self, cfg: VisualizationMarkersCfg, visible: bool = True): + self.cfg = cfg + self.group_id = f"{cfg.prim_path}::{id(self)}" + self.visible = visible + self.translations: torch.Tensor | None = None + self.orientations: torch.Tensor | None = None + self.scales: torch.Tensor | None = None + self.marker_indices: torch.Tensor | None = None + self.count = len(cfg.markers) + self._registered_meshes: set[tuple[int, str]] = set() + self._warned_unsupported: set[str] = set() + + sim = sim_utils.SimulationContext.instance() + if sim is not None: + sim.vis_marker_registry.set_group(self.group_id, self) + + def close(self) -> None: + """Remove marker backend from the simulation marker registry.""" + sim = sim_utils.SimulationContext.instance() + if sim is not None: + sim.vis_marker_registry.remove_group(self.group_id) + + def infer_device(self) -> torch.device: + """Infer the device from current marker state.""" + for value in (self.translations, self.orientations, self.scales, self.marker_indices): + if value is not None: + return value.device + return torch.device("cpu") + + def set_visibility(self, visible: bool) -> None: + """Set marker visibility.""" + self.visible = visible + + def is_visible(self) -> bool: + """Return whether this marker group is visible.""" + return self.visible + + def visualize( + self, + translations: torch.Tensor | None, + orientations: torch.Tensor | None, + scales: torch.Tensor | None, + marker_indices: torch.Tensor | None, + ) -> None: + """Update marker state consumed by Newton-family visualizers.""" + if translations is not None: + self.translations = translations.detach() + self.count = translations.shape[0] + if orientations is not None: + self.orientations = orientations.detach() + self.count = orientations.shape[0] + if scales is not None: + self.scales = scales.detach() + self.count = scales.shape[0] + if marker_indices is not None: + self.marker_indices = marker_indices.detach().to(dtype=torch.int32) + self.count = marker_indices.shape[0] + elif self.count != 0: + self.marker_indices = torch.zeros(self.count, dtype=torch.int32, device=self.infer_device()) + + def render(self, viewer, visible_env_ids: list[int] | None, num_envs: int) -> None: + """Render marker state to a Newton viewer.""" + state = _filter_marker_state(self, visible_env_ids=visible_env_ids, num_envs=num_envs) + if state["count"] == 0: + for name, marker_cfg in self.cfg.markers.items(): + self._hide_batch(viewer, name, _resolve_newton_marker_cfg(name, marker_cfg, self.cfg)) + return + + translations = state["translations"] + if translations is None: + return + orientations = state["orientations"] + if orientations is None: + orientations = torch.tensor([[0.0, 0.0, 0.0, 1.0]], device=translations.device).repeat(state["count"], 1) + scales = state["scales"] + if scales is None: + scales = torch.ones((state["count"], 3), dtype=torch.float32, device=translations.device) + marker_indices = state["marker_indices"] + if marker_indices is None: + marker_indices = torch.zeros(state["count"], dtype=torch.int64, device=translations.device) + + for proto_index, (name, marker_cfg) in enumerate(self.cfg.markers.items()): + newton_cfg = _resolve_newton_marker_cfg(name, marker_cfg, self.cfg) + batch_name = f"{self.group_id}/{name}" + selected = marker_indices == proto_index + if not state["visible"] or int(selected.sum().item()) == 0: + self._hide_batch(viewer, name, newton_cfg) + continue + + if newton_cfg.renderer == "none": + unsupported_key = f"{self.group_id}:{name}" + if unsupported_key not in self._warned_unsupported: + logger.warning( + "[NewtonVisualizationMarkers] Unsupported marker prototype '%s' in group '%s'; skipping.", + name, + self.group_id, + ) + self._warned_unsupported.add(unsupported_key) + continue + + selected_translations = translations[selected] + selected_orientations = orientations[selected] + default_scale = newton_cfg.scale or _extract_scale_hint(marker_cfg) + selected_scales = scales[selected] * torch.tensor( + default_scale, dtype=torch.float32, device=scales.device + ).unsqueeze(0) + + if newton_cfg.renderer == "mesh": + mesh_name = f"{self.group_id}/meshes/{name}" + self._ensure_mesh_registered(viewer, mesh_name, newton_cfg) + color = newton_cfg.color or _extract_color(marker_cfg) + colors = torch.tensor(color, dtype=torch.float32, device=scales.device).repeat( + selected_scales.shape[0], 1 + ) + materials = torch.zeros((selected_scales.shape[0], 4), dtype=torch.float32, device=scales.device) + if newton_cfg.texture is not None: + # ViewerGL gates texture sampling with material.w. Rerun and + # Viser ignore this flag but consume the mesh texture. + materials[:, 3] = 1.0 + xforms = torch.cat((selected_translations, selected_orientations), dim=1).detach().cpu().numpy() + viewer.log_instances( + batch_name, + mesh_name, + wp.array(xforms.astype(np.float32), dtype=wp.transform), + wp.array(selected_scales.detach().cpu().numpy().astype(np.float32), dtype=wp.vec3), + wp.array(colors.detach().cpu().numpy().astype(np.float32), dtype=wp.vec3), + wp.array(materials.detach().cpu().numpy().astype(np.float32), dtype=wp.vec4), + hidden=False, + ) + elif newton_cfg.renderer == "frame": + starts, ends, colors = _build_frame_lines(selected_translations, selected_orientations, selected_scales) + width = max(float(selected_scales.mean().item()) * 0.05, 0.0025) + viewer.log_lines( + batch_name, + wp.array(starts.detach().cpu().numpy().astype(np.float32), dtype=wp.vec3), + wp.array(ends.detach().cpu().numpy().astype(np.float32), dtype=wp.vec3), + wp.array(colors.detach().cpu().numpy().astype(np.float32), dtype=wp.vec3), + width=width, + hidden=False, + ) + + def _hide_batch(self, viewer, name: str, newton_cfg: _NewtonMarkerSpec) -> None: + batch_name = f"{self.group_id}/{name}" + if newton_cfg.renderer == "mesh" and newton_cfg.mesh_type is not None: + mesh_name = f"{self.group_id}/meshes/{name}" + self._ensure_mesh_registered(viewer, mesh_name, newton_cfg) + viewer.log_instances(batch_name, mesh_name, None, None, None, None, hidden=True) + elif newton_cfg.renderer == "frame": + viewer.log_lines(batch_name, None, None, None, hidden=True) + + def _ensure_mesh_registered(self, viewer, mesh_name: str, newton_cfg: _NewtonMarkerSpec) -> None: + # The marker backend is shared by all Newton-family visualizers. Mesh + # registration is viewer-local, so the same marker mesh must be logged + # once per viewer (for example, once for Rerun and once for Viser). + registered_key = (id(viewer), mesh_name) + if registered_key in self._registered_meshes or newton_cfg.mesh_type is None: + return + mesh = _create_mesh(newton_cfg) + viewer.log_mesh( + mesh_name, + wp.array(mesh.vertices.astype(np.float32), dtype=wp.vec3), + wp.array(mesh.indices.astype(np.int32), dtype=wp.int32), + normals=wp.array(mesh.normals.astype(np.float32), dtype=wp.vec3) if mesh.normals.size else None, + uvs=wp.array(mesh.uvs.astype(np.float32), dtype=wp.vec2) if mesh.uvs.size else None, + texture=newton_cfg.texture, + hidden=True, + ) + self._registered_meshes.add(registered_key) + + +def _resolve_newton_marker_cfg(name: str, marker_cfg: object, cfg: VisualizationMarkersCfg) -> _NewtonMarkerSpec: + del name, cfg + return _infer_newton_marker_cfg(marker_cfg) + + +def _infer_newton_marker_cfg(marker_cfg: object) -> _NewtonMarkerSpec: + cfg_type = type(marker_cfg).__name__ + + if cfg_type == "SphereCfg": + return _NewtonMarkerSpec(renderer="mesh", mesh_type="sphere", mesh_params={"radius": float(marker_cfg.radius)}) + if cfg_type == "CuboidCfg": + return _NewtonMarkerSpec( + renderer="mesh", mesh_type="box", mesh_params={"size": tuple(float(v) for v in marker_cfg.size)} + ) + if cfg_type == "CylinderCfg": + return _NewtonMarkerSpec( + renderer="mesh", + mesh_type="cylinder", + mesh_params={"radius": float(marker_cfg.radius), "height": float(marker_cfg.height)}, + ) + if cfg_type == "CapsuleCfg": + return _NewtonMarkerSpec( + renderer="mesh", + mesh_type="capsule", + mesh_params={"radius": float(marker_cfg.radius), "height": float(marker_cfg.height)}, + ) + if cfg_type == "ConeCfg": + return _NewtonMarkerSpec( + renderer="mesh", + mesh_type="cone", + mesh_params={"radius": float(marker_cfg.radius), "height": float(marker_cfg.height)}, + ) + + if cfg_type == "UsdFileCfg": + usd_path = str(marker_cfg.usd_path).lower() + default_scale = _extract_scale_hint(marker_cfg) + if usd_path.endswith("arrow_x.usd"): + return _NewtonMarkerSpec( + renderer="mesh", + mesh_type="arrow", + mesh_params={"base_radius": 0.08, "base_height": 0.7, "cap_radius": 0.16, "cap_height": 0.3}, + scale=(default_scale[0], default_scale[1] * 2.5, default_scale[2] * 2.5), + ) + if usd_path.endswith("frame_prim.usd"): + return _NewtonMarkerSpec(renderer="frame", scale=default_scale) + if "dexcube" in usd_path or "dex_cube" in usd_path: + # TODO: Remove this specialized DexCube mesh code when general + # UsdFileCfg-to-Newton mesh conversion is supported. + # DexCube USDs are roughly 6 cm wide. Keep scale separate so task + # configs such as scale=(1.2, 1.2, 1.2) still apply naturally. + return _NewtonMarkerSpec( + renderer="mesh", + mesh_type="textured_box", + mesh_params={"size": (0.06, 0.06, 0.06)}, + color=(1.0, 1.0, 1.0), + texture=_DEX_CUBE_TEXTURE_URL, + ) + + # TODO: Add generic UsdFileCfg -> Newton mesh extraction for mesh-backed USD marker assets. + # For now, only common marker USDs are mapped to lightweight Newton-native fallbacks. + + return _NewtonMarkerSpec(renderer="none") + + +def _create_mesh(newton_cfg: _NewtonMarkerSpec): + mesh_params = newton_cfg.mesh_params or {} + if newton_cfg.mesh_type == "arrow": + return Mesh.create_arrow( + float(mesh_params["base_radius"]), + float(mesh_params["base_height"]), + cap_radius=float(mesh_params["cap_radius"]), + cap_height=float(mesh_params["cap_height"]), + up_axis=Axis.X, + ) + if newton_cfg.mesh_type == "box": + size = mesh_params["size"] + return Mesh.create_box(float(size[0]) * 0.5, float(size[1]) * 0.5, float(size[2]) * 0.5) + if newton_cfg.mesh_type == "textured_box": + return _create_textured_box_mesh(mesh_params["size"]) + if newton_cfg.mesh_type == "sphere": + return Mesh.create_sphere(radius=float(mesh_params["radius"])) + if newton_cfg.mesh_type == "cylinder": + return Mesh.create_cylinder( + float(mesh_params["radius"]), + float(mesh_params["height"]) * 0.5, + up_axis=Axis.Z, + ) + if newton_cfg.mesh_type == "capsule": + return Mesh.create_capsule( + float(mesh_params["radius"]), + float(mesh_params["height"]) * 0.5, + up_axis=Axis.Z, + ) + if newton_cfg.mesh_type == "cone": + return Mesh.create_cone( + float(mesh_params["radius"]), + float(mesh_params["height"]) * 0.5, + up_axis=Axis.Z, + ) + raise ValueError(f"Unsupported Newton mesh type: {newton_cfg.mesh_type}") + + +def _create_textured_box_mesh(size: tuple[float, float, float]) -> _MeshData: + # TODO: Remove this specialized DexCube mesh code when general + # UsdFileCfg-to-Newton mesh conversion is supported. + half = np.asarray(size, dtype=np.float32) * 0.5 + usd_vertices = np.asarray( + [ + (-1.0, -1.0, 1.0), + (-1.0, 1.0, 1.0), + (-1.0, 1.0, -1.0), + (-1.0, -1.0, -1.0), + (-1.0, -1.0, -1.0), + (-1.0, 1.0, -1.0), + (1.0, 1.0, -1.0), + (1.0, -1.0, -1.0), + (1.0, -1.0, -1.0), + (1.0, 1.0, -1.0), + (1.0, 1.0, 1.0), + (1.0, -1.0, 1.0), + (1.0, -1.0, 1.0), + (1.0, 1.0, 1.0), + (-1.0, 1.0, 1.0), + (-1.0, -1.0, 1.0), + (-1.0, -1.0, -1.0), + (1.0, -1.0, -1.0), + (1.0, -1.0, 1.0), + (-1.0, -1.0, 1.0), + (1.0, 1.0, -1.0), + (-1.0, 1.0, -1.0), + (-1.0, 1.0, 1.0), + (1.0, 1.0, 1.0), + ], + dtype=np.float32, + ) + uvs = np.asarray( + [ + (1.0, 0.333333), + (1.0, 0.666667), + (0.5, 0.666667), + (0.5, 0.333333), + (0.5, 0.666667), + (0.5, 1.0), + (0.0, 1.0), + (0.0, 0.666667), + (0.5, 0.333333), + (0.5, 0.666667), + (0.0, 0.666667), + (0.0, 0.333333), + (1.0, 0.0), + (1.0, 0.333333), + (0.5, 0.333333), + (0.5, 0.0), + (0.5, 0.0), + (0.5, 0.333333), + (0.0, 0.333333), + (0.0, 0.0), + (1.0, 0.666667), + (1.0, 1.0), + (0.5, 1.0), + (0.5, 0.666667), + ], + dtype=np.float32, + ) + indices: list[int] = [] + for base in range(0, 24, 4): + indices.extend([base, base + 1, base + 2, base, base + 2, base + 3]) + return _MeshData( + vertices=usd_vertices * half, + indices=np.asarray(indices, dtype=np.int32), + normals=np.zeros((0, 3), dtype=np.float32), + uvs=uvs, + ) + + +def _filter_marker_state( + marker: NewtonVisualizationMarkers, + visible_env_ids: list[int] | None, + num_envs: int, +) -> dict[str, Any]: + if visible_env_ids is None or marker.count == 0 or num_envs <= 0 or marker.count % num_envs != 0: + return { + "visible": marker.visible, + "translations": marker.translations, + "orientations": marker.orientations, + "scales": marker.scales, + "marker_indices": marker.marker_indices, + "count": marker.count, + } + + keep: list[int] = [] + repeat_count = marker.count // num_envs + for block_idx in range(repeat_count): + base = block_idx * num_envs + for env_id in visible_env_ids: + idx = base + env_id + if idx < marker.count: + keep.append(idx) + + if len(keep) == marker.count: + return { + "visible": marker.visible, + "translations": marker.translations, + "orientations": marker.orientations, + "scales": marker.scales, + "marker_indices": marker.marker_indices, + "count": marker.count, + } + + index = torch.tensor(keep, dtype=torch.long, device=marker.infer_device()) + return { + "visible": marker.visible, + "translations": marker.translations.index_select(0, index) if marker.translations is not None else None, + "orientations": marker.orientations.index_select(0, index) if marker.orientations is not None else None, + "scales": marker.scales.index_select(0, index) if marker.scales is not None else None, + "marker_indices": marker.marker_indices.index_select(0, index) if marker.marker_indices is not None else None, + "count": len(keep), + } + + +def _extract_scale_hint(marker_cfg: object) -> tuple[float, float, float]: + scale = marker_cfg.scale if type(marker_cfg).__name__ == "UsdFileCfg" else None + if scale is None: + return (1.0, 1.0, 1.0) + return tuple(float(v) for v in scale) + + +def _extract_color(marker_cfg: object) -> tuple[float, float, float]: + material_cfg = marker_cfg.visual_material + if material_cfg is None: + return _UNBOUND_DEFAULT_FALLBACK_GRAY + + if color := _extract_omnipbr_like_color(material_cfg): + return color + + material_type = type(material_cfg).__name__ + if material_type == "PreviewSurfaceCfg": + return _extract_rgb(material_cfg.diffuse_color) or _UNBOUND_DEFAULT_FALLBACK_GRAY + if material_type == "GlassMdlCfg": + return _extract_rgb(material_cfg.glass_color) or _UNBOUND_DEFAULT_FALLBACK_GRAY + + return _UNBOUND_DEFAULT_FALLBACK_GRAY + + +def _extract_omnipbr_like_color(material_cfg: object) -> tuple[float, float, float] | None: + material_type = type(material_cfg).__name__ + if material_type == "MdlFileCfg": + if not str(material_cfg.mdl_path).lower().endswith("omnipbr.mdl"): + return None + brightness = material_cfg.albedo_brightness + if brightness is not None: + diffuse_constant = (float(brightness), float(brightness), float(brightness)) + else: + diffuse_constant = _OMNIPBR_DEFAULTS["diffuse_color_constant"] + diffuse_tint = _OMNIPBR_DEFAULTS["diffuse_tint"] + else: + return None + + return ( + diffuse_constant[0] * diffuse_tint[0], + diffuse_constant[1] * diffuse_tint[1], + diffuse_constant[2] * diffuse_tint[2], + ) + + +def _extract_rgb(value: Any) -> tuple[float, float, float] | None: + if value is None: + return None + try: + rgb = tuple(float(v) for v in value) + except TypeError: + return None + if len(rgb) < 3: + return None + return (rgb[0], rgb[1], rgb[2]) + + +def _build_frame_lines( + translations: torch.Tensor, + orientations: torch.Tensor, + scales: torch.Tensor, +) -> tuple[torch.Tensor, torch.Tensor, torch.Tensor]: + unit_axes = ( + torch.eye(3, dtype=torch.float32, device=translations.device).unsqueeze(0).repeat(translations.shape[0], 1, 1) + ) + scaled_axes = unit_axes * scales.unsqueeze(1) + repeated_quats = orientations.unsqueeze(1).repeat(1, 3, 1).reshape(-1, 4) + rotated_axes = quat_apply(repeated_quats, scaled_axes.reshape(-1, 3)).reshape(-1, 3, 3) + starts = translations.unsqueeze(1).repeat(1, 3, 1).reshape(-1, 3) + ends = (translations.unsqueeze(1) + rotated_axes).reshape(-1, 3) + colors = torch.tensor( + [[1.0, 0.0, 0.0], [0.0, 1.0, 0.0], [0.0, 0.35, 1.0]], + dtype=torch.float32, + device=translations.device, + ).repeat(translations.shape[0], 1) + return starts, ends, colors diff --git a/source/isaaclab_visualizers/isaaclab_visualizers/newton/newton_visualizer.py b/source/isaaclab_visualizers/isaaclab_visualizers/newton/newton_visualizer.py index 8c8bb0bed9d8..b548a3e5f4f3 100644 --- a/source/isaaclab_visualizers/isaaclab_visualizers/newton/newton_visualizer.py +++ b/source/isaaclab_visualizers/isaaclab_visualizers/newton/newton_visualizer.py @@ -18,6 +18,7 @@ from isaaclab_visualizers.newton_adapter import apply_viewer_visible_worlds, resolve_visible_env_indices +from .newton_visualization_markers import render_newton_visualization_markers from .newton_visualizer_cfg import NewtonVisualizerCfg logger = logging.getLogger(__name__) @@ -268,6 +269,7 @@ def __init__(self, cfg: NewtonVisualizerCfg): self._scene_data_provider = None self._last_camera_pose: tuple[tuple[float, float, float], tuple[float, float, float]] | None = None self._headless_no_viewer = False + self._resolved_visible_env_ids: list[int] | None = None def initialize(self, scene_data_provider: BaseSceneDataProvider) -> None: """Initialize viewer resources and bind scene data provider. @@ -335,8 +337,10 @@ def initialize(self, scene_data_provider: BaseSceneDataProvider) -> None: self._viewer.renderer.sky_lower = self._viewer._coerce_color3(self.cfg.sky_lower_color) self._viewer.renderer._light_color = self._viewer._coerce_color3(self.cfg.light_color) - _resolved = resolve_visible_env_indices(self._env_ids, self.cfg.max_visible_envs, num_envs) - num_visualized_envs = len(_resolved) if _resolved is not None else num_envs + self._resolved_visible_env_ids = resolve_visible_env_indices(self._env_ids, self.cfg.max_visible_envs, num_envs) + num_visualized_envs = ( + len(self._resolved_visible_env_ids) if self._resolved_visible_env_ids is not None else num_envs + ) self._log_initialization_table( logger=logger, title="NewtonVisualizer Configuration", @@ -374,6 +378,7 @@ def step(self, dt: float) -> None: self._update_camera_from_usd_path() self._state = self._scene_data_provider.get_newton_state() + num_envs = int(self._scene_data_provider.get_metadata().get("num_envs", 0)) contacts = None if self._viewer.show_contacts: @@ -401,6 +406,10 @@ def step(self, dt: float) -> None: self._viewer.log_contacts(contacts, self._state) except RuntimeError as exc: logger.debug(f"[NewtonVisualizer] Failed to log contacts: {exc}") + if self.cfg.enable_markers: + render_newton_visualization_markers( + self._viewer, self._resolved_visible_env_ids, num_envs=num_envs + ) self._viewer.end_frame() else: self._viewer._update() @@ -475,8 +484,8 @@ def _update_camera_from_usd_path(self) -> None: self._apply_camera_pose(pose) def supports_markers(self) -> bool: - """Newton OpenGL viewer does not implement Isaac Lab marker primitives.""" - return False + """Newton OpenGL viewer supports Isaac Lab markers through viewer-side meshes and lines.""" + return bool(self.cfg.enable_markers) def supports_live_plots(self) -> bool: """Newton OpenGL viewer does not provide live-plot panels.""" diff --git a/source/isaaclab_visualizers/isaaclab_visualizers/rerun/rerun_visualizer.py b/source/isaaclab_visualizers/isaaclab_visualizers/rerun/rerun_visualizer.py index 5390802df69d..5600ad2ee9c4 100644 --- a/source/isaaclab_visualizers/isaaclab_visualizers/rerun/rerun_visualizer.py +++ b/source/isaaclab_visualizers/isaaclab_visualizers/rerun/rerun_visualizer.py @@ -20,6 +20,7 @@ from isaaclab.visualizers.base_visualizer import BaseVisualizer +from isaaclab_visualizers.newton.newton_visualization_markers import render_newton_visualization_markers from isaaclab_visualizers.newton_adapter import apply_viewer_visible_worlds, resolve_visible_env_indices from .rerun_visualizer_cfg import RerunVisualizerCfg @@ -133,6 +134,7 @@ def __init__(self, cfg: RerunVisualizerCfg): self._state = None self._scene_data_provider = None self._last_camera_pose: tuple[tuple[float, float, float], tuple[float, float, float]] | None = None + self._resolved_visible_env_ids: list[int] | None = None def initialize(self, scene_data_provider: BaseSceneDataProvider) -> None: """Initialize rerun viewer and bind scene data provider. @@ -196,8 +198,10 @@ def initialize(self, scene_data_provider: BaseSceneDataProvider) -> None: self._viewer.scaling = 1.0 self._viewer._paused = False - _resolved = resolve_visible_env_indices(self._env_ids, self.cfg.max_visible_envs, num_envs) - num_visualized_envs = len(_resolved) if _resolved is not None else num_envs + self._resolved_visible_env_ids = resolve_visible_env_indices(self._env_ids, self.cfg.max_visible_envs, num_envs) + num_visualized_envs = ( + len(self._resolved_visible_env_ids) if self._resolved_visible_env_ids is not None else num_envs + ) self._log_initialization_table( logger=logger, title="RerunVisualizer Configuration", @@ -235,16 +239,22 @@ def step(self, dt: float) -> None: self._update_camera_from_usd_path() self._state = self._scene_data_provider.get_newton_state() + num_envs = int(self._scene_data_provider.get_metadata().get("num_envs", 0)) if not self._viewer.is_paused(): self._viewer.begin_frame(self._sim_time) - if self._state is not None: - body_q = getattr(self._state, "body_q", None) - if hasattr(body_q, "shape") and body_q.shape[0] == 0: - self._viewer.end_frame() - return - self._viewer.log_state(self._state) - self._viewer.end_frame() + try: + if self._state is not None: + body_q = getattr(self._state, "body_q", None) + if hasattr(body_q, "shape") and body_q.shape[0] == 0: + return + self._viewer.log_state(self._state) + if self.cfg.enable_markers: + render_newton_visualization_markers( + self._viewer, self._resolved_visible_env_ids, num_envs=num_envs + ) + finally: + self._viewer.end_frame() def close(self) -> None: """Close viewer/session resources.""" @@ -323,8 +333,8 @@ def _update_camera_from_usd_path(self) -> None: self._apply_camera_pose(pose) def supports_markers(self) -> bool: - """Rerun backend currently does not expose Isaac Lab marker primitives.""" - return False + """Rerun backend supports Isaac Lab markers through Newton viewer primitives.""" + return bool(self.cfg.enable_markers) def supports_live_plots(self) -> bool: """Rerun backend currently does not expose Isaac Lab live-plot widgets.""" diff --git a/source/isaaclab_visualizers/isaaclab_visualizers/viser/viser_visualizer.py b/source/isaaclab_visualizers/isaaclab_visualizers/viser/viser_visualizer.py index a629ab8b2fed..44a0e92c1d70 100644 --- a/source/isaaclab_visualizers/isaaclab_visualizers/viser/viser_visualizer.py +++ b/source/isaaclab_visualizers/isaaclab_visualizers/viser/viser_visualizer.py @@ -19,6 +19,7 @@ from isaaclab.visualizers.base_visualizer import BaseVisualizer +from isaaclab_visualizers.newton.newton_visualization_markers import render_newton_visualization_markers from isaaclab_visualizers.newton_adapter import apply_viewer_visible_worlds, resolve_visible_env_indices from .viser_visualizer_cfg import ViserVisualizerCfg @@ -129,6 +130,8 @@ def __init__(self, cfg: ViserVisualizerCfg): self._active_record_path: str | None = None self._last_camera_pose: tuple[tuple[float, float, float], tuple[float, float, float]] | None = None self._pending_camera_pose: tuple[tuple[float, float, float], tuple[float, float, float]] | None = None + self._resolved_visible_env_ids: list[int] | None = None + self._warned_marker_render_failure = False def initialize(self, scene_data_provider: BaseSceneDataProvider) -> None: """Initialize viewer resources and bind scene data provider. @@ -151,8 +154,12 @@ def initialize(self, scene_data_provider: BaseSceneDataProvider) -> None: self._active_record_path = self.cfg.record_to_viser self._create_viewer(record_to_viser=self.cfg.record_to_viser, metadata=metadata) num_envs_meta = int(metadata.get("num_envs", 0)) - _resolved = resolve_visible_env_indices(self._env_ids, self.cfg.max_visible_envs, num_envs_meta) - num_visualized_envs = len(_resolved) if _resolved is not None else num_envs_meta + self._resolved_visible_env_ids = resolve_visible_env_indices( + self._env_ids, self.cfg.max_visible_envs, num_envs_meta + ) + num_visualized_envs = ( + len(self._resolved_visible_env_ids) if self._resolved_visible_env_ids is not None else num_envs_meta + ) viewer_url = _viser_web_viewer_url(self.cfg.port) self._log_initialization_table( logger=logger, @@ -183,10 +190,26 @@ def step(self, dt: float) -> None: self._apply_pending_camera_pose() self._state = self._scene_data_provider.get_newton_state() + num_envs = int(self._scene_data_provider.get_metadata().get("num_envs", 0)) self._sim_time += dt self._viewer.begin_frame(self._sim_time) - self._viewer.log_state(self._state) - self._viewer.end_frame() + try: + self._viewer.log_state(self._state) + if self.cfg.enable_markers: + self._render_markers(num_envs) + finally: + self._viewer.end_frame() + + def _render_markers(self, num_envs: int) -> None: + """Render marker overlays without letting them interrupt Viser body updates.""" + try: + render_newton_visualization_markers(self._viewer, self._resolved_visible_env_ids, num_envs=num_envs) + except Exception as exc: + if not self._warned_marker_render_failure: + logger.warning("[ViserVisualizer] Marker rendering failed; continuing body updates: %s", exc) + self._warned_marker_render_failure = True + else: + logger.debug("[ViserVisualizer] Marker rendering failed: %s", exc) def close(self) -> None: """Close viewer resources and finalize optional recording.""" @@ -223,8 +246,8 @@ def is_training_paused(self) -> bool: return False def supports_markers(self) -> bool: - """Viser backend currently does not expose Isaac Lab marker primitives.""" - return False + """Viser backend supports Isaac Lab markers through Newton viewer primitives.""" + return bool(self.cfg.enable_markers) def supports_live_plots(self) -> bool: """Viser backend currently does not expose Isaac Lab live-plot widgets.""" From fa5959feb911664b11318cc3296903fe6c7d7d56 Mon Sep 17 00:00:00 2001 From: Kelly Guo Date: Tue, 5 May 2026 14:53:51 -0700 Subject: [PATCH 02/51] Improves hanging flakiness in CI tests (#5479) # Description - Increase the CI startup-hang grace period from 45s to 120s so slow but valid Kit startup is not killed prematurely. - Make `SurfaceGripper` fail fast on non-CPU simulation backends before loading the surface gripper extension. - Skip the CI-only `SurfaceGripperView` CPU initialization path that can deadlock, while keeping CUDA fail-fast coverage. ## Type of change - Bug fix (non-breaking change which fixes an issue) ## Checklist - [x] I have read and understood the [contribution guidelines](https://isaac-sim.github.io/IsaacLab/main/source/refs/contributing.html) - [x] I have run the [`pre-commit` checks](https://pre-commit.com/) with `./isaaclab.sh --format` - [x] I have made corresponding changes to the documentation - [x] My changes generate no new warnings - [ ] I have added tests that prove my fix is effective or that my feature works - [ ] I have updated the changelog and the corresponding version in the extension's `config/extension.toml` file - [ ] I have added my name to the `CONTRIBUTORS.md` or my name already exists there --- .../changelog.d/test-articulation-timeout.rst | 6 ++++++ .../assets/surface_gripper/surface_gripper.py | 6 +++--- .../isaaclab_physx/test/assets/test_surface_gripper.py | 10 ++++++++++ tools/conftest.py | 8 ++++---- 4 files changed, 23 insertions(+), 7 deletions(-) create mode 100644 source/isaaclab_physx/changelog.d/test-articulation-timeout.rst diff --git a/source/isaaclab_physx/changelog.d/test-articulation-timeout.rst b/source/isaaclab_physx/changelog.d/test-articulation-timeout.rst new file mode 100644 index 000000000000..e0c1b96870c2 --- /dev/null +++ b/source/isaaclab_physx/changelog.d/test-articulation-timeout.rst @@ -0,0 +1,6 @@ +Fixed +^^^^^ + +* Fixed :class:`~isaaclab_physx.assets.SurfaceGripper` initialization on + non-CPU simulation backends to raise before loading the surface gripper + extension, avoiding hangs during startup. diff --git a/source/isaaclab_physx/isaaclab_physx/assets/surface_gripper/surface_gripper.py b/source/isaaclab_physx/isaaclab_physx/assets/surface_gripper/surface_gripper.py index 590289feb659..6662582dac7c 100644 --- a/source/isaaclab_physx/isaaclab_physx/assets/surface_gripper/surface_gripper.py +++ b/source/isaaclab_physx/isaaclab_physx/assets/surface_gripper/surface_gripper.py @@ -443,9 +443,6 @@ def _initialize_impl(self) -> None: Use `--device cpu` to run the simulation on CPU. """ - enable_extension("isaacsim.robot.surface_gripper") - from isaacsim.robot.surface_gripper import GripperView - # Check that we are using the CPU backend. if self._device != "cpu": raise Exception( @@ -453,6 +450,9 @@ def _initialize_impl(self) -> None: " `--device cpu` to run the simulation on CPU." ) + enable_extension("isaacsim.robot.surface_gripper") + from isaacsim.robot.surface_gripper import GripperView + # obtain the first prim in the regex expression (all others are assumed to be a copy of this) template_prim = sim_utils.find_first_matching_prim(self._cfg.prim_path) if template_prim is None: diff --git a/source/isaaclab_physx/test/assets/test_surface_gripper.py b/source/isaaclab_physx/test/assets/test_surface_gripper.py index e85a4a8415cc..c075821bb985 100644 --- a/source/isaaclab_physx/test/assets/test_surface_gripper.py +++ b/source/isaaclab_physx/test/assets/test_surface_gripper.py @@ -9,6 +9,8 @@ """Launch Isaac Sim Simulator first.""" +import os + from isaaclab.app import AppLauncher # launch omniverse app @@ -35,6 +37,10 @@ # from isaacsim.robot.surface_gripper import GripperView +_RUNNING_CI = ( + os.environ.get("CI") == "true" or os.environ.get("GITHUB_ACTIONS") == "true" or os.environ.get("GITLAB_CI") +) + def generate_surface_gripper_cfgs( kinematic_enabled: bool = False, @@ -158,6 +164,10 @@ def sim(request): @pytest.mark.parametrize("device", ["cpu"]) @pytest.mark.parametrize("add_ground_plane", [True]) @pytest.mark.isaacsim_ci +@pytest.mark.skipif( + _RUNNING_CI, + reason="Isaac Sim SurfaceGripperView initialization can deadlock in CI; keep CUDA fail-fast coverage only.", +) def test_initialization(sim, num_articulations, device, add_ground_plane) -> None: """Test initialization for articulation with a surface gripper. diff --git a/tools/conftest.py b/tools/conftest.py index bf92d62f6c46..55b00ce44afa 100644 --- a/tools/conftest.py +++ b/tools/conftest.py @@ -33,16 +33,16 @@ def pytest_ignore_collect(collection_path, config): on-disk cache is populated. """ -STARTUP_DEADLINE = 45 +STARTUP_DEADLINE = 120 """Seconds to wait for AppLauncher init or pytest collection before declaring a startup hang. AppLauncher prints ``[ISAACLAB] AppLauncher initialization complete`` to ``sys.__stderr__`` (never suppressed) when Kit finishes initializing, and pytest prints ``collected N items`` to stdout after collection. If neither appears -within this deadline the process is treated as hung. 45 s is above any -legitimate Kit startup (typically 30--60 s) while still catching real hangs -without wasting the full hard timeout. +within this deadline the process is treated as hung. Kit startup can exceed +60 s on cold CI workers, so this catches real startup hangs without killing +legitimate slow launches. """ STARTUP_HANG_RETRIES = 2 From 2d52d620dca239ba2fa59ee2e5de42ba98097cc4 Mon Sep 17 00:00:00 2001 From: hujc Date: Tue, 5 May 2026 15:52:45 -0700 Subject: [PATCH 03/51] Docs: update contributing.rst and PR template for changelog fragments (#5478) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Follow-up to #5434 (fragment-based changelog system). Two contributor-facing references still pointed at the old "edit CHANGELOG.rst directly" workflow: - **`docs/source/refs/contributing.rst`** — *Maintaining a changelog and extension.toml* section described per-version editing of CHANGELOG.rst with manual SemVer bumps. - **`.github/PULL_REQUEST_TEMPLATE.md`** — checklist asked contributors to update the changelog and bump extension.toml directly. Replaced only the parts that talk about direct editing; section/style guidance (Added/Changed/Deprecated/Removed/Fixed, past tense, the sample bullets themselves) stays intact. ## Test plan - [x] Pre-commit clean - [ ] Verify Build Latest Docs CI step renders the new section correctly cc @kellyguo11 — addresses the doc gaps flagged after #5434 merged. --- .github/PULL_REQUEST_TEMPLATE.md | 2 +- docs/source/refs/contributing.rst | 32 ++++++++++++++++--------------- 2 files changed, 18 insertions(+), 16 deletions(-) diff --git a/.github/PULL_REQUEST_TEMPLATE.md b/.github/PULL_REQUEST_TEMPLATE.md index ee9fa4ebdc5e..c19d35fb7e79 100644 --- a/.github/PULL_REQUEST_TEMPLATE.md +++ b/.github/PULL_REQUEST_TEMPLATE.md @@ -47,7 +47,7 @@ To upload images to a PR -- simply drag and drop an image while in edit mode and - [ ] I have made corresponding changes to the documentation - [ ] My changes generate no new warnings - [ ] I have added tests that prove my fix is effective or that my feature works -- [ ] I have updated the changelog and the corresponding version in the extension's `config/extension.toml` file +- [ ] I have added a changelog fragment under `source//changelog.d/` for every touched package (do **not** edit `CHANGELOG.rst` or bump `extension.toml` — CI handles that) - [ ] I have added my name to the `CONTRIBUTORS.md` or my name already exists there ## Type of change - Test change ## Screenshots Please attach before and after screenshots of the change if applicable. ## Checklist - [x] I have read and understood the [contribution guidelines](https://isaac-sim.github.io/IsaacLab/main/source/refs/contributing.html) - [x] I have run the [`pre-commit` checks](https://pre-commit.com/) with `./isaaclab.sh --format` - [x] I have made corresponding changes to the documentation - [x] My changes generate no new warnings - [x] I have added tests that prove my fix is effective or that my feature works - [x] I have updated the changelog and the corresponding version in the extension's `config/extension.toml` file - [x] I have added my name to the `CONTRIBUTORS.md` or my name already exists there --------- Signed-off-by: HuiDong Chen Co-authored-by: greptile-apps[bot] <165735046+greptile-apps[bot]@users.noreply.github.com> --- .../changelog.d/huidongc-flaky-mark.skip | 0 .../test/rendering_test_utils.py | 42 +++++++++++++------ .../test/test_rendering_dexsuite_kuka.py | 1 - .../test_rendering_dexsuite_kuka_kitless.py | 1 - 4 files changed, 30 insertions(+), 14 deletions(-) create mode 100644 source/isaaclab_tasks/changelog.d/huidongc-flaky-mark.skip diff --git a/source/isaaclab_tasks/changelog.d/huidongc-flaky-mark.skip b/source/isaaclab_tasks/changelog.d/huidongc-flaky-mark.skip new file mode 100644 index 000000000000..e69de29bb2d1 diff --git a/source/isaaclab_tasks/test/rendering_test_utils.py b/source/isaaclab_tasks/test/rendering_test_utils.py index 788064900f85..f79f55c553a5 100644 --- a/source/isaaclab_tasks/test/rendering_test_utils.py +++ b/source/isaaclab_tasks/test/rendering_test_utils.py @@ -66,13 +66,17 @@ # Parametrization: (physics_backend, renderer, data_type) # --------------------------------------------------------------------------- -# OVRTX kitless paths can segfault on GitHub Actions runners; keep warp/Kit paths in CI. -_SKIP_ON_GITHUB_ACTIONS = os.environ.get("GITHUB_ACTIONS") == "true" -_SKIP_ON_GITHUB_ACTIONS_MARK = pytest.mark.skipif( - _SKIP_ON_GITHUB_ACTIONS, - reason="Skipped on GitHub Actions until the test can run on GitHub Actions.", +# OVRTX kitless paths can segfault on CI runners; keep warp/Kit paths in CI. +_SKIP_ON_CI = any(os.environ.get(name) == "true" for name in ("CI", "GITHUB_ACTIONS", "GITLAB_CI")) +_SKIP_ON_CI_MARK = pytest.mark.skipif( + _SKIP_ON_CI, + reason="Skipped on CI runners until the test can run on CI runners.", ) +# Let's just accept the fact that low-resolution camera outputs from RTX renderers are not deterministic enough to pass +# golden image testing on every CI run. +_FLAKY_MARK = pytest.mark.flaky(max_runs=3, min_passes=1) + PHYSICS_RENDERER_AOV_COMBINATIONS = [ # physx + isaacsim_rtx_renderer pytest.param( @@ -80,42 +84,49 @@ "isaacsim_rtx_renderer", "rgb", id="physx-isaacsim_rtx-rgb", + marks=_FLAKY_MARK, ), pytest.param( "physx", "isaacsim_rtx_renderer", "albedo", id="physx-isaacsim_rtx-albedo", + marks=_FLAKY_MARK, ), pytest.param( "physx", "isaacsim_rtx_renderer", "depth", id="physx-isaacsim_rtx-depth", + marks=_FLAKY_MARK, ), pytest.param( "physx", "isaacsim_rtx_renderer", "simple_shading_constant_diffuse", id="physx-isaacsim_rtx-simple_shading_constant_diffuse", + marks=_FLAKY_MARK, ), pytest.param( "physx", "isaacsim_rtx_renderer", "simple_shading_diffuse_mdl", id="physx-isaacsim_rtx-simple_shading_diffuse_mdl", + marks=_FLAKY_MARK, ), pytest.param( "physx", "isaacsim_rtx_renderer", "simple_shading_full_mdl", id="physx-isaacsim_rtx-simple_shading_full_mdl", + marks=_FLAKY_MARK, ), pytest.param( "physx", "isaacsim_rtx_renderer", "semantic_segmentation", id="physx-isaacsim_rtx-semantic_segmentation", + marks=_FLAKY_MARK, ), # newton + isaacsim_rtx_renderer pytest.param( @@ -123,42 +134,49 @@ "isaacsim_rtx_renderer", "rgb", id="newton-isaacsim_rtx-rgb", + marks=_FLAKY_MARK, ), pytest.param( "newton", "isaacsim_rtx_renderer", "albedo", id="newton-isaacsim_rtx-albedo", + marks=_FLAKY_MARK, ), pytest.param( "newton", "isaacsim_rtx_renderer", "depth", id="newton-isaacsim_rtx-depth", + marks=_FLAKY_MARK, ), pytest.param( "newton", "isaacsim_rtx_renderer", "simple_shading_constant_diffuse", id="newton-isaacsim_rtx-simple_shading_constant_diffuse", + marks=_FLAKY_MARK, ), pytest.param( "newton", "isaacsim_rtx_renderer", "simple_shading_diffuse_mdl", id="newton-isaacsim_rtx-simple_shading_diffuse_mdl", + marks=_FLAKY_MARK, ), pytest.param( "newton", "isaacsim_rtx_renderer", "simple_shading_full_mdl", id="newton-isaacsim_rtx-simple_shading_full_mdl", + marks=_FLAKY_MARK, ), pytest.param( "newton", "isaacsim_rtx_renderer", "semantic_segmentation", id="newton-isaacsim_rtx-semantic_segmentation", + marks=_FLAKY_MARK, ), # physx + newton_renderer (warp) pytest.param( @@ -182,49 +200,49 @@ "ovrtx_renderer", "rgb", id="newton-ovrtx-rgb", - marks=_SKIP_ON_GITHUB_ACTIONS_MARK, + marks=_SKIP_ON_CI_MARK, ), pytest.param( "newton", "ovrtx_renderer", "albedo", id="newton-ovrtx-albedo", - marks=_SKIP_ON_GITHUB_ACTIONS_MARK, + marks=_SKIP_ON_CI_MARK, ), pytest.param( "newton", "ovrtx_renderer", "depth", id="newton-ovrtx-depth", - marks=_SKIP_ON_GITHUB_ACTIONS_MARK, + marks=_SKIP_ON_CI_MARK, ), pytest.param( "newton", "ovrtx_renderer", "simple_shading_constant_diffuse", id="newton-ovrtx-simple_shading_constant_diffuse", - marks=_SKIP_ON_GITHUB_ACTIONS_MARK, + marks=_SKIP_ON_CI_MARK, ), pytest.param( "newton", "ovrtx_renderer", "simple_shading_diffuse_mdl", id="newton-ovrtx-simple_shading_diffuse_mdl", - marks=_SKIP_ON_GITHUB_ACTIONS_MARK, + marks=_SKIP_ON_CI_MARK, ), pytest.param( "newton", "ovrtx_renderer", "simple_shading_full_mdl", id="newton-ovrtx-simple_shading_full_mdl", - marks=_SKIP_ON_GITHUB_ACTIONS_MARK, + marks=_SKIP_ON_CI_MARK, ), pytest.param( "newton", "ovrtx_renderer", "semantic_segmentation", id="newton-ovrtx-semantic_segmentation", - marks=_SKIP_ON_GITHUB_ACTIONS_MARK, + marks=_SKIP_ON_CI_MARK, ), # newton + newton_renderer (warp) pytest.param( diff --git a/source/isaaclab_tasks/test/test_rendering_dexsuite_kuka.py b/source/isaaclab_tasks/test/test_rendering_dexsuite_kuka.py index 623c1e08c233..0400c3386e63 100644 --- a/source/isaaclab_tasks/test/test_rendering_dexsuite_kuka.py +++ b/source/isaaclab_tasks/test/test_rendering_dexsuite_kuka.py @@ -31,7 +31,6 @@ _attach_comparison_properties_fixture = make_attach_comparison_properties_fixture(_COMPARISON_SCORES) -@pytest.mark.flaky(max_runs=3, min_passes=1) @pytest.mark.parametrize("physics_backend,renderer,data_type", PHYSICS_RENDERER_AOV_COMBINATIONS) def test_rendering_dexsuite_kuka(physics_backend, renderer, data_type): """Test dexsuite kuka allegro lift environment rendering correctness.""" diff --git a/source/isaaclab_tasks/test/test_rendering_dexsuite_kuka_kitless.py b/source/isaaclab_tasks/test/test_rendering_dexsuite_kuka_kitless.py index f76d43364ab5..15afbee806b1 100644 --- a/source/isaaclab_tasks/test/test_rendering_dexsuite_kuka_kitless.py +++ b/source/isaaclab_tasks/test/test_rendering_dexsuite_kuka_kitless.py @@ -27,7 +27,6 @@ _require_ovrtx_install_fixture = make_require_ovrtx_install_fixture() -@pytest.mark.flaky(max_runs=3, min_passes=1) @pytest.mark.parametrize("physics_backend,renderer,data_type", KITLESS_PHYSICS_RENDERER_AOV_COMBINATIONS) def test_rendering_dexsuite_kuka_kitless(physics_backend, renderer, data_type): """Camera output must match golden images (Dexsuite Kuka-Allegro Lift, single camera).""" From efd9d1e742f6ef5040e44d98a9046320832e8f70 Mon Sep 17 00:00:00 2001 From: Peter Verswyvelen Date: Wed, 6 May 2026 17:56:50 +0200 Subject: [PATCH 05/51] perf: add PrepareForReuse to FabricFrameView, remove sync_usd_on_fabric_write (#5380) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit ## Summary Replace the `sync_usd_on_fabric_write` workaround in `FabricFrameView` with proper `PrepareForReuse()` calls on the Fabric `PrimSelection`. This tells the renderer (FSD/Storm) that Fabric data has changed, so the next rendered frame reflects updated transforms — eliminating the need to copy Fabric writes back to USD. ## Motivation The existing `sync_usd_on_fabric_write` flag worked by mirroring every Fabric write back to USD, which defeated the performance benefits of Fabric. With `PrepareForReuse()`, the rendering pipeline is properly notified of Fabric data changes without any USD writeback. Additionally, the old code incorrectly fell back to USD for CPU devices — Warp handles CPU Fabric buffers correctly, so the fallback was unnecessary. This addresses two of the issues raised in @pbarejko Piotr's review of PR #4923: - **Issue #1** (USD write-back): Fabric writes no longer sync back to USD - **Issue #4** (PrepareForReuse): Renderer notification via `PrepareForReuse()` instead of USD writeback ## Changes ### Core (FabricFrameView) - Call `_prepare_for_reuse()` in write paths (`set_world_poses`, `set_scales`) to notify the renderer - Remove `sync_usd_on_fabric_write` parameter (accepted via `**kwargs` for backward compat) - Remove incorrect CPU/device fallback warnings — Warp handles CPU Fabric buffers correctly - Add `_rebuild_fabric_arrays()` for topology change recovery when `PrepareForReuse()` returns True, with assertion guarding the prim-count invariant ### Camera - Remove `sync_usd_on_fabric_write=True` from FrameView construction in `camera.py` ## Benchmark Results 1024 prims, 50 iterations, NVIDIA L40 GPU: | Operation | USD (ms) | Fabric (ms) | Speedup | |---|---|---|---| | Get World Poses | 14.71 | 0.07 | **203x** | | Set World Poses | 40.75 | 0.16 | **259x** | | Interleaved Set→Get | 55.90 | 0.24 | **232x** | | Get Local Poses | 11.08 | 11.12 | 1.0x | | Set Local Poses | 16.14 | 16.28 | 1.0x | Local poses fall back to USD (expected — Fabric only accelerates world poses via `omni:fabric:worldMatrix`). ## Tests Added | Test | What it validates | |------|------------------| | `test_camera_pose_update_reflected_in_render` | Camera pose changes propagate to rendered depth (close vs far) for CPU/GPU, tiled/non-tiled | | `test_fabric_set_world_does_not_write_back_to_usd` | Fabric writes stay in Fabric, USD prim unchanged | | `test_set_world_updates_local` (xfail) | Documents Issue #5: `set_world_poses` doesn't update local pose in Fabric mode | ## Test Results | Test Suite | Passed | Skipped | Xfailed | Total | |---|---|---|---|---| | Fabric contract tests (`test_views_xform_prim_fabric.py`) | 17 | 16 | 1 | 34 | | USD contract tests (`test_views_xform_prim.py`) | 45 | 0 | 0 | 45 | | Camera render test (`test_tiled_camera.py`) | 8 | 0 | 0 | 8 | ## Type of change - Performance improvement (removes redundant USD writeback on Fabric operations) ## Checklist - [x] I have read and understood the [contribution guidelines](https://isaac-sim.github.io/IsaacLab/main/source/refs/contributing.html) - [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 *No doc changes needed (parameter wasn't referenced in any docs)* --- CONTRIBUTORS.md | 1 + .../fix-fabric-prepare-for-reuse.rst | 8 + .../isaaclab/sensors/camera/camera.py | 7 +- .../isaaclab/sim/views/usd_frame_view.py | 3 +- source/isaaclab/test/sensors/test_camera.py | 66 +++++++++ .../test_multi_mesh_ray_caster_camera.py | 4 +- .../test/sensors/test_ray_caster_camera.py | 4 +- .../fix-fabric-prepare-for-reuse.rst | 12 ++ .../sim/views/fabric_frame_view.py | 135 ++++++++++++----- .../test/sim/test_views_xform_prim_fabric.py | 137 +++++++++++++++++- 10 files changed, 323 insertions(+), 54 deletions(-) create mode 100644 source/isaaclab/changelog.d/fix-fabric-prepare-for-reuse.rst create mode 100644 source/isaaclab_physx/changelog.d/fix-fabric-prepare-for-reuse.rst diff --git a/CONTRIBUTORS.md b/CONTRIBUTORS.md index 82c5eb49ba92..a13693c64171 100644 --- a/CONTRIBUTORS.md +++ b/CONTRIBUTORS.md @@ -144,6 +144,7 @@ Guidelines for modifications: * Patrick Yin * Paul Reeves * Peter Du +* Peter Verswyvelen * Philipp Reist * Piotr Barejko * Pulkit Goyal diff --git a/source/isaaclab/changelog.d/fix-fabric-prepare-for-reuse.rst b/source/isaaclab/changelog.d/fix-fabric-prepare-for-reuse.rst new file mode 100644 index 000000000000..20a6d385c094 --- /dev/null +++ b/source/isaaclab/changelog.d/fix-fabric-prepare-for-reuse.rst @@ -0,0 +1,8 @@ +Changed +^^^^^^^ + +* Updated :class:`~isaaclab.sensors.camera.Camera` to construct its internal + :class:`~isaaclab.sim.views.FrameView` without the now-removed + ``sync_usd_on_fabric_write`` kwarg. USD attributes on camera prims are + no longer kept in sync with Fabric writes; read poses through the view's + getters instead. diff --git a/source/isaaclab/isaaclab/sensors/camera/camera.py b/source/isaaclab/isaaclab/sensors/camera/camera.py index be52668dbd6c..675ee4a7bb7c 100644 --- a/source/isaaclab/isaaclab/sensors/camera/camera.py +++ b/source/isaaclab/isaaclab/sensors/camera/camera.py @@ -18,8 +18,7 @@ import isaaclab.sim as sim_utils import isaaclab.utils.sensors as sensor_utils from isaaclab.app.settings_manager import get_settings_manager -from isaaclab.renderers import BaseRenderer -from isaaclab.renderers.camera_render_spec import CameraRenderSpec +from isaaclab.renderers import BaseRenderer, CameraRenderSpec from isaaclab.sim.views import FrameView from isaaclab.utils import to_camel_case from isaaclab.utils.math import ( @@ -380,9 +379,7 @@ def _initialize_impl(self): # references to prims located in the stage. sim_ctx.render_context.ensure_prepare_stage(self.stage, self._num_envs) - # Create a view for the sensor with Fabric enabled for fast pose queries. - # TODO: remove sync_usd_on_fabric_write=True once the GPU Fabric sync bug is fixed. - self._view = FrameView(self.cfg.prim_path, device=self._device, stage=self.stage, sync_usd_on_fabric_write=True) + self._view = FrameView(self.cfg.prim_path, device=self._device, stage=self.stage) # Check that sizes are correct if self._view.count != self._num_envs: raise RuntimeError( diff --git a/source/isaaclab/isaaclab/sim/views/usd_frame_view.py b/source/isaaclab/isaaclab/sim/views/usd_frame_view.py index 7730c3dd735d..88392d54b2a0 100644 --- a/source/isaaclab/isaaclab/sim/views/usd_frame_view.py +++ b/source/isaaclab/isaaclab/sim/views/usd_frame_view.py @@ -72,8 +72,7 @@ def __init__( stage: USD stage to search for prims. Defaults to None, in which case the current active stage from the simulation context is used. **kwargs: Additional keyword arguments (ignored). Allows forward-compatible - construction when callers pass backend-specific options like - ``sync_usd_on_fabric_write``. + construction when callers pass backend-specific options. Raises: ValueError: If any matched prim is not Xformable or doesn't have standardized diff --git a/source/isaaclab/test/sensors/test_camera.py b/source/isaaclab/test/sensors/test_camera.py index daed8e95773d..99c93fec7323 100644 --- a/source/isaaclab/test/sensors/test_camera.py +++ b/source/isaaclab/test/sensors/test_camera.py @@ -1161,6 +1161,72 @@ def cleanup(self, render_data): Renderer._registry.pop(backend, None) +@pytest.mark.parametrize("device", ["cuda:0", "cpu"]) +@pytest.mark.isaacsim_ci +def test_camera_pose_update_reflected_in_render(setup_camera_device, device): + """Camera pose changes via FrameView should be visible in rendered depth. + + Moves the camera close then far, renders depth, and verifies that the mean + valid depth from the far position is significantly larger (>1.5×) than the + close position. This validates that Fabric-side pose writes (via + PrepareForReuse) and USD writes are correctly propagated to the RTX + renderer. + """ + sim, _unused_cam_cfg, dt = setup_camera_device + + cam_cfg = CameraCfg( + prim_path="/World/PoseTestCam", + height=128, + width=256, + update_period=0, + update_latest_camera_pose=True, + data_types=["distance_to_camera"], + spawn=sim_utils.PinholeCameraCfg( + focal_length=24.0, + focus_distance=400.0, + horizontal_aperture=20.955, + clipping_range=(0.1, 1.0e5), + ), + ) + camera = Camera(cam_cfg) + try: + sim.reset() + + target = torch.tensor([[0.0, 0.0, 0.0]], dtype=torch.float32, device=camera.device) + max_range = cam_cfg.spawn.clipping_range[1] + + # -- close position -- + eyes_close = torch.tensor([[2.0, 2.0, 2.0]], dtype=torch.float32, device=camera.device) + camera.set_world_poses_from_view(eyes_close, target) + sim.step() + camera.update(dt) + depth_close = camera.data.output["distance_to_camera"].clone() + + # -- far position -- + eyes_far = torch.tensor([[8.0, 8.0, 8.0]], dtype=torch.float32, device=camera.device) + camera.set_world_poses_from_view(eyes_far, target) + sim.step() + camera.update(dt) + depth_far = camera.data.output["distance_to_camera"].clone() + + # -- validate -- + valid_close = depth_close[depth_close < max_range] + valid_far = depth_far[depth_far < max_range] + + assert valid_close.numel() > 0, "No valid close-range depth pixels" + assert valid_far.numel() > 0, "No valid far-range depth pixels" + + mean_close = valid_close.mean().item() + mean_far = valid_far.mean().item() + + assert mean_far > mean_close * 1.5, ( + f"Far depth ({mean_far:.2f}) should be > 1.5× close depth ({mean_close:.2f}). " + "Camera pose change may not be reaching the renderer." + ) + finally: + del camera + + def _populate_scene(): """Add prims to the scene.""" # Ground-plane diff --git a/source/isaaclab/test/sensors/test_multi_mesh_ray_caster_camera.py b/source/isaaclab/test/sensors/test_multi_mesh_ray_caster_camera.py index 8657c938c691..7e7efe16d091 100644 --- a/source/isaaclab/test/sensors/test_multi_mesh_ray_caster_camera.py +++ b/source/isaaclab/test/sensors/test_multi_mesh_ray_caster_camera.py @@ -752,11 +752,11 @@ def test_output_equal_to_usd_camera_when_intrinsics_set(setup_simulation): # set camera position camera_warp.set_world_poses_from_view( - eyes=torch.tensor([[0.0, 0.0, 5.0]], device=camera_warp.device), + eyes=torch.tensor([[0.1, 0.0, 5.0]], device=camera_warp.device), targets=torch.tensor([[0.0, 0.0, 0.0]], device=camera_warp.device), ) camera_usd.set_world_poses_from_view( - eyes=torch.tensor([[0.0, 0.0, 5.0]], device=camera_usd.device), + eyes=torch.tensor([[0.1, 0.0, 5.0]], device=camera_usd.device), targets=torch.tensor([[0.0, 0.0, 0.0]], device=camera_usd.device), ) diff --git a/source/isaaclab/test/sensors/test_ray_caster_camera.py b/source/isaaclab/test/sensors/test_ray_caster_camera.py index a913d38dd833..752734936934 100644 --- a/source/isaaclab/test/sensors/test_ray_caster_camera.py +++ b/source/isaaclab/test/sensors/test_ray_caster_camera.py @@ -898,11 +898,11 @@ def test_output_equal_to_usd_camera_when_intrinsics_set(setup_sim, focal_length_ # set camera position camera_warp.set_world_poses_from_view( - eyes=torch.tensor([[0.001, 0.0, 5.0]], device=camera_warp.device), + eyes=torch.tensor([[0.1, 0.0, 5.0]], device=camera_warp.device), targets=torch.tensor([[0.0, 0.0, 0.0]], device=camera_warp.device), ) camera_usd.set_world_poses_from_view( - eyes=torch.tensor([[0.001, 0.0, 5.0]], device=camera_usd.device), + eyes=torch.tensor([[0.1, 0.0, 5.0]], device=camera_usd.device), targets=torch.tensor([[0.0, 0.0, 0.0]], device=camera_usd.device), ) diff --git a/source/isaaclab_physx/changelog.d/fix-fabric-prepare-for-reuse.rst b/source/isaaclab_physx/changelog.d/fix-fabric-prepare-for-reuse.rst new file mode 100644 index 000000000000..e7d842da72bd --- /dev/null +++ b/source/isaaclab_physx/changelog.d/fix-fabric-prepare-for-reuse.rst @@ -0,0 +1,12 @@ +Changed +^^^^^^^ + +* **Breaking:** Removed the ``sync_usd_on_fabric_write`` keyword argument from + :class:`~isaaclab_physx.sim.views.FabricFrameView`. Fabric writes + (``set_world_poses``, ``set_scales``) now notify the renderer via + ``PrepareForReuse()`` on the underlying ``PrimSelection`` instead of writing + back to USD, which is ~200x faster and avoids the stale USD shadow state the + old path produced. Callers passing ``sync_usd_on_fabric_write=True`` should + remove the argument; if they relied on USD reflecting Fabric writes, they + should now read Fabric poses directly via the view's getters or refresh USD + explicitly. diff --git a/source/isaaclab_physx/isaaclab_physx/sim/views/fabric_frame_view.py b/source/isaaclab_physx/isaaclab_physx/sim/views/fabric_frame_view.py index de65e8501793..1bcff86d57ac 100644 --- a/source/isaaclab_physx/isaaclab_physx/sim/views/fabric_frame_view.py +++ b/source/isaaclab_physx/isaaclab_physx/sim/views/fabric_frame_view.py @@ -23,6 +23,12 @@ logger = logging.getLogger(__name__) +# TODO: extend this to ``cuda:N`` once we wire up multi-GPU support for the view. +# Recent Kit / USDRT releases do support multi-GPU ``SelectPrims``, but the +# rest of the FabricFrameView wiring (selections, indexed arrays, etc.) still +# assumes a single device — to be tackled in a follow-up. +_fabric_supported_devices = ("cpu", "cuda", "cuda:0") + def _to_float32_2d(a: wp.array | torch.Tensor) -> wp.array | torch.Tensor: """Ensure array is compatible with Fabric kernels (2-D float32). @@ -47,9 +53,15 @@ class FabricFrameView(BaseFrameView): fallback and non-accelerated operations (local poses, visibility, scales when Fabric is disabled). - When Fabric is enabled, world-pose and scale operations use GPU-accelerated - Warp kernels operating on ``omni:fabric:worldMatrix``. All other operations - delegate to the internal USD view. + When Fabric is enabled, world-pose and scale operations use Warp kernels + operating on ``omni:fabric:worldMatrix``. All other operations delegate + to the internal USD view. + + After every Fabric write (``set_world_poses``, ``set_scales``), + :meth:`PrepareForReuse` is called on the ``PrimSelection`` to notify + the FSD renderer that Fabric data has changed and to detect topology + changes that require rebuilding internal mappings. Read operations + do not call PrepareForReuse to avoid unnecessary renderer invalidation. Pose getters return :class:`~isaaclab.utils.warp.ProxyArray`. Setters accept ``wp.array``. """ @@ -59,27 +71,32 @@ def __init__( prim_path: str, device: str = "cpu", validate_xform_ops: bool = True, - sync_usd_on_fabric_write: bool = False, stage: Usd.Stage | None = None, + **kwargs, ): + """Initialize the view. + + Args: + prim_path: USD prim-path pattern to match. + device: Device for Warp arrays (``"cpu"`` or ``"cuda:0"``). + validate_xform_ops: Whether to validate prim xform-ops. + stage: USD stage; defaults to the current sim context's stage. + **kwargs: Additional keyword arguments (ignored). Matches the signature of + :class:`~isaaclab.sim.views.UsdFrameView` so that the top-level + :class:`~isaaclab.sim.views.FrameView` factory can forward backend-agnostic + kwargs without each backend having to know about every option. + """ self._usd_view = UsdFrameView(prim_path, device=device, validate_xform_ops=validate_xform_ops, stage=stage) self._device = device - self._sync_usd_on_fabric_write = sync_usd_on_fabric_write settings = SettingsManager.instance() self._use_fabric = bool(settings.get("/physics/fabricEnabled", False)) - if self._use_fabric and self._device == "cpu": - logger.warning( - "Fabric mode with Warp fabric-array operations is not supported on CPU devices. " - "Falling back to standard USD operations on the CPU. This may impact performance." - ) - self._use_fabric = False - - if self._use_fabric and self._device not in ("cuda", "cuda:0"): + if self._use_fabric and self._device not in _fabric_supported_devices: logger.warning( f"Fabric mode is not supported on device '{self._device}'. " - "USDRT SelectPrims and Warp fabric arrays only support cuda:0. " + "USDRT SelectPrims and Warp fabric arrays are currently " + f"only supported on {', '.join(_fabric_supported_devices)}. " "Falling back to standard USD operations. This may impact performance." ) self._use_fabric = False @@ -136,6 +153,8 @@ def set_world_poses(self, positions=None, orientations=None, indices=None): if not self._fabric_initialized: self._initialize_fabric() + self._prepare_for_reuse() + indices_wp = self._resolve_indices_wp(indices) count = indices_wp.shape[0] @@ -167,8 +186,6 @@ def set_world_poses(self, positions=None, orientations=None, indices=None): self._fabric_hierarchy.update_world_xforms() self._fabric_usd_sync_done = True - if self._sync_usd_on_fabric_write: - self._usd_view.set_world_poses(positions, orientations, indices) def get_world_poses(self, indices: wp.array | None = None) -> tuple[ProxyArray, ProxyArray]: if not self._use_fabric: @@ -231,6 +248,8 @@ def set_scales(self, scales, indices=None): if not self._fabric_initialized: self._initialize_fabric() + self._prepare_for_reuse() + indices_wp = self._resolve_indices_wp(indices) count = indices_wp.shape[0] @@ -258,8 +277,6 @@ def set_scales(self, scales, indices=None): self._fabric_hierarchy.update_world_xforms() self._fabric_usd_sync_done = True - if self._sync_usd_on_fabric_write: - self._usd_view.set_scales(scales, indices) def get_scales(self, indices=None): if not self._use_fabric: @@ -297,6 +314,56 @@ def get_scales(self, indices=None): wp.synchronize() return scales_wp + # ------------------------------------------------------------------ + # Internal — PrepareForReuse (renderer notification + topology tracking) + # ------------------------------------------------------------------ + + def _prepare_for_reuse(self) -> None: + """Call PrepareForReuse on the PrimSelection to notify the renderer. + + PrepareForReuse serves two purposes: + + 1. **Renderer notification**: Tells FSD/Storm that Fabric data has + been (or will be) modified, so the next rendered frame reflects + the updated transforms. + 2. **Topology change detection**: Returns True when Fabric's + internal memory layout changed (e.g., prims added/removed). + In that case, view-to-fabric index mappings and fabricarrays + must be rebuilt. + """ + if self._fabric_selection is None: + return + + topology_changed = self._fabric_selection.PrepareForReuse() + if topology_changed: + logger.info("Fabric topology changed — rebuilding view-to-fabric index mapping.") + self._rebuild_fabric_arrays() + + def _rebuild_fabric_arrays(self) -> None: + """Rebuild fabricarray and view↔fabric mappings after a topology change. + + Note: Only index mappings and fabricarrays are rebuilt. Position/orientation/scale + buffers are *not* resized because ``self.count`` is derived from the USD prim-path + pattern (via ``_usd_view.count``) and does not change when Fabric rearranges its + internal memory layout. The assertion below guards this invariant. + """ + assert self.count == self._default_view_indices.shape[0], ( + f"Prim count changed ({self.count} vs {self._default_view_indices.shape[0]}). " + "Fabric topology change added/removed tracked prims — full re-initialization required." + ) + self._view_to_fabric = wp.zeros((self.count,), dtype=wp.uint32, device=self._fabric_device) + self._fabric_to_view = wp.fabricarray(self._fabric_selection, self._view_index_attr) + + wp.launch( + kernel=fabric_utils.set_view_to_fabric_array, + dim=self._fabric_to_view.shape[0], + inputs=[self._fabric_to_view, self._view_to_fabric], + device=self._fabric_device, + ) + wp.synchronize() + + self._fabric_world_matrices = wp.fabricarray(self._fabric_selection, "omni:fabric:worldMatrix") + # ------------------------------------------------------------------ # Internal — Fabric initialization # ------------------------------------------------------------------ @@ -337,34 +404,25 @@ def _initialize_fabric(self) -> None: ) wp.synchronize() - fabric_device = self._device - if self._device == "cuda": - logger.warning("Fabric device is not specified, defaulting to 'cuda:0'.") - fabric_device = "cuda:0" - elif self._device.startswith("cuda:"): - if self._device != "cuda:0": - logger.debug( - f"SelectPrims only supports cuda:0. Using cuda:0 for SelectPrims " - f"even though simulation device is {self._device}." - ) - fabric_device = "cuda:0" + # The constructor should have taken care of this, but double check here to avoid regressions + assert self._device in _fabric_supported_devices self._fabric_selection = fabric_stage.SelectPrims( require_attrs=[ (usdrt.Sdf.ValueTypeNames.UInt, self._view_index_attr, usdrt.Usd.Access.Read), (usdrt.Sdf.ValueTypeNames.Matrix4d, "omni:fabric:worldMatrix", usdrt.Usd.Access.ReadWrite), ], - device=fabric_device, + device=self._device, ) - self._view_to_fabric = wp.zeros((self.count,), dtype=wp.uint32, device=fabric_device) + self._view_to_fabric = wp.zeros((self.count,), dtype=wp.uint32, device=self._device) self._fabric_to_view = wp.fabricarray(self._fabric_selection, self._view_index_attr) wp.launch( kernel=fabric_utils.set_view_to_fabric_array, dim=self._fabric_to_view.shape[0], inputs=[self._fabric_to_view, self._view_to_fabric], - device=fabric_device, + device=self._device, ) wp.synchronize() @@ -376,13 +434,17 @@ def _initialize_fabric(self) -> None: self._fabric_dummy_buffer = wp.zeros((0, 3), dtype=wp.float32, device=self._device) self._fabric_world_matrices = wp.fabricarray(self._fabric_selection, "omni:fabric:worldMatrix") self._fabric_stage = fabric_stage - self._fabric_device = fabric_device + self._fabric_device = self._device self._fabric_initialized = True self._fabric_usd_sync_done = False def _sync_fabric_from_usd_once(self) -> None: - """Sync Fabric world matrices from USD once, on the first read.""" + """Sync Fabric world matrices from USD once, on the first read. + + ``set_world_poses`` and ``set_scales`` each set ``_fabric_usd_sync_done`` + themselves, so no explicit flag assignment is needed here. + """ if not self._fabric_initialized: self._initialize_fabric() @@ -391,13 +453,8 @@ def _sync_fabric_from_usd_once(self) -> None: orientations_usd = orientations_usd_ta.warp scales_usd = self._usd_view.get_scales() - prev_sync = self._sync_usd_on_fabric_write - self._sync_usd_on_fabric_write = False self.set_world_poses(positions_usd, orientations_usd) self.set_scales(scales_usd) - self._sync_usd_on_fabric_write = prev_sync - - self._fabric_usd_sync_done = True def _resolve_indices_wp(self, indices: wp.array | None) -> wp.array: """Resolve view indices as a Warp uint32 array.""" diff --git a/source/isaaclab_physx/test/sim/test_views_xform_prim_fabric.py b/source/isaaclab_physx/test/sim/test_views_xform_prim_fabric.py index 4376c0e0b8ea..f0c18ccb98c7 100644 --- a/source/isaaclab_physx/test/sim/test_views_xform_prim_fabric.py +++ b/source/isaaclab_physx/test/sim/test_views_xform_prim_fabric.py @@ -21,8 +21,9 @@ import pytest # noqa: E402 import torch # noqa: E402 +import warp as wp # noqa: E402 from frame_view_contract_utils import * # noqa: F401, F403, E402 -from frame_view_contract_utils import CHILD_OFFSET, ViewBundle # noqa: E402 +from frame_view_contract_utils import CHILD_OFFSET, ViewBundle, test_set_world_updates_local # noqa: E402 from isaaclab_physx.sim.views import FabricFrameView as FrameView # noqa: E402 from pxr import Gf, UsdGeom # noqa: E402 @@ -45,8 +46,6 @@ def test_setup_teardown(): def _skip_if_unavailable(device: str): if device.startswith("cuda") and not torch.cuda.is_available(): pytest.skip("CUDA not available") - if device == "cpu": - pytest.skip("Warp fabricarray operations on CPU have known issues") # ------------------------------------------------------------------ @@ -95,7 +94,7 @@ def factory(num_envs: int, device: str) -> ViewBundle: sim_utils.create_prim(f"/World/Parent_{i}/Child", "Camera", translation=CHILD_OFFSET, stage=stage) sim_utils.SimulationContext(sim_utils.SimulationCfg(dt=0.01, device=device, use_fabric=True)) - view = FrameView("/World/Parent_.*/Child", device=device, sync_usd_on_fabric_write=True) + view = FrameView("/World/Parent_.*/Child", device=device) return ViewBundle( view=view, get_parent_pos=_get_parent_positions, @@ -104,3 +103,133 @@ def factory(num_envs: int, device: str) -> ViewBundle: ) return factory + + +# ------------------------------------------------------------------ +# Override shared contract test with expected failure for Fabric. +# FabricFrameView.set_world_poses writes to Fabric worldMatrix only; the local +# pose (read via USD) does not reflect the change because there is no +# Fabric → USD writeback for local poses. This is tracked as Issue #5 +# (localMatrix: set_local_poses falls back to USD). +# ------------------------------------------------------------------ + + +@pytest.mark.parametrize("device", ["cpu", "cuda:0"]) +@pytest.mark.xfail( + reason=( + "Issue #5: FabricFrameView.set_world_poses writes to Fabric worldMatrix only. " + "get_local_poses reads from stale USD because there is no Fabric→USD " + "writeback for local poses." + ), + strict=True, +) +def test_set_world_updates_local(device, view_factory): # noqa: F811 + """Override the shared test to mark it as expected failure.""" + from frame_view_contract_utils import test_set_world_updates_local as _impl # noqa: PLC0415 + + _impl(device, view_factory) + + +# ------------------------------------------------------------------ +# Fabric-specific tests (not in shared contract) +# ------------------------------------------------------------------ + + +@wp.kernel +def _fill_position(out: wp.array(dtype=wp.float32, ndim=2), x: float, y: float, z: float): + i = wp.tid() + out[i, 0] = wp.float32(x) + out[i, 1] = wp.float32(y) + out[i, 2] = wp.float32(z) + + +@pytest.mark.parametrize("device", ["cpu", "cuda:0"]) +def test_fabric_set_world_does_not_write_back_to_usd(device, view_factory): + """Verify that set_world_poses in Fabric mode does NOT sync back to USD. + + This confirms the removal of sync_usd_on_fabric_write. After calling + set_world_poses, the USD prim's xformOps should still contain the + original (stale) values. + """ + bundle = view_factory(1, device) + view = bundle.view + + # Capture the original USD world position BEFORE any Fabric write + stage = sim_utils.get_current_stage() + prim = stage.GetPrimAtPath(view.prim_paths[0]) + xform_cache = UsdGeom.XformCache() + usd_tf_before = xform_cache.GetLocalToWorldTransform(prim) + usd_t_before = usd_tf_before.ExtractTranslation() + orig_usd_pos = torch.tensor([float(usd_t_before[0]), float(usd_t_before[1]), float(usd_t_before[2])]) + + # Write to Fabric — move to (99, 99, 99) + new_pos = wp.zeros((1, 3), dtype=wp.float32, device=device) + wp.launch(kernel=_fill_position, dim=1, inputs=[new_pos, 99.0, 99.0, 99.0], device=device) + view.set_world_poses(positions=new_pos) + + # Verify Fabric has the new position + fab_pos, _ = view.get_world_poses() + pos_torch = wp.to_torch(fab_pos) + assert torch.allclose(pos_torch, torch.tensor([[99.0, 99.0, 99.0]], device=device), atol=0.1), ( + f"Fabric should have new position, got {pos_torch}" + ) + + # Verify USD still has the ORIGINAL position (no writeback). Equality, not + # approximate — USD should literally not have moved, so any drift would + # indicate a residual writeback path. + xform_cache_after = UsdGeom.XformCache() + usd_tf_after = xform_cache_after.GetLocalToWorldTransform(prim) + usd_t_after = usd_tf_after.ExtractTranslation() + usd_pos_after = torch.tensor([float(usd_t_after[0]), float(usd_t_after[1]), float(usd_t_after[2])]) + assert torch.allclose(usd_pos_after, orig_usd_pos, atol=0.0), ( + f"USD should still have original position {orig_usd_pos}, but got {usd_pos_after}. " + f"sync_usd_on_fabric_write may not have been fully removed." + ) + + +@pytest.mark.parametrize("device", ["cpu", "cuda:0"]) +def test_fabric_rebuild_after_topology_change(device, view_factory, monkeypatch): + """Forcing the topology-changed branch on a write triggers + :meth:`_rebuild_fabric_arrays` and leaves the view in a state where + subsequent writes/reads still produce correct data. + + Real ``PrimSelection.PrepareForReuse`` reports topology change only when + Fabric reallocates internally, which is hard to provoke from a unit test. + Instead we monkeypatch ``_prepare_for_reuse`` on the instance to always + take the rebuild branch and verify the view remains usable. + """ + bundle = view_factory(2, device) + view = bundle.view + + # First write — initializes Fabric and binds _fabric_selection. + initial = wp.zeros((2, 3), dtype=wp.float32, device=device) + wp.launch(kernel=_fill_position, dim=2, inputs=[initial, 1.0, 2.0, 3.0], device=device) + view.set_world_poses(positions=initial) + + rebuild_calls = [] + real_rebuild = view._rebuild_fabric_arrays + + def spy_rebuild(): + rebuild_calls.append(True) + real_rebuild() + + def force_topology_changed(): + if view._fabric_selection is not None: + view._fabric_selection.PrepareForReuse() + spy_rebuild() + + monkeypatch.setattr(view, "_prepare_for_reuse", force_topology_changed) + + # Trigger another write — goes through the forced topology-change branch. + new = wp.zeros((2, 3), dtype=wp.float32, device=device) + wp.launch(kernel=_fill_position, dim=2, inputs=[new, 4.0, 5.0, 6.0], device=device) + view.set_world_poses(positions=new) + + assert rebuild_calls, "Forced topology-change branch did not invoke _rebuild_fabric_arrays" + + # Read back — proves the rebuilt _view_to_fabric and _fabric_world_matrices + # are still consistent. + ret_pos, _ = view.get_world_poses() + pos_torch = wp.to_torch(ret_pos) + expected = torch.tensor([[4.0, 5.0, 6.0], [4.0, 5.0, 6.0]], device=device) + assert torch.allclose(pos_torch, expected, atol=1e-7), f"Read after rebuild failed on {device}: {pos_torch}" From b258e87c7c6e8c6695b8ce15d547530199eb0e10 Mon Sep 17 00:00:00 2001 From: John Date: Wed, 6 May 2026 15:30:42 -0700 Subject: [PATCH 06/51] Update pytorch3d installation command in locomanipulation SDG documentation (#5506) # Description This PR changes the PyTorch3d installation command in the locomanipulation SDG policy training / rollout to use git and install pytorch3d from source. Fixes # (issue) NV bug 6115836 ## Type of change - Bug fix (non-breaking change which fixes an issue) ## Screenshots Please attach before and after screenshots of the change if applicable. ## Checklist - [ ] I have read and understood the [contribution guidelines](https://isaac-sim.github.io/IsaacLab/main/source/refs/contributing.html) - [ ] I have run the [`pre-commit` checks](https://pre-commit.com/) with `./isaaclab.sh --format` - [ ] I have made corresponding changes to the documentation - [ ] My changes generate no new warnings - [ ] I have added tests that prove my fix is effective or that my feature works - [ ] I have updated the changelog and the corresponding version in the extension's `config/extension.toml` file - [ ] I have added my name to the `CONTRIBUTORS.md` or my name already exists there --- docs/source/overview/imitation-learning/humanoids_imitation.rst | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/source/overview/imitation-learning/humanoids_imitation.rst b/docs/source/overview/imitation-learning/humanoids_imitation.rst index 694c3225dbf1..ae9989ddd8de 100644 --- a/docs/source/overview/imitation-learning/humanoids_imitation.rst +++ b/docs/source/overview/imitation-learning/humanoids_imitation.rst @@ -629,7 +629,7 @@ Then, from the **Isaac-GR00T** directory, install GR00T N1.5 and its dependencie uv pip install -e . uv pip install wheel MAX_JOBS=4 uv pip install --no-build-isolation flash-attn==2.7.1.post4 - MAX_JOBS=4 uv pip install --no-build-isolation pytorch3d + MAX_JOBS=4 uv pip install --no-build-isolation 'git+https://github.com/facebookresearch/pytorch3d.git@v0.7.9' uv pip install diffusers decord zmq Convert dataset to LeRobot format From 7b44452e9fa2893522332d70f542f6d232dc8e09 Mon Sep 17 00:00:00 2001 From: r-schmitt <139814266+r-schmitt@users.noreply.github.com> Date: Thu, 7 May 2026 11:53:13 -0400 Subject: [PATCH 07/51] use RendererCfg as default renderer_cfg in CameraCfg (#5521) # Description the camera config was importing `isaaclab_physx.renderers` because the default render_cfg was set to that config. this PR sets that to RendererConfig to remove the import, but provides a get_default_render_config method to the backend_utils to lazily import the config if needed. this is called __post_init__ on the camera config to replace the generic config as soon as possible to avoid downstream issues referencing the renderer config. this action can be moved to the factory if downstream references are cleaned up. ## Type of change - Refactor to remove imports in cfg class ## Checklist - [x] I have read and understood the [contribution guidelines](https://isaac-sim.github.io/IsaacLab/main/source/refs/contributing.html) - [x] I have run the [`pre-commit` checks](https://pre-commit.com/) with `./isaaclab.sh --format` - [x] I have made corresponding changes to the documentation - [x] My changes generate no new warnings - [x] I have added tests that prove my fix is effective or that my feature works - [x] I have updated the changelog and the corresponding version in the extension's `config/extension.toml` file - [x] I have added my name to the `CONTRIBUTORS.md` or my name already exists there --------- Co-authored-by: nvsekkin <72572910+nvsekkin@users.noreply.github.com> --- .../rschmitt_default_cameracfg_renderer.rst | 11 ++++++ .../isaaclab/sensors/camera/camera.py | 3 +- .../isaaclab/sensors/camera/camera_cfg.py | 12 +++++-- .../sensors/camera/tiled_camera_cfg.py | 8 +++++ .../isaaclab/isaaclab/utils/backend_utils.py | 36 +++++++++++++++++++ 5 files changed, 66 insertions(+), 4 deletions(-) create mode 100644 source/isaaclab/changelog.d/rschmitt_default_cameracfg_renderer.rst diff --git a/source/isaaclab/changelog.d/rschmitt_default_cameracfg_renderer.rst b/source/isaaclab/changelog.d/rschmitt_default_cameracfg_renderer.rst new file mode 100644 index 000000000000..e11891e307b5 --- /dev/null +++ b/source/isaaclab/changelog.d/rschmitt_default_cameracfg_renderer.rst @@ -0,0 +1,11 @@ +Added +^^^^^ + +* Added :meth:`~isaaclab.utils.backend_utils.get_default_renderer_cfg`. to lazy load the IsaacRtxRendererCfg + +Changed +^^^^^^^ + +* :class:`~isaaclab.sensors.camera.CameraCfg` now defaults its render_cfg to :class:`~isaaclab.renderers.RenderCfg` + :meth:`~isaaclab.utils.backend_utils.get_default_renderer_cfg` is called during __post_init__ to replace + the generic RenderCfg with the default config :class:`~isaaclab_physx.renderers.IsaacRtxRendererCfg` diff --git a/source/isaaclab/isaaclab/sensors/camera/camera.py b/source/isaaclab/isaaclab/sensors/camera/camera.py index 675ee4a7bb7c..c481002e524e 100644 --- a/source/isaaclab/isaaclab/sensors/camera/camera.py +++ b/source/isaaclab/isaaclab/sensors/camera/camera.py @@ -113,7 +113,8 @@ def __init__(self, cfg: CameraCfg): # IsaacRtxRendererCfg overrides to flip /isaaclab/render/rtx_sensors. The # flag must be set pre-sim.reset() because SimulationContext.is_rendering # and several env classes read it before the renderer's __init__ runs. - if self.cfg.renderer_cfg.renderer_type == "isaac_rtx": + renderer_type = getattr(self.cfg.renderer_cfg, "renderer_type", None) + if renderer_type == "isaac_rtx": get_settings_manager().set_bool("/isaaclab/render/rtx_sensors", True) # Compute camera orientation (convention conversion) and spawn diff --git a/source/isaaclab/isaaclab/sensors/camera/camera_cfg.py b/source/isaaclab/isaaclab/sensors/camera/camera_cfg.py index 5ee6cf30b6f6..3ecec15d11d3 100644 --- a/source/isaaclab/isaaclab/sensors/camera/camera_cfg.py +++ b/source/isaaclab/isaaclab/sensors/camera/camera_cfg.py @@ -9,8 +9,6 @@ from dataclasses import MISSING, field from typing import TYPE_CHECKING, Literal -from isaaclab_physx.renderers import IsaacRtxRendererCfg - from isaaclab.renderers import RendererCfg from isaaclab.sim import FisheyeCameraCfg, PinholeCameraCfg from isaaclab.utils import configclass @@ -191,7 +189,7 @@ class OffsetCfg: on :attr:`renderer_cfg` instead. """ - renderer_cfg: RendererCfg = field(default_factory=IsaacRtxRendererCfg) + renderer_cfg: RendererCfg = field(default_factory=RendererCfg) """Renderer configuration for camera sensor.""" def __post_init__(self): @@ -201,6 +199,14 @@ def __post_init__(self): :class:`DeprecationWarning` and is copied onto ``self.renderer_cfg`` when that cfg defines the same-named field. """ + # TODO when Camera.__init__ moves rtx_sensor setting out of camera initialization + # the default renderer config instantiation can be moved into the render factory + # and get_default_render_cfg method can be removed from backend_utils + renderer_type = getattr(self.renderer_cfg, "renderer_type", None) + if renderer_type == "default": + from isaaclab.utils.backend_utils import get_default_renderer_cfg + + self.renderer_cfg = get_default_renderer_cfg() # Forwarded by name: any same-named field on ``renderer_cfg`` will receive the value. for field_name, default in _DEPRECATED_RENDERER_FIELD_DEFAULTS.items(): value = getattr(self, field_name) diff --git a/source/isaaclab/isaaclab/sensors/camera/tiled_camera_cfg.py b/source/isaaclab/isaaclab/sensors/camera/tiled_camera_cfg.py index d35ff285ff13..e200468daa78 100644 --- a/source/isaaclab/isaaclab/sensors/camera/tiled_camera_cfg.py +++ b/source/isaaclab/isaaclab/sensors/camera/tiled_camera_cfg.py @@ -27,6 +27,14 @@ class TiledCameraCfg(CameraCfg): class_type: type["TiledCamera"] | str = "{DIR}.tiled_camera:TiledCamera" def __post_init__(self): + # TODO when Camera.__init__ moves rtx_sensor setting out of camera initialization + # the default renderer config instantiation can be moved into the render factory + # and get_default_render_cfg method can be removed from backend_utils + renderer_type = getattr(self.renderer_cfg, "renderer_type", None) + if renderer_type == "default": + from isaaclab.utils.backend_utils import get_default_renderer_cfg + + self.renderer_cfg = get_default_renderer_cfg() warnings.warn( "TiledCameraCfg is deprecated. Use CameraCfg directly — " "Camera now includes TiledCamera's vectorized rendering optimizations.", diff --git a/source/isaaclab/isaaclab/utils/backend_utils.py b/source/isaaclab/isaaclab/utils/backend_utils.py index 9f69a66aa04d..ddc627171ae1 100644 --- a/source/isaaclab/isaaclab/utils/backend_utils.py +++ b/source/isaaclab/isaaclab/utils/backend_utils.py @@ -3,12 +3,48 @@ # # SPDX-License-Identifier: BSD-3-Clause +from __future__ import annotations + import importlib import logging +from typing import TYPE_CHECKING + +if TYPE_CHECKING: + from isaaclab.renderers.renderer_cfg import RendererCfg logger = logging.getLogger(__name__) +def get_default_renderer_cfg() -> RendererCfg: + """Return the default :class:`~isaaclab.renderers.renderer_cfg.RendererCfg` for cameras. + + Lazily imports :mod:`isaaclab_physx.renderers` and returns a new + :class:`~isaaclab_physx.renderers.IsaacRtxRendererCfg` instance. + + Returns: + A new default Isaac RTX renderer configuration. + + Raises: + ImportError: If :mod:`isaaclab_physx.renderers` cannot be imported or does not + expose ``IsaacRtxRendererCfg``. + """ + try: + renderers_mod = importlib.import_module("isaaclab_physx.renderers") + except ImportError as e: + raise ImportError( + "The default camera renderer configuration requires the optional 'isaaclab_physx' " + "package (import 'isaaclab_physx.renderers'). Install isaaclab_physx or set " + "CameraCfg.renderer_cfg explicitly." + ) from e + try: + default_cls = renderers_mod.IsaacRtxRendererCfg + except AttributeError as e: + raise ImportError( + "Module 'isaaclab_physx.renderers' is available but does not define 'IsaacRtxRendererCfg'." + ) from e + return default_cls() + + class FactoryBase: """A generic factory class that dynamically loads backends.""" From b582dab8734eb25dce9fe1b1b044cdf7aeb65a5d Mon Sep 17 00:00:00 2001 From: vidurv-nvidia Date: Thu, 7 May 2026 12:32:35 -0700 Subject: [PATCH 08/51] Refactors schema cfgs to separate solver-common from PhysX-specific fields (#5275) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit # Description Splits IsaacLab's USD-physics cfg classes into solver-common base classes and backend-specific subclasses, and refactors the writers (`modify_*_properties`, `spawn_rigid_body_material`) so that schema application is data-driven rather than hard-coded per-class. Prepares the schema layer for multi-backend support (PhysX today, Newton/Mjc next) without polluting base classes with silently-ignored fields or stamping backend-specific schemas onto prims that didn't opt in. ## Architecture Two layered concepts: 1. **Per-declaring-class routing.** Each cfg field's USD namespace is determined by the class that declares it (walking the MRO). Base-class fields write under `physics:*`; subclass fields write under their own namespace (`physxRigidBody:*`, etc.). When a `PhysxRigidBodyPropertiesCfg` instance is written, base fields still go under `physics:*` because `_usd_namespace` is read from the declaring class via `__dict__`, not via `getattr` (which would hit the subclass override). 2. **Per-field exceptions.** Some "universal physics" fields have no USD path except through a backend-namespaced attribute today (e.g., `disable_gravity` only exists at `physxRigidBody:disableGravity`). These are declared as `_usd_field_exceptions = {applied_schema: (namespace, [fields...])}` on the base class; the writer applies the exception schema only when one of the listed fields is non-None. The single helper `_apply_namespaced_schemas(prim, cfg, cfg_dict)` in `schemas.py` does both passes for every writer (rigid body, collision, articulation root, joint drive, mesh collision, rigid-body material). ## Design constraints **One cfg class per spawner slot.** Spawners (`UsdFileCfg`, `MeshCuboidCfg`, etc.) carry a single field for each property group: `rigid_props: RigidBodyBaseCfg | None`, `collision_props: CollisionBaseCfg | None`, `joint_drive_props: JointDriveBaseCfg | None`, etc. The user cannot pass two cfgs into the same slot, so the cfg class hierarchy must be **single-rooted per spawner field** — one base class per group, with backend-specific subclasses below. This rules out a "PhysX cfg sits next to a Newton cfg as siblings" design and drives several placement decisions: | Constraint | Consequence | |---|---| | Universal-physics fields must be reachable from any backend's cfg | Goes on the **base** class, not a sibling backend cfg. Users on Newton-only deployments can use `RigidBodyBaseCfg(disable_gravity=True)` without importing `isaaclab_physx`. | | A PhysX-namespaced field whose semantics are universal (e.g., `disable_gravity`) | Lives on the base but routes to the PhysX namespace via `_usd_field_exceptions`. The base stays backend-clean; the writer dispatches the PhysX write only when the field is non-None. | | Writer logic must not branch on cfg subclass | Every writer is the same code path regardless of subclass. The cfg metadata (`_usd_namespace`, `_usd_applied_schema`, `_usd_field_exceptions`) drives behavior; the writer is a pure data interpreter. | | Adding a new backend (Newton, Mjc) | Requires a new subclass with its own `_usd_namespace` / `_usd_applied_schema`. No spawner-side changes, no writer-side changes, no base-cfg-side changes. | | A field has multiple USD paths today (one PhysX-namespaced, one Newton-namespaced) | Belongs on the **PhysX subclass**, not the base. A future `NewtonArticulationRootPropertiesCfg` will own the same conceptual field on the Newton side. ("Rule 2" — e.g., `enabled_self_collisions`.) | | A field has only one USD path today, namespaced under PhysX, but the conceptual quantity is universal | Belongs on the **base** with an `_usd_field_exceptions` entry. ("Rule 1" — e.g., `disable_gravity`, `articulation_enabled`, `contact_offset`, `rest_offset`, `max_joint_velocity`.) When Newton ships its own native attribute, the exception namespace switches transparently with no API change. | ## Field placement ### Base (solver-common) classes — `physics:*` namespace via `UsdPhysics.*API` | Cfg class | Field | USD attribute | |---|---|---| | `RigidBodyBaseCfg` | `rigid_body_enabled` | `physics:rigidBodyEnabled` | | `RigidBodyBaseCfg` | `kinematic_enabled` | `physics:kinematicEnabled` | | `CollisionBaseCfg` | `collision_enabled` | `physics:collisionEnabled` | | `MassPropertiesCfg` | `mass` | `physics:mass` | | `MassPropertiesCfg` | `density` | `physics:density` | | `RigidBodyMaterialBaseCfg` | `static_friction` | `physics:staticFriction` | | `RigidBodyMaterialBaseCfg` | `dynamic_friction` | `physics:dynamicFriction` | | `RigidBodyMaterialBaseCfg` | `restitution` | `physics:restitution` | | `JointDriveBaseCfg` | `drive_type` | `drive::physics:type` | | `JointDriveBaseCfg` | `max_force` | `drive::physics:maxForce` | | `JointDriveBaseCfg` | `stiffness` | `drive::physics:stiffness` | | `JointDriveBaseCfg` | `damping` | `drive::physics:damping` | | `MeshCollisionBaseCfg` | `mesh_approximation_name` | `physics:approximation` (token) | | `ArticulationRootBaseCfg` | `fix_root_link` | (synthesizes `UsdPhysics.FixedJoint`) | `JointDriveBaseCfg` and `MeshCollisionBaseCfg` use the typed `UsdPhysics.DriveAPI` / `UsdPhysics.MeshCollisionAPI` accessors at the writer level (multi-instance namespace and `TfToken` with `allowedTokens`, respectively); all other base fields flow through the helper's per-class routing. ### PhysX subclasses — `physx*:*` namespaces, `Physx*API` schemas | Cfg class | `_usd_namespace` | `_usd_applied_schema` | Adds fields | |---|---|---|---| | `PhysxRigidBodyPropertiesCfg` | `physxRigidBody` | `PhysxRigidBodyAPI` | `linear_damping`, `angular_damping`, `max_linear_velocity`, `max_angular_velocity`, `max_depenetration_velocity`, `max_contact_impulse`, `enable_gyroscopic_forces`, `retain_accelerations`, solver iter counts, sleep / stabilization thresholds | | `PhysxCollisionPropertiesCfg` | `physxCollision` | `PhysxCollisionAPI` | `torsional_patch_radius`, `min_torsional_patch_radius` | | `PhysxArticulationRootPropertiesCfg` | `physxArticulation` | `PhysxArticulationAPI` | `enabled_self_collisions`, solver iter counts, sleep / stabilization thresholds | | `PhysxJointDrivePropertiesCfg` | `physxJoint` | `PhysxJointAPI` | (currently empty; reserved for future PhysX-only knobs) | | `PhysxRigidBodyMaterialCfg` | `physxMaterial` | `PhysxMaterialAPI` | `compliant_contact_stiffness`, `compliant_contact_damping`, `friction_combine_mode`, `restitution_combine_mode` | | `PhysxConvexHullPropertiesCfg` | `physxConvexHullCollision` | `PhysxConvexHullCollisionAPI` | `hull_vertex_limit`, `min_thickness` | | `PhysxConvexDecompositionPropertiesCfg` | `physxConvexDecompositionCollision` | `PhysxConvexDecompositionCollisionAPI` | hull / voxel / shrink-wrap tunables | | `PhysxTriangleMeshPropertiesCfg` | `physxTriangleMeshCollision` | `PhysxTriangleMeshCollisionAPI` | `weld_tolerance` | | `PhysxTriangleMeshSimplificationPropertiesCfg` | `physxTriangleMeshSimplificationCollision` | `PhysxTriangleMeshSimplificationCollisionAPI` | `simplification_metric`, `weld_tolerance` | | `PhysxSDFMeshPropertiesCfg` | `physxSDFMeshCollision` | `PhysxSDFMeshCollisionAPI` | `sdf_margin`, `sdf_narrow_band_thickness`, `sdf_resolution`, etc. | ### `_usd_field_exceptions` table These fields are declared on a *base* class but the only USD path today goes through a non-base namespace. Each entry says: "if any listed field on this cfg is non-None, apply the exception schema and write that one attribute under the exception namespace." All other fields on the cfg follow the per-declaring-class routing rule. | Base cfg class | Exception schema | Namespace | Field(s) | Why on the base | |---|---|---|---|---| | `RigidBodyBaseCfg` | `PhysxRigidBodyAPI` | `physxRigidBody` | `disable_gravity` | Per-body gravity exclusion is universal physics; PhysX honors per-body, Newton consumes the same attribute via the bridge resolver (scene-level today; per-body fix is a Newton-side kernel change, not a cfg-API change) | | `CollisionBaseCfg` | `PhysxCollisionAPI` | `physxCollision` | `contact_offset`, `rest_offset` | Collision-pair generation distance and rest gap are universal physics; Newton importer consumes both via PhysX bridge to populate `Model.shape_collision_radius` / `_thickness` (`import_usd.py:2104, 2111`) | | `ArticulationRootBaseCfg` | `PhysxArticulationAPI` | `physxArticulation` | `articulation_enabled` | PhysX honors at sim time; IsaacLab Newton wrapper reads it as a spawn-time guard at `rigid_object.py:1035`. Universal user-facing intent | | `JointDriveBaseCfg` | `PhysxJointAPI` | `physxJoint` | `max_joint_velocity` | Sole USD path to `Model.joint_velocity_limit` in Newton (no `newton:*` equivalent today). The exception namespace switches transparently when Newton ships `newton:maxJointVelocity` as a registered applied API | When any exception field is non-None, the corresponding `Physx*API` schema is applied to the prim. When all exception fields are None, no PhysX schema is stamped — Newton-targeted prims authored from `*BaseCfg` stay free of PhysX schemas they didn't opt in to. ## Field renames (with deprecation aliases) To enforce the convention that python `snake_case` cfg field names map identity-style to USD `camelCase` attribute names, two legacy fields were renamed. Both keep the old name as a deprecation alias forwarded via `__post_init__` (emits `DeprecationWarning`, scheduled for removal in 5.0). | Old name | New name | USD attribute | |---|---|---| | `JointDriveBaseCfg.max_velocity` | `max_joint_velocity` | `physxJoint:maxJointVelocity` | | `JointDriveBaseCfg.max_effort` | `max_force` | `drive::physics:maxForce` | ## Type of change - New feature (non-breaking change which adds functionality) - Breaking change (existing functionality will not work without user modification) The split is non-breaking at the spawner-cfg level — every base-class type accepts any subclass via polymorphism, and every legacy `RigidBodyPropertiesCfg` / `JointDrivePropertiesCfg` / `CollisionPropertiesCfg` / `ArticulationRootPropertiesCfg` / `MeshCollisionPropertiesCfg` / `RigidBodyMaterialCfg` / `FixedTendonPropertiesCfg` / `SpatialTendonPropertiesCfg` import path continues to work via deprecation-alias subclasses and `__getattr__` shims on `isaaclab.sim`, `isaaclab.sim.schemas`, and `isaaclab.sim.schemas.schemas_cfg`. Direct attribute access to the renamed fields still works through deprecation aliases. Removal scheduled for 5.0. The breaking aspect: cfg classes in `isaaclab_physx.sim.schemas` and `isaaclab_physx.sim.spawners.materials` are physically relocated. Anyone importing from internal paths (rather than `isaaclab.sim`) needs to update. ## Migration ```python # Before import isaaclab.sim as sim_utils rigid_props = sim_utils.RigidBodyPropertiesCfg(disable_gravity=True, linear_damping=0.1) joint_props = sim_utils.JointDrivePropertiesCfg(max_effort=80.0, max_velocity=5.0) collision_props = sim_utils.CollisionPropertiesCfg(contact_offset=0.02, torsional_patch_radius=1.0) material = sim_utils.RigidBodyMaterialCfg(static_friction=0.7, compliant_contact_stiffness=1000.0) # After (PhysX-targeted) import isaaclab.sim as sim_utils from isaaclab_physx.sim.schemas import ( PhysxRigidBodyPropertiesCfg, PhysxJointDrivePropertiesCfg, PhysxCollisionPropertiesCfg, ) from isaaclab_physx.sim.spawners.materials import PhysxRigidBodyMaterialCfg rigid_props = PhysxRigidBodyPropertiesCfg(disable_gravity=True, linear_damping=0.1) joint_props = PhysxJointDrivePropertiesCfg(max_force=80.0, max_joint_velocity=5.0) collision_props = PhysxCollisionPropertiesCfg(contact_offset=0.02, torsional_patch_radius=1.0) material = PhysxRigidBodyMaterialCfg(static_friction=0.7, compliant_contact_stiffness=1000.0) # After (Newton-targeted — base classes only, no PhysX schemas applied) from isaaclab.sim.schemas import RigidBodyBaseCfg, JointDriveBaseCfg, CollisionBaseCfg from isaaclab.sim.spawners.materials import RigidBodyMaterialBaseCfg rigid_props = RigidBodyBaseCfg(disable_gravity=True) # only base + exception fields available joint_props = JointDriveBaseCfg(max_force=80.0, max_joint_velocity=5.0) material = RigidBodyMaterialBaseCfg(static_friction=0.7) ``` Spawner type annotations remain unchanged — they accept any subclass via polymorphism. ## Internal helper ```python def _apply_namespaced_schemas(prim, cfg, cfg_dict): # 1. Per-field exceptions: pop listed fields, apply exception schema if any non-None, # write under exception namespace. # 2. Per-declaring-class routing: walk MRO to find each remaining field's owner class; # write under that class's _usd_namespace; apply that class's _usd_applied_schema. ``` Used by all five `modify_*_properties` writers and `spawn_rigid_body_material`. Replaced ~125 lines of duplicated gating logic with a single ~30-line helper. ## Side change: configclass `source/isaaclab/isaaclab/utils/configclass.py:_process_mutable_types` now detects string-form `ClassVar` annotations under PEP 563 (`from __future__ import annotations`) so it doesn't wrap `ClassVar[dict]` defaults in `field(default_factory=...)`. Matches Python stdlib `dataclasses` semantics. No pre-existing IsaacLab class used `ClassVar` inside a `@configclass` block, so the change has no effect on existing code; it enables the `ClassVar` metadata pattern this PR introduces. ## Test plan - [x] `test_schemas.py` (38 → 40 tests): all schema-cfg classes write correct attributes under the right namespace; PhysX schemas are NOT applied when only base/UsdPhysics fields are set; deprecation aliases (`max_velocity` → `max_joint_velocity`, `max_effort` → `max_force`) forward correctly and emit `DeprecationWarning`. **40 passed.** - [x] `test_schemas_shim.py`: legacy import paths (`isaaclab.sim.schemas.RigidBodyPropertiesCfg` etc.) resolve via `__getattr__` shims. **All passing.** - [x] `test_articulation.py`, `test_rigid_object_iface.py`, `test_valid_configs.py`, `test_spawn_*` — no regressions. - [x] Full suite (`./isaaclab.sh -t`): 8768/9205 pass, 437 unrelated baseline failures (rendering, `omni.physics.tensors.api` missing, OSC controller, `install_ci`, `pyglet`, Newton env-path, Anymal-C determinism). Zero new regressions; +123 passing tests vs. earlier state. - [x] `./isaaclab.sh -f` (pre-commit) clean. ## Supersedes Together with #5276, supersedes #4847 and #5203 with a cleaner schema-layer design. ## Checklist - [x] I have read and understood the [contribution guidelines](https://isaac-sim.github.io/IsaacLab/main/source/refs/contributing.html) - [x] I have run the [`pre-commit` checks](https://pre-commit.com/) with `./isaaclab.sh --format` - [x] I have made corresponding changes to the documentation (changelog fragments under `source/isaaclab/changelog.d/`) - [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 (fragment-based system) 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 --------- Co-authored-by: ooctipus --- .../vidur-cfg-exception-table.minor.rst | 27 + .../vidur-rebalance-cfg-placement.minor.rst | 122 +++ source/isaaclab/isaaclab/sim/__init__.py | 69 +- source/isaaclab/isaaclab/sim/__init__.pyi | 12 +- .../sim/converters/mesh_converter_cfg.py | 4 +- .../isaaclab/isaaclab/sim/schemas/__init__.py | 51 +- .../isaaclab/sim/schemas/__init__.pyi | 34 +- .../isaaclab/isaaclab/sim/schemas/schemas.py | 490 +++++++----- .../isaaclab/sim/schemas/schemas_cfg.py | 656 ++++++++------- .../sim/spawners/from_files/from_files_cfg.py | 2 +- .../sim/spawners/materials/__init__.py | 28 +- .../sim/spawners/materials/__init__.pyi | 4 +- .../spawners/materials/physics_materials.py | 52 +- .../materials/physics_materials_cfg.py | 75 +- .../isaaclab/sim/spawners/spawner_cfg.py | 4 +- source/isaaclab/isaaclab/utils/configclass.py | 10 +- source/isaaclab/test/sim/test_schemas.py | 646 ++++++++++++++- source/isaaclab/test/sim/test_schemas_shim.py | 172 ++++ .../vidur-feature-usd-proprties-refactor.skip | 0 .../test/assets/test_articulation.py | 10 +- .../vidur-rebalance-cfg-placement.minor.rst | 77 ++ .../isaaclab_physx/sim/__init__.pyi | 10 +- .../isaaclab_physx/sim/schemas/__init__.pyi | 54 +- .../isaaclab_physx/sim/schemas/schemas_cfg.py | 755 +++++++++++++++++- .../sim/spawners/materials/__init__.pyi | 4 + .../materials/physics_materials_cfg.py | 83 ++ .../test/assets/test_articulation.py | 10 +- 27 files changed, 2762 insertions(+), 699 deletions(-) create mode 100644 source/isaaclab/changelog.d/vidur-cfg-exception-table.minor.rst create mode 100644 source/isaaclab/changelog.d/vidur-rebalance-cfg-placement.minor.rst create mode 100644 source/isaaclab/test/sim/test_schemas_shim.py create mode 100644 source/isaaclab_newton/changelog.d/vidur-feature-usd-proprties-refactor.skip create mode 100644 source/isaaclab_physx/changelog.d/vidur-rebalance-cfg-placement.minor.rst diff --git a/source/isaaclab/changelog.d/vidur-cfg-exception-table.minor.rst b/source/isaaclab/changelog.d/vidur-cfg-exception-table.minor.rst new file mode 100644 index 000000000000..de2d19065b61 --- /dev/null +++ b/source/isaaclab/changelog.d/vidur-cfg-exception-table.minor.rst @@ -0,0 +1,27 @@ +Changed +^^^^^^^ + +* Cleaned up the schema-cfg base classes to no longer carry PhysX namespace metadata. + :class:`~isaaclab.sim.schemas.RigidBodyBaseCfg`, + :class:`~isaaclab.sim.schemas.CollisionBaseCfg`, + :class:`~isaaclab.sim.schemas.ArticulationRootBaseCfg`, and + :class:`~isaaclab.sim.schemas.JointDriveBaseCfg` now declare ``_usd_namespace = None`` and + ``_usd_applied_schema = None``. Per-field PhysX overrides for fields whose only USD path + today is the ``physx*:*`` namespace (``disable_gravity``, ``contact_offset``, + ``rest_offset``, ``articulation_enabled``, ``max_velocity``) are declared via a new + ``_usd_field_exceptions`` mapping ``applied_schema -> (namespace, {cfg_field: usd_attr})``. + When any listed field is non-None at write time, the writer applies that schema and writes + the attribute under the exception namespace; otherwise the schema is not stamped onto the + prim. PhysX subclasses (:class:`PhysxRigidBodyPropertiesCfg`, + :class:`PhysxCollisionPropertiesCfg`, :class:`PhysxArticulationRootPropertiesCfg`, + :class:`PhysxJointDrivePropertiesCfg`) now self-declare ``_usd_namespace`` and + ``_usd_applied_schema`` for their own fields. Observable behavior on standard inputs is + unchanged. +* Consolidated the per-writer schema-application loop in + :mod:`isaaclab.sim.schemas` into a single shared helper ``_apply_namespaced_schemas``. + ``modify_articulation_root_properties``, ``modify_rigid_body_properties``, + ``modify_collision_properties``, ``modify_joint_drive_properties``, + ``modify_mesh_collision_properties``, and ``spawn_rigid_body_material`` all delegate to the + helper after writing their typed-API ``UsdPhysics`` fields. The canonical exception-table + + main-namespace gating logic now lives in one place instead of being duplicated across + six call sites. diff --git a/source/isaaclab/changelog.d/vidur-rebalance-cfg-placement.minor.rst b/source/isaaclab/changelog.d/vidur-rebalance-cfg-placement.minor.rst new file mode 100644 index 000000000000..72be33772d9d --- /dev/null +++ b/source/isaaclab/changelog.d/vidur-rebalance-cfg-placement.minor.rst @@ -0,0 +1,122 @@ +Added +^^^^^ + +* Added :class:`~isaaclab.sim.spawners.materials.RigidBodyMaterialBaseCfg`, the solver-common + base class for rigid-body physics materials. Carries the ``UsdPhysics.MaterialAPI`` standard + fields (``static_friction``, ``dynamic_friction``, ``restitution``). The PhysX-specific + compliant-contact and combine-mode fields moved to + :class:`~isaaclab_physx.sim.spawners.materials.PhysxRigidBodyMaterialCfg`. +* Added :class:`~isaaclab.sim.schemas.CollisionBaseCfg`, the solver-common base class for + collision properties. Carries :attr:`collision_enabled` (``UsdPhysics.CollisionAPI``) plus + :attr:`contact_offset` and :attr:`rest_offset` whose USD attributes are PhysX-namespaced + but are consumed by Newton's importer via the PhysX bridge resolver + (``import_usd.py:2104, 2111``). +* Added :class:`~isaaclab.sim.schemas.ArticulationRootBaseCfg`, the solver-common base class + for articulation root properties (``fix_root_link``, ``articulation_enabled``). +* Added :class:`~isaaclab.sim.schemas.MeshCollisionBaseCfg`, the solver-common base class for + mesh collision properties carrying ``mesh_approximation_name`` (writes + ``physics:approximation`` via :class:`UsdPhysics.MeshCollisionAPI`). The class-level + ``_usd_applied_schema`` metadata replaces the deprecated ``usd_api`` / ``physx_api`` + instance-field dispatch. + +Changed +^^^^^^^ + +* Moved the ``max_velocity`` field from :class:`~isaaclab_physx.sim.schemas.PhysxJointDrivePropertiesCfg` + to :class:`~isaaclab.sim.schemas.JointDriveBaseCfg`. The field is the only USD path to set + Newton's ``Model.joint_velocity_limit`` and is consumed by Newton's importer. The USD + attribute written is unchanged (``physxJoint:maxJointVelocity``); existing code using + ``PhysxJointDrivePropertiesCfg(max_velocity=...)`` continues to work because the field + is inherited. +* Moved the ``disable_gravity`` field from :class:`~isaaclab_physx.sim.schemas.PhysxRigidBodyPropertiesCfg` + to :class:`~isaaclab.sim.schemas.RigidBodyBaseCfg`. PhysX honors per-body via + ``physxRigidBody:disableGravity``; Newton currently honors at scene level (partial), + documented in the field docstring. Existing code using + ``PhysxRigidBodyPropertiesCfg(disable_gravity=...)`` continues to work via inheritance. +* Documented :attr:`~isaaclab.sim.schemas.ArticulationRootPropertiesCfg.articulation_enabled` + and :attr:`~isaaclab.sim.schemas.ArticulationRootPropertiesCfg.enabled_self_collisions` + to lock their placement for the future :class:`ArticulationRootBaseCfg` / + ``PhysxArticulationRootPropertiesCfg`` split: ``articulation_enabled`` stays on the base + (single-namespace USD with verified Newton consumer); ``enabled_self_collisions`` moves + to the PhysX subclass (dual-namespace USD, with a future Newton sibling cfg owning the + ``newton:*`` namespace). +* Changed the defaults of :attr:`~isaaclab_physx.sim.spawners.materials.PhysxRigidBodyMaterialCfg.compliant_contact_stiffness`, + :attr:`compliant_contact_damping`, :attr:`friction_combine_mode`, and + :attr:`restitution_combine_mode` from concrete values (``0.0``, ``0.0``, ``"average"``, + ``"average"``) to ``None``. PhysX engine defaults match the previous concrete values, so + user-observable simulation behavior is unchanged; the difference is that these attributes + are now authored on the prim only when the user explicitly sets them (consistent with the + rest of the consumption-gated cfg layer). +* Relocated :class:`RigidBodyMaterialCfg` to :mod:`isaaclab_physx.sim.spawners.materials` and + split its fields between the new :class:`~isaaclab.sim.spawners.materials.RigidBodyMaterialBaseCfg` + (UsdPhysics-standard friction/restitution) and + :class:`~isaaclab_physx.sim.spawners.materials.PhysxRigidBodyMaterialCfg` + (PhysX-specific compliant-contact and combine-mode fields). A forwarding shim on + :mod:`isaaclab.sim.spawners.materials` and :mod:`isaaclab.sim` preserves existing imports. +* Refactored :func:`~isaaclab.sim.spawners.materials.spawn_rigid_body_material` to be + metadata-driven: it reads ``_usd_applied_schema``, ``_usd_namespace``, and + ``_usd_attr_name_map`` from the cfg class and gates ``PhysxMaterialAPI`` application on + whether the user authored at least one PhysX-namespaced field with a non-``None`` value. + Previously, the writer applied ``PhysxMaterialAPI`` unconditionally on every material spawn. +* Relocated :class:`CollisionPropertiesCfg` to :mod:`isaaclab_physx.sim.schemas` and split + its fields between the new :class:`~isaaclab.sim.schemas.CollisionBaseCfg` (solver-common + ``collision_enabled`` plus the PhysX-namespaced but Newton-consumed + ``contact_offset`` / ``rest_offset``) and + :class:`~isaaclab_physx.sim.schemas.PhysxCollisionPropertiesCfg` (PhysX-only + ``torsional_patch_radius`` / ``min_torsional_patch_radius``). A forwarding shim on + :mod:`isaaclab.sim.schemas`, :mod:`isaaclab.sim.schemas.schemas_cfg`, and + :mod:`isaaclab.sim` preserves existing imports. +* Refactored :func:`~isaaclab.sim.schemas.modify_collision_properties` to be metadata-driven + and to gate ``PhysxCollisionAPI`` application on whether the user authored at least one + PhysX-namespaced field with a non-``None`` value. Previously, the writer applied + ``PhysxCollisionAPI`` unconditionally on every collision prim, stamping the schema onto + Newton-targeted prims that only set ``collision_enabled``. +* Relocated :class:`ArticulationRootPropertiesCfg` to :mod:`isaaclab_physx.sim.schemas` and + split its fields between the new :class:`~isaaclab.sim.schemas.ArticulationRootBaseCfg` + (solver-common ``fix_root_link`` plus the PhysX-namespaced ``articulation_enabled`` which + is consumed by the IL Newton wrapper as a spawn-time guard) and + :class:`~isaaclab_physx.sim.schemas.PhysxArticulationRootPropertiesCfg` + (``enabled_self_collisions`` and PhysX TGS solver iter / sleep / stabilization thresholds). + A forwarding shim on :mod:`isaaclab.sim.schemas`, + :mod:`isaaclab.sim.schemas.schemas_cfg`, and :mod:`isaaclab.sim` preserves existing imports. +* Refactored :func:`~isaaclab.sim.schemas.modify_articulation_root_properties` to be + metadata-driven and to gate ``PhysxArticulationAPI`` application on whether the user + authored at least one PhysX-namespaced field with a non-``None`` value. Previously, the + writer applied ``PhysxArticulationAPI`` unconditionally on every articulation root, + stamping the schema onto Newton-targeted prims that only set ``fix_root_link``. +* Relocated :class:`MeshCollisionPropertiesCfg`, :class:`ConvexHullPropertiesCfg`, + :class:`ConvexDecompositionPropertiesCfg`, :class:`TriangleMeshPropertiesCfg`, + :class:`TriangleMeshSimplificationPropertiesCfg`, and :class:`SDFMeshPropertiesCfg` to + :mod:`isaaclab_physx.sim.schemas`. :class:`BoundingCubePropertiesCfg` and + :class:`BoundingSpherePropertiesCfg` stay in core because they author no PhysX schema. + A forwarding shim preserves existing imports. +* Refactored :func:`~isaaclab.sim.schemas.modify_mesh_collision_properties` to be + metadata-driven. The writer now reads ``_usd_applied_schema`` and ``_usd_namespace`` from + the cfg class instead of consulting instance-level ``usd_api`` / ``physx_api`` fields. + The standard :class:`UsdPhysics.MeshCollisionAPI` is always applied; PhysX cooking + schemas (``PhysxConvexHullCollisionAPI`` etc.) are gated on at least one + PhysX-namespaced tuning field being set. +* Relocated :class:`FixedTendonPropertiesCfg` and :class:`SpatialTendonPropertiesCfg` to + :mod:`isaaclab_physx.sim.schemas` as :class:`PhysxFixedTendonPropertiesCfg` and + :class:`PhysxSpatialTendonPropertiesCfg`. Tendons are a PhysX-only feature; no Newton + equivalent exists. A forwarding shim on :mod:`isaaclab.sim.schemas`, + :mod:`isaaclab.sim.schemas.schemas_cfg`, and :mod:`isaaclab.sim` preserves existing + imports. + +Deprecated +^^^^^^^^^^ + +* Deprecated the ``usd_api`` and ``physx_api`` instance attributes on the mesh-collision + cfg classes in favor of class-level ``_usd_applied_schema`` metadata. Reading these + attributes still works through one minor version but emits a ``DeprecationWarning``. + Scheduled for removal in 5.0. + +Fixed +^^^^^ + +* Fixed :meth:`~isaaclab.sim.schemas.modify_joint_drive_properties` and + :meth:`~isaaclab.sim.schemas.modify_rigid_body_properties` so that ``PhysxJointAPI`` and + ``PhysxRigidBodyAPI`` are applied only when the user authored at least one PhysX-namespaced + field with a non-``None`` value. Previously, schema application was gated on class-level + metadata being defined, which caused Newton-targeted prims to receive PhysX schemas even + when the user only set base ``UsdPhysics``-standard fields. diff --git a/source/isaaclab/isaaclab/sim/__init__.py b/source/isaaclab/isaaclab/sim/__init__.py index 3c75a3548956..9c140a2507cf 100644 --- a/source/isaaclab/isaaclab/sim/__init__.py +++ b/source/isaaclab/isaaclab/sim/__init__.py @@ -28,4 +28,71 @@ from isaaclab.utils.module import lazy_export -lazy_export() +_stub_getattr, _stub_dir, __all__ = lazy_export() + +# Names that moved out of this package into ``isaaclab_physx.sim.schemas``. +# Resolved lazily on first access so importing ``isaaclab.sim`` does not +# require ``isaaclab_physx`` to be installed. +_PHYSX_FORWARDS_SCHEMAS = frozenset({ + "RigidBodyPropertiesCfg", + "JointDrivePropertiesCfg", + "PhysxRigidBodyPropertiesCfg", + "PhysxJointDrivePropertiesCfg", + "CollisionPropertiesCfg", + "PhysxCollisionPropertiesCfg", + "PhysXCollisionPropertiesCfg", + "PhysxDeformableCollisionPropertiesCfg", + "ArticulationRootPropertiesCfg", + "PhysxArticulationRootPropertiesCfg", + "MeshCollisionPropertiesCfg", + "ConvexHullPropertiesCfg", + "ConvexDecompositionPropertiesCfg", + "TriangleMeshPropertiesCfg", + "TriangleMeshSimplificationPropertiesCfg", + "SDFMeshPropertiesCfg", + "PhysxConvexHullPropertiesCfg", + "PhysxConvexDecompositionPropertiesCfg", + "PhysxTriangleMeshPropertiesCfg", + "PhysxTriangleMeshSimplificationPropertiesCfg", + "PhysxSDFMeshPropertiesCfg", + "FixedTendonPropertiesCfg", + "SpatialTendonPropertiesCfg", + "PhysxFixedTendonPropertiesCfg", + "PhysxSpatialTendonPropertiesCfg", +}) + +# Names that moved out of this package into ``isaaclab_physx.sim.spawners.materials``. +_PHYSX_FORWARDS_MATERIALS = frozenset({ + "RigidBodyMaterialCfg", + "PhysxRigidBodyMaterialCfg", +}) + +_PHYSX_FORWARDS = _PHYSX_FORWARDS_SCHEMAS | _PHYSX_FORWARDS_MATERIALS + + +def __getattr__(name): + if name in _PHYSX_FORWARDS_SCHEMAS: + try: + from isaaclab_physx.sim.schemas import schemas_cfg as _physx_cfg + except ImportError as e: + raise ImportError( + f"'isaaclab.sim.{name}' has moved to 'isaaclab_physx.sim.schemas'." + " Install the isaaclab_physx extension or update your import. This forwarding" + " shim is scheduled for removal in 5.0." + ) from e + return getattr(_physx_cfg, name) + if name in _PHYSX_FORWARDS_MATERIALS: + try: + from isaaclab_physx.sim.spawners.materials import physics_materials_cfg as _physx_mat_cfg + except ImportError as e: + raise ImportError( + f"'isaaclab.sim.{name}' has moved to 'isaaclab_physx.sim.spawners.materials'." + " Install the isaaclab_physx extension or update your import. This forwarding" + " shim is scheduled for removal in 5.0." + ) from e + return getattr(_physx_mat_cfg, name) + return _stub_getattr(name) + + +def __dir__(): + return sorted(set(_stub_dir()) | _PHYSX_FORWARDS) diff --git a/source/isaaclab/isaaclab/sim/__init__.pyi b/source/isaaclab/isaaclab/sim/__init__.pyi index a718ccdcb989..e1d9f535a207 100644 --- a/source/isaaclab/isaaclab/sim/__init__.pyi +++ b/source/isaaclab/isaaclab/sim/__init__.pyi @@ -36,14 +36,14 @@ __all__ = [ "ArticulationRootPropertiesCfg", "BoundingCubePropertiesCfg", "BoundingSpherePropertiesCfg", - "CollisionPropertiesCfg", + "CollisionBaseCfg", "ConvexDecompositionPropertiesCfg", "ConvexHullPropertiesCfg", "FixedTendonPropertiesCfg", - "JointDrivePropertiesCfg", + "JointDriveBaseCfg", "MassPropertiesCfg", "MeshCollisionPropertiesCfg", - "RigidBodyPropertiesCfg", + "RigidBodyBaseCfg", "SDFMeshPropertiesCfg", "SpatialTendonPropertiesCfg", "TriangleMeshPropertiesCfg", @@ -202,14 +202,14 @@ from .schemas import ( ArticulationRootPropertiesCfg, BoundingCubePropertiesCfg, BoundingSpherePropertiesCfg, - CollisionPropertiesCfg, + CollisionBaseCfg, ConvexDecompositionPropertiesCfg, ConvexHullPropertiesCfg, FixedTendonPropertiesCfg, - JointDrivePropertiesCfg, + JointDriveBaseCfg, MassPropertiesCfg, MeshCollisionPropertiesCfg, - RigidBodyPropertiesCfg, + RigidBodyBaseCfg, SDFMeshPropertiesCfg, SpatialTendonPropertiesCfg, TriangleMeshPropertiesCfg, diff --git a/source/isaaclab/isaaclab/sim/converters/mesh_converter_cfg.py b/source/isaaclab/isaaclab/sim/converters/mesh_converter_cfg.py index 767f6dd04583..549aecab2eff 100644 --- a/source/isaaclab/isaaclab/sim/converters/mesh_converter_cfg.py +++ b/source/isaaclab/isaaclab/sim/converters/mesh_converter_cfg.py @@ -19,7 +19,7 @@ class MeshConverterCfg(AssetConverterBaseCfg): If None, then no mass properties will be added. """ - rigid_props: schemas_cfg.RigidBodyPropertiesCfg = None + rigid_props: schemas_cfg.RigidBodyBaseCfg = None """Rigid body properties to apply to the USD. Defaults to None. Note: @@ -32,7 +32,7 @@ class MeshConverterCfg(AssetConverterBaseCfg): Note: If None, then no collision properties will be added. """ - mesh_collision_props: schemas_cfg.MeshCollisionPropertiesCfg = None + mesh_collision_props: schemas_cfg.MeshCollisionBaseCfg = None """Mesh approximation properties to apply to all collision meshes in the USD. Note: If None, then no mesh approximation properties will be added. diff --git a/source/isaaclab/isaaclab/sim/schemas/__init__.py b/source/isaaclab/isaaclab/sim/schemas/__init__.py index f56ca862de59..2692196d4829 100644 --- a/source/isaaclab/isaaclab/sim/schemas/__init__.py +++ b/source/isaaclab/isaaclab/sim/schemas/__init__.py @@ -34,4 +34,53 @@ from isaaclab.utils.module import lazy_export -lazy_export() +_stub_getattr, _stub_dir, __all__ = lazy_export() + +# Names that moved out of this module into ``isaaclab_physx.sim.schemas``. +# Resolved lazily on first access so importing ``isaaclab.sim.schemas`` does +# not require ``isaaclab_physx`` to be installed. +_PHYSX_FORWARDS = frozenset({ + "RigidBodyPropertiesCfg", + "JointDrivePropertiesCfg", + "PhysxRigidBodyPropertiesCfg", + "PhysxJointDrivePropertiesCfg", + "CollisionPropertiesCfg", + "PhysxCollisionPropertiesCfg", + "PhysXCollisionPropertiesCfg", + "PhysxDeformableCollisionPropertiesCfg", + "ArticulationRootPropertiesCfg", + "PhysxArticulationRootPropertiesCfg", + "MeshCollisionPropertiesCfg", + "ConvexHullPropertiesCfg", + "ConvexDecompositionPropertiesCfg", + "TriangleMeshPropertiesCfg", + "TriangleMeshSimplificationPropertiesCfg", + "SDFMeshPropertiesCfg", + "PhysxConvexHullPropertiesCfg", + "PhysxConvexDecompositionPropertiesCfg", + "PhysxTriangleMeshPropertiesCfg", + "PhysxTriangleMeshSimplificationPropertiesCfg", + "PhysxSDFMeshPropertiesCfg", + "FixedTendonPropertiesCfg", + "SpatialTendonPropertiesCfg", + "PhysxFixedTendonPropertiesCfg", + "PhysxSpatialTendonPropertiesCfg", +}) + + +def __getattr__(name): + if name in _PHYSX_FORWARDS: + try: + from isaaclab_physx.sim.schemas import schemas_cfg as _physx_cfg + except ImportError as e: + raise ImportError( + f"'isaaclab.sim.schemas.{name}' has moved to 'isaaclab_physx.sim.schemas'." + " Install the isaaclab_physx extension or update your import. This forwarding" + " shim is scheduled for removal in 5.0." + ) from e + return getattr(_physx_cfg, name) + return _stub_getattr(name) + + +def __dir__(): + return sorted(set(_stub_dir()) | _PHYSX_FORWARDS) diff --git a/source/isaaclab/isaaclab/sim/schemas/__init__.pyi b/source/isaaclab/isaaclab/sim/schemas/__init__.pyi index f413b3ded12d..9a90ed0d810d 100644 --- a/source/isaaclab/isaaclab/sim/schemas/__init__.pyi +++ b/source/isaaclab/isaaclab/sim/schemas/__init__.pyi @@ -21,21 +21,14 @@ __all__ = [ "modify_mesh_collision_properties", "modify_rigid_body_properties", "modify_spatial_tendon_properties", - "ArticulationRootPropertiesCfg", + "ArticulationRootBaseCfg", "BoundingCubePropertiesCfg", "BoundingSpherePropertiesCfg", - "CollisionPropertiesCfg", - "ConvexDecompositionPropertiesCfg", - "ConvexHullPropertiesCfg", - "FixedTendonPropertiesCfg", - "JointDrivePropertiesCfg", + "CollisionBaseCfg", + "JointDriveBaseCfg", "MassPropertiesCfg", - "MeshCollisionPropertiesCfg", - "RigidBodyPropertiesCfg", - "SDFMeshPropertiesCfg", - "SpatialTendonPropertiesCfg", - "TriangleMeshPropertiesCfg", - "TriangleMeshSimplificationPropertiesCfg", + "MeshCollisionBaseCfg", + "RigidBodyBaseCfg", ] from .schemas import ( @@ -58,19 +51,12 @@ from .schemas import ( modify_spatial_tendon_properties, ) from .schemas_cfg import ( - ArticulationRootPropertiesCfg, + ArticulationRootBaseCfg, BoundingCubePropertiesCfg, BoundingSpherePropertiesCfg, - CollisionPropertiesCfg, - ConvexDecompositionPropertiesCfg, - ConvexHullPropertiesCfg, - FixedTendonPropertiesCfg, - JointDrivePropertiesCfg, + CollisionBaseCfg, + JointDriveBaseCfg, MassPropertiesCfg, - MeshCollisionPropertiesCfg, - RigidBodyPropertiesCfg, - SDFMeshPropertiesCfg, - SpatialTendonPropertiesCfg, - TriangleMeshPropertiesCfg, - TriangleMeshSimplificationPropertiesCfg, + MeshCollisionBaseCfg, + RigidBodyBaseCfg, ) diff --git a/source/isaaclab/isaaclab/sim/schemas/schemas.py b/source/isaaclab/isaaclab/sim/schemas/schemas.py index 0f97b542e031..70f129413e5b 100644 --- a/source/isaaclab/isaaclab/sim/schemas/schemas.py +++ b/source/isaaclab/isaaclab/sim/schemas/schemas.py @@ -6,9 +6,9 @@ # needed to import for allowing type-hinting: Usd.Stage | None from __future__ import annotations +import dataclasses import logging import math -from typing import Any from pxr import Usd, UsdPhysics @@ -46,21 +46,167 @@ } -PHYSX_MESH_COLLISION_CFGS = [ - schemas_cfg.ConvexDecompositionPropertiesCfg, - schemas_cfg.ConvexHullPropertiesCfg, - schemas_cfg.TriangleMeshPropertiesCfg, - schemas_cfg.TriangleMeshSimplificationPropertiesCfg, - schemas_cfg.SDFMeshPropertiesCfg, -] +# Lazy accessors. These lists were used by the legacy ``usd_api`` / ``physx_api`` instance- +# field dispatch in ``modify_mesh_collision_properties``. The new metadata-driven writer +# does not consult them, but they are preserved as a public API so external code that +# imported them keeps working. The PhysX leaves now live in ``isaaclab_physx``; we resolve +# them lazily so this module does not import ``isaaclab_physx`` at load time. +def _get_physx_mesh_collision_cfgs() -> list: + from isaaclab_physx.sim.schemas import schemas_cfg as _physx_cfg + + return [ + _physx_cfg.PhysxConvexHullPropertiesCfg, + _physx_cfg.PhysxConvexDecompositionPropertiesCfg, + _physx_cfg.PhysxTriangleMeshPropertiesCfg, + _physx_cfg.PhysxTriangleMeshSimplificationPropertiesCfg, + _physx_cfg.PhysxSDFMeshPropertiesCfg, + # legacy deprecation aliases + _physx_cfg.ConvexHullPropertiesCfg, + _physx_cfg.ConvexDecompositionPropertiesCfg, + _physx_cfg.TriangleMeshPropertiesCfg, + _physx_cfg.TriangleMeshSimplificationPropertiesCfg, + _physx_cfg.SDFMeshPropertiesCfg, + ] + + +class _LazyList: + """Lazy list whose contents are produced on first access. + + Used to keep the public ``PHYSX_MESH_COLLISION_CFGS`` / ``USD_MESH_COLLISION_CFGS`` symbols + resolvable for callers that imported them, without triggering an ``isaaclab_physx`` import + at this module's load time. + """ + + def __init__(self, factory): + self._factory = factory + self._cache = None + + def _resolved(self): + if self._cache is None: + self._cache = list(self._factory()) + return self._cache + + def __iter__(self): + return iter(self._resolved()) + + def __contains__(self, item): + return item in self._resolved() + + def __len__(self): + return len(self._resolved()) + + def __getitem__(self, index): + return self._resolved()[index] + + +PHYSX_MESH_COLLISION_CFGS = _LazyList(_get_physx_mesh_collision_cfgs) + +USD_MESH_COLLISION_CFGS = _LazyList( + lambda: [ + schemas_cfg.BoundingCubePropertiesCfg, + schemas_cfg.BoundingSpherePropertiesCfg, + ] +) + + +""" +Schema-application helper. +""" + + +def _get_field_declaring_class(cfg_class: type, field_name: str) -> type | None: + """Return the most-base class in the MRO that declares ``field_name``. + + Each cfg field is owned by a single class in the hierarchy (the one whose body + contains its annotation). This function walks the MRO in reverse so a base class + declaration wins over a subclass redeclaration with the same name -- the field's + USD namespace follows where it semantically lives, not where it was last + overridden for default values. + """ + for cls in reversed(cfg_class.__mro__): + if field_name in getattr(cls, "__annotations__", {}): + return cls + return None + + +def _apply_namespaced_schemas(prim, cfg, cfg_dict: dict) -> None: + """Route every cfg field to its declaring class's namespace and apply schemas. + + The helper handles the common ``AddAppliedSchema`` + namespaced-attribute write + logic shared by every metadata-driven writer. Caller is responsible for popping + fields that need typed-API writes (multi-instance ``UsdPhysics.DriveAPI``, + ``TfToken`` attributes with ``allowedTokens``) out of ``cfg_dict`` first. + + USD attribute names are derived by snake_case -> camelCase conversion of cfg field + names. The codebase enforces this as a convention: any cfg field whose + snake_case name does not produce the correct USD camelCase attr is renamed (with a + deprecation alias forwarded in ``__post_init__``) rather than mapped via metadata. + + Two passes: + + 1. **Per-field exceptions** -- ``cfg._usd_field_exceptions`` is a mapping + ``applied_schema -> (namespace, [cfg_field, ...])``. For each schema, if any + listed field is non-None, the schema is applied (once) and each non-None field is + written under that schema's namespace. Fields are popped from ``cfg_dict``. + 2. **Per-declaring-class routing** -- each remaining non-None field is grouped by the + class that declares it (walking the MRO). Each group writes under that class's + ``_usd_namespace`` and applies that class's ``_usd_applied_schema`` (if any). This + means base-class fields go under the base namespace (e.g. ``physics:*``) even when + the cfg instance is a PhysX subclass -- the subclass's ``_usd_namespace = + "physxRigidBody"`` only governs *its own* fields. + + Args: + prim: The USD prim to author on. + cfg: The cfg instance carrying the metadata. + cfg_dict: A mutable dict view of the cfg's non-metadata fields. Modified in place. -USD_MESH_COLLISION_CFGS = [ - schemas_cfg.BoundingCubePropertiesCfg, - schemas_cfg.BoundingSpherePropertiesCfg, - schemas_cfg.ConvexDecompositionPropertiesCfg, - schemas_cfg.ConvexHullPropertiesCfg, - schemas_cfg.TriangleMeshSimplificationPropertiesCfg, -] + Raises: + ValueError: If a non-None field's declaring class does not define ``_usd_namespace``. + """ + cfg_class = type(cfg) + + # 1. Per-field exceptions (overrides per-class routing for codeless-PhysX-namespace + # fields like ``disable_gravity`` on RigidBodyBaseCfg). + field_exceptions = getattr(cfg, "_usd_field_exceptions", {}) or {} + for applied_schema, (exc_ns, fields) in field_exceptions.items(): + triggered: list[tuple[str, object]] = [] + for cfg_field in fields: + if cfg_field in cfg_dict: + value = cfg_dict.pop(cfg_field) + if value is not None: + triggered.append((to_camel_case(cfg_field, "cC"), value)) + if not triggered: + continue + if applied_schema and applied_schema not in prim.GetAppliedSchemas(): + prim.AddAppliedSchema(applied_schema) + for usd_attr, value in triggered: + safe_set_attribute_on_usd_prim(prim, f"{exc_ns}:{usd_attr}", value, camel_case=False) + + # 2. Group remaining non-None writes by declaring class. + by_class: dict[type, list[tuple[str, object]]] = {} + for cfg_field, value in list(cfg_dict.items()): + if value is None: + continue + decl_class = _get_field_declaring_class(cfg_class, cfg_field) + if decl_class is None: + continue + by_class.setdefault(decl_class, []).append((to_camel_case(cfg_field, "cC"), value)) + + for decl_class, writes in by_class.items(): + # Read namespace/schema from the declaring class's own ``__dict__`` (not via + # ``getattr``) so subclass overrides don't leak into base-field routing. + namespace = decl_class.__dict__.get("_usd_namespace", None) + applied_schema = decl_class.__dict__.get("_usd_applied_schema", None) + if namespace is None: + raise ValueError( + f"{decl_class.__name__} declares fields {[a for a, _ in writes]} but does" + " not define '_usd_namespace'. Add '_usd_namespace' to the class metadata" + " or route the fields via '_usd_field_exceptions'." + ) + if applied_schema and applied_schema not in prim.GetAppliedSchemas(): + prim.AddAppliedSchema(applied_schema) + for usd_attr, value in writes: + safe_set_attribute_on_usd_prim(prim, f"{namespace}:{usd_attr}", value, camel_case=False) """ @@ -69,7 +215,7 @@ def define_articulation_root_properties( - prim_path: str, cfg: schemas_cfg.ArticulationRootPropertiesCfg, stage: Usd.Stage | None = None + prim_path: str, cfg: schemas_cfg.ArticulationRootBaseCfg, stage: Usd.Stage | None = None ): """Apply the articulation root schema on the input prim and set its properties. @@ -103,7 +249,7 @@ def define_articulation_root_properties( @apply_nested def modify_articulation_root_properties( - prim_path: str, cfg: schemas_cfg.ArticulationRootPropertiesCfg, stage: Usd.Stage | None = None + prim_path: str, cfg: schemas_cfg.ArticulationRootBaseCfg, stage: Usd.Stage | None = None ) -> bool: """Modify PhysX parameters for an articulation root prim. @@ -153,21 +299,14 @@ def modify_articulation_root_properties( # check if prim has articulation applied on it if not UsdPhysics.ArticulationRootAPI(articulation_prim): return False - # ensure PhysX articulation API is applied - applied_schemas = articulation_prim.GetAppliedSchemas() - if "PhysxArticulationAPI" not in applied_schemas: - articulation_prim.AddAppliedSchema("PhysxArticulationAPI") - # convert to dict - cfg = cfg.to_dict() - # extract non-USD properties - fix_root_link = cfg.pop("fix_root_link", None) + # convert to dict, filtering out class metadata (underscore-prefixed keys) + cfg_dict = {f.name: getattr(cfg, f.name) for f in dataclasses.fields(cfg)} + # extract writer-side (non-USD) properties + fix_root_link = cfg_dict.pop("fix_root_link", None) - # set into physx api (prim attributes under physxArticulation:*) - for attr_name, value in cfg.items(): - safe_set_attribute_on_usd_prim( - articulation_prim, f"physxArticulation:{to_camel_case(attr_name, 'cC')}", value, camel_case=False - ) + # apply per-field exceptions + main-namespace writes + _apply_namespaced_schemas(articulation_prim, cfg, cfg_dict) # fix root link based on input # we do the fixed joint processing later to not interfere with setting other properties @@ -242,9 +381,7 @@ def modify_articulation_root_properties( """ -def define_rigid_body_properties( - prim_path: str, cfg: schemas_cfg.RigidBodyPropertiesCfg, stage: Usd.Stage | None = None -): +def define_rigid_body_properties(prim_path: str, cfg: schemas_cfg.RigidBodyBaseCfg, stage: Usd.Stage | None = None): """Apply the rigid body schema on the input prim and set its properties. See :func:`modify_rigid_body_properties` for more details on how the properties are set. @@ -277,7 +414,7 @@ def define_rigid_body_properties( @apply_nested def modify_rigid_body_properties( - prim_path: str, cfg: schemas_cfg.RigidBodyPropertiesCfg, stage: Usd.Stage | None = None + prim_path: str, cfg: schemas_cfg.RigidBodyBaseCfg, stage: Usd.Stage | None = None ) -> bool: """Modify PhysX parameters for a rigid body prim. @@ -315,25 +452,14 @@ def modify_rigid_body_properties( # check if prim has rigid-body applied on it if not UsdPhysics.RigidBodyAPI(rigid_body_prim): return False - # retrieve the USD rigid-body api - usd_rigid_body_api = UsdPhysics.RigidBodyAPI(rigid_body_prim) - # ensure PhysX rigid body API is applied - applied_schemas = rigid_body_prim.GetAppliedSchemas() - if "PhysxRigidBodyAPI" not in applied_schemas: - rigid_body_prim.AddAppliedSchema("PhysxRigidBodyAPI") - - # convert to dict - cfg = cfg.to_dict() - # set into USD API - for attr_name in ["rigid_body_enabled", "kinematic_enabled"]: - value = cfg.pop(attr_name, None) - safe_set_attribute_on_usd_schema(usd_rigid_body_api, attr_name, value, camel_case=True) - # set into PhysX API (prim attributes under physxRigidBody:*) - for attr_name, value in cfg.items(): - safe_set_attribute_on_usd_prim( - rigid_body_prim, f"physxRigidBody:{to_camel_case(attr_name, 'cC')}", value, camel_case=False - ) - # success + # convert to dict, filtering out class metadata (underscore-prefixed keys) + cfg_dict = {f.name: getattr(cfg, f.name) for f in dataclasses.fields(cfg)} + + # All fields routed by the helper via per-declaring-class lookup: base + # ``rigid_body_enabled`` / ``kinematic_enabled`` go under ``physics:*``; + # ``disable_gravity`` via field exceptions; PhysX-subclass fields under + # ``physxRigidBody:*``. + _apply_namespaced_schemas(rigid_body_prim, cfg, cfg_dict) return True @@ -412,29 +538,21 @@ def modify_collision_properties( # check if prim has collision applied on it if not UsdPhysics.CollisionAPI(collider_prim): return False - # retrieve the USD collision api - usd_collision_api = UsdPhysics.CollisionAPI(collider_prim) - # ensure PhysX collision API is applied - applied_schemas = collider_prim.GetAppliedSchemas() - if "PhysxCollisionAPI" not in applied_schemas: - collider_prim.AddAppliedSchema("PhysxCollisionAPI") - + # dispatch nested mesh-collision cfg if present (preserve legacy behavior) mesh_collision_cfg = getattr(cfg, "mesh_collision_property", None) if mesh_collision_cfg is not None: modify_mesh_collision_properties(prim_path, mesh_collision_cfg, stage) - # convert to dict - cfg = cfg.to_dict() - # pop the mesh_collision_property since it is already set - cfg.pop("mesh_collision_property", None) - # set into USD API - for attr_name in ["collision_enabled"]: - value = cfg.pop(attr_name, None) - safe_set_attribute_on_usd_schema(usd_collision_api, attr_name, value, camel_case=True) - # set into PhysX API (prim attributes under physxCollision:*) - for attr_name, value in cfg.items(): - safe_set_attribute_on_usd_prim( - collider_prim, f"physxCollision:{to_camel_case(attr_name, 'cC')}", value, camel_case=False - ) + + # convert to dict, filtering out class metadata (underscore-prefixed keys) + cfg_dict = {f.name: getattr(cfg, f.name) for f in dataclasses.fields(cfg)} + # pop the mesh_collision_property since it is already dispatched above + cfg_dict.pop("mesh_collision_property", None) + + # All fields routed by the helper via per-declaring-class lookup: base + # ``collision_enabled`` goes under ``physics:*``; ``contact_offset`` / + # ``rest_offset`` via field exceptions; PhysX-subclass fields under + # ``physxCollision:*``. + _apply_namespaced_schemas(collider_prim, cfg, cfg_dict) # success return True @@ -513,15 +631,10 @@ def modify_mass_properties(prim_path: str, cfg: schemas_cfg.MassPropertiesCfg, s # check if prim has mass API applied on it if not UsdPhysics.MassAPI(rigid_prim): return False - # retrieve the USD mass api - usd_physics_mass_api = UsdPhysics.MassAPI(rigid_prim) - # convert to dict - cfg = cfg.to_dict() - # set into USD API - for attr_name in ["mass", "density"]: - value = cfg.pop(attr_name, None) - safe_set_attribute_on_usd_schema(usd_physics_mass_api, attr_name, value, camel_case=True) + # ``mass`` / ``density`` (``physics:*``) routed via the helper's per-declaring-class lookup. + cfg_dict = {f.name: getattr(cfg, f.name) for f in dataclasses.fields(cfg)} + _apply_namespaced_schemas(rigid_prim, cfg, cfg_dict) # success return True @@ -612,7 +725,7 @@ def activate_contact_sensors(prim_path: str, threshold: float = 0.0, stage: Usd. @apply_nested def modify_joint_drive_properties( - prim_path: str, cfg: schemas_cfg.JointDrivePropertiesCfg, stage: Usd.Stage | None = None + prim_path: str, cfg: schemas_cfg.JointDriveBaseCfg, stage: Usd.Stage | None = None ) -> bool: """Modify PhysX parameters for a joint prim. @@ -671,54 +784,49 @@ def modify_joint_drive_properties( usd_drive_api = UsdPhysics.DriveAPI(prim, drive_api_name) if not usd_drive_api: usd_drive_api = UsdPhysics.DriveAPI.Apply(prim, drive_api_name) - # ensure PhysX joint API is applied - if "PhysxJointAPI" not in applied_schemas_str: - prim.AddAppliedSchema("PhysxJointAPI") - - # mapping from configuration name to USD attribute name - cfg_to_usd_map = { - "max_velocity": "max_joint_velocity", - "max_effort": "max_force", - "drive_type": "type", - } - # convert to dict - cfg = cfg.to_dict() + + # ``drive_type`` is a permanent inline carve-out: the USD attribute is named ``type`` + # (a Python keyword-like name we cannot use as a cfg field). All other solver-common + # joint-drive fields follow the snake_case = camelCase convention. + # convert to dict, filtering out class metadata (underscore-prefixed keys) + cfg_dict = {f.name: getattr(cfg, f.name) for f in dataclasses.fields(cfg)} # ensure_drives_exist: if both stiffness and damping are zero on the authored drive, # set a minimal stiffness so that backends like Newton recognise the drive as active. - ensure_drives = cfg.pop("ensure_drives_exist", False) - if ensure_drives and cfg["stiffness"] is None and cfg["damping"] is None: + ensure_drives = cfg_dict.pop("ensure_drives_exist", False) + if ensure_drives and cfg_dict["stiffness"] is None and cfg_dict["damping"] is None: # read the current values from the drive cur_stiffness = usd_drive_api.GetStiffnessAttr().Get() cur_damping = usd_drive_api.GetDampingAttr().Get() if (cur_stiffness is None or cur_stiffness == 0.0) and (cur_damping is None or cur_damping == 0.0): - cfg["stiffness"] = 1e-3 + cfg_dict["stiffness"] = 1e-3 # check if linear drive is_linear_drive = prim.IsA(UsdPhysics.PrismaticJoint) # convert values for angular drives from radians to degrees units if not is_linear_drive: - if cfg["max_velocity"] is not None: - # rad / s --> deg / s - cfg["max_velocity"] = cfg["max_velocity"] * 180.0 / math.pi - if cfg["stiffness"] is not None: + if cfg_dict.get("max_joint_velocity") is not None: + # rad / s --> deg / s (PhysX angular convention is degrees) + cfg_dict["max_joint_velocity"] = cfg_dict["max_joint_velocity"] * 180.0 / math.pi + if cfg_dict["stiffness"] is not None: # N-m/rad --> N-m/deg - cfg["stiffness"] = cfg["stiffness"] * math.pi / 180.0 - if cfg["damping"] is not None: + cfg_dict["stiffness"] = cfg_dict["stiffness"] * math.pi / 180.0 + if cfg_dict["damping"] is not None: # N-m-s/rad --> N-m-s/deg - cfg["damping"] = cfg["damping"] * math.pi / 180.0 - - # set into PhysX API (prim attributes under physxJoint:*) - for attr_name in ["max_velocity"]: - value = cfg.pop(attr_name, None) - usd_attr_name = cfg_to_usd_map[attr_name] - safe_set_attribute_on_usd_prim( - prim, f"physxJoint:{to_camel_case(usd_attr_name, 'cC')}", value, camel_case=False - ) - # set into USD API - for attr_name, attr_value in cfg.items(): - attr_name = cfg_to_usd_map.get(attr_name, attr_name) - safe_set_attribute_on_usd_schema(usd_drive_api, attr_name, attr_value, camel_case=True) + cfg_dict["damping"] = cfg_dict["damping"] * math.pi / 180.0 + + # set into USD API (solver-common properties; UsdPhysics.DriveAPI fields). Pop only + # the solver-common fields here; the helper handles the PhysX-namespaced remainder. + for attr_name in ["drive_type", "max_force", "stiffness", "damping"]: + if attr_name not in cfg_dict: + continue + attr_value = cfg_dict.pop(attr_name) + usd_attr_name = "type" if attr_name == "drive_type" else attr_name + safe_set_attribute_on_usd_schema(usd_drive_api, usd_attr_name, attr_value, camel_case=True) + + # apply per-field exceptions (max_velocity -> physxJoint:maxJointVelocity) + any + # PhysX-subclass main-namespace writes + _apply_namespaced_schemas(prim, cfg, cfg_dict) return True @@ -730,7 +838,7 @@ def modify_joint_drive_properties( @apply_nested def modify_fixed_tendon_properties( - prim_path: str, cfg: schemas_cfg.FixedTendonPropertiesCfg, stage: Usd.Stage | None = None + prim_path: str, cfg: schemas_cfg.PhysxFixedTendonPropertiesCfg, stage: Usd.Stage | None = None ) -> bool: """Modify PhysX parameters for a fixed tendon attachment prim. @@ -794,7 +902,7 @@ def modify_fixed_tendon_properties( @apply_nested def modify_spatial_tendon_properties( - prim_path: str, cfg: schemas_cfg.SpatialTendonPropertiesCfg, stage: Usd.Stage | None = None + prim_path: str, cfg: schemas_cfg.PhysxSpatialTendonPropertiesCfg, stage: Usd.Stage | None = None ) -> bool: """Modify PhysX parameters for a spatial tendon attachment prim. @@ -858,75 +966,19 @@ def modify_spatial_tendon_properties( """ -def _get_physx_collision_namespace(schema_name: str) -> str: - """Convert PhysX schema name to attribute namespace used on the prim.""" - if not schema_name: - raise ValueError("PhysX schema name must be provided for mesh collision properties.") - schema_name = schema_name.removesuffix("API") - return schema_name[0].lower() + schema_name[1:] - - -def _get_usd_mesh_collision_api(api_name: str): - """Resolve the USD mesh collision API from a string name.""" - if not api_name: - raise ValueError("USD schema name must be provided for mesh collision properties.") - usd_api = getattr(UsdPhysics, api_name, None) - if usd_api is None: - raise ValueError(f"USD schema '{api_name}' not found in UsdPhysics.") - return usd_api - - -def extract_mesh_collision_api_and_attrs( - cfg: schemas_cfg.MeshCollisionPropertiesCfg, -) -> tuple[tuple[str, Any], dict[str, Any]]: - """Extract the mesh collision API type/value and custom attributes from the configuration. - - Args: - cfg: The configuration for the mesh collision properties. - - Returns: - A tuple of ((api_type, api_value), custom_attrs). api_type is "usd" or "physx"; - api_value is the USD API class (callable) or PhysX schema name string. - - Raises: - ValueError: When neither USD nor PhysX API can be determined to be used. - """ - custom_attrs = { - key: value - for key, value in cfg.to_dict().items() - if value is not None and key not in ["usd_api", "physx_api", "mesh_approximation_name"] - } - - use_usd_api = False - use_physx_api = False - - if len(custom_attrs) > 0 and type(cfg) in PHYSX_MESH_COLLISION_CFGS: - use_physx_api = True - elif len(custom_attrs) == 0: - if type(cfg) in USD_MESH_COLLISION_CFGS: - use_usd_api = True - else: - use_physx_api = True - elif len(custom_attrs) > 0 and type(cfg) in USD_MESH_COLLISION_CFGS: - raise ValueError("Args are specified but the USD Mesh API doesn't support them!") - - if use_usd_api and getattr(cfg, "usd_api", None): - return ("usd", cfg.usd_api), custom_attrs - if use_physx_api and getattr(cfg, "physx_api", None): - return ("physx", cfg.physx_api), custom_attrs - raise ValueError("Either USD or PhysX API should be used for modifying mesh collision attributes!") - - def define_mesh_collision_properties( - prim_path: str, cfg: schemas_cfg.MeshCollisionPropertiesCfg, stage: Usd.Stage | None = None + prim_path: str, cfg: schemas_cfg.MeshCollisionBaseCfg, stage: Usd.Stage | None = None ): """Apply the mesh collision schema on the input prim and set its properties. - See :func:`modify_collision_mesh_properties` for more details on how the properties are set. + + See :func:`modify_mesh_collision_properties` for more details on how the properties are set. + Args: - prim_path : The prim path where to apply the mesh collision schema. - cfg : The configuration for the mesh collision properties. - stage : The stage where to find the prim. Defaults to None, in which case the + prim_path: The prim path where to apply the mesh collision schema. + cfg: The configuration for the mesh collision properties. + stage: The stage where to find the prim. Defaults to None, in which case the current stage is used. + Raises: ValueError: When the prim path is not valid. """ @@ -939,36 +991,43 @@ def define_mesh_collision_properties( if not prim.IsValid(): raise ValueError(f"Prim path '{prim_path}' is not valid.") - (api_type, api_value), _ = extract_mesh_collision_api_and_attrs(cfg=cfg) - - if api_type == "usd": - usd_api_class = _get_usd_mesh_collision_api(api_value) - if not usd_api_class(prim): - usd_api_class.Apply(prim) - else: - if api_value not in prim.GetAppliedSchemas(): - prim.AddAppliedSchema(api_value) + # Always apply the standard ``UsdPhysics.MeshCollisionAPI`` so the approximation token is + # writable. The PhysX cooking schema (if any) is applied lazily by the writer below + # only when the user authored at least one PhysX-namespaced tuning field. + if not UsdPhysics.MeshCollisionAPI(prim): + UsdPhysics.MeshCollisionAPI.Apply(prim) modify_mesh_collision_properties(prim_path=prim_path, cfg=cfg, stage=stage) @apply_nested def modify_mesh_collision_properties( - prim_path: str, cfg: schemas_cfg.MeshCollisionPropertiesCfg, stage: Usd.Stage | None = None + prim_path: str, cfg: schemas_cfg.MeshCollisionBaseCfg, stage: Usd.Stage | None = None ) -> bool: """Set properties for the mesh collision of a prim. - These properties are based on either the `Phsyx the `UsdPhysics.MeshCollisionAPI` schema. + + Metadata-driven writer. The standard ``UsdPhysics.MeshCollisionAPI`` is applied + unconditionally (it is the carrier of the ``physics:approximation`` token). The + PhysX cooking schema declared by ``_usd_applied_schema`` (e.g. + ``PhysxConvexHullCollisionAPI``) is gated on the user authoring at least one + non-``None`` namespaced tuning field, mirroring the gating used by the other + consumption-gated writers (rigid body, joint drive, collision, articulation root). + .. note:: - This function is decorated with :func:`apply_nested` that sets the properties to all the prims - (that have the schema applied on them) under the input prim path. - .. UsdPhysics.MeshCollisionAPI: https://openusd.org/release/api/class_usd_physics_mesh_collision_a_p_i.html + This function is decorated with :func:`apply_nested` that sets the properties to + all the prims (that have the schema applied on them) under the input prim path. + + .. _UsdPhysics.MeshCollisionAPI: https://openusd.org/release/api/class_usd_physics_mesh_collision_a_p_i.html + Args: - prim_path : The prim path of the rigid body. This prim should be a Mesh prim. - cfg : The configuration for the mesh collision properties. - stage : The stage where to find the prim. Defaults to None, in which case the + prim_path: The prim path of the rigid body. This prim should be a Mesh prim. + cfg: The configuration for the mesh collision properties. + stage: The stage where to find the prim. Defaults to None, in which case the current stage is used. + Returns: True if the properties were successfully set, False otherwise. + Raises: ValueError: When the mesh approximation name is invalid. """ @@ -981,8 +1040,12 @@ def modify_mesh_collision_properties( # we need MeshCollisionAPI to set mesh collision approximation attribute if not UsdPhysics.MeshCollisionAPI(prim): UsdPhysics.MeshCollisionAPI.Apply(prim) - # convert mesh approximation string to token - approximation_name = cfg.mesh_approximation_name + + # convert to dict, filtering out class metadata (underscore-prefixed keys) + cfg_dict = {f.name: getattr(cfg, f.name) for f in dataclasses.fields(cfg)} + + # write the standard ``physics:approximation`` token via UsdPhysics.MeshCollisionAPI + approximation_name = cfg_dict.pop("mesh_approximation_name", "none") if approximation_name not in MESH_APPROXIMATION_TOKENS: raise ValueError( f"Invalid mesh approximation name: '{approximation_name}'. " @@ -993,23 +1056,14 @@ def modify_mesh_collision_properties( UsdPhysics.MeshCollisionAPI(prim), "Approximation", approximation_token, camel_case=False ) - (api_type, api_value), custom_attrs = extract_mesh_collision_api_and_attrs(cfg=cfg) - - if api_type == "usd": - usd_api_class = _get_usd_mesh_collision_api(api_value) - mesh_collision_api = usd_api_class(prim) - if not mesh_collision_api: - return False - for attr_name, value in custom_attrs.items(): - camel_case = attr_name != "Attribute" - safe_set_attribute_on_usd_schema(mesh_collision_api, attr_name, value, camel_case=camel_case) - else: - if api_value not in prim.GetAppliedSchemas(): - return False - attr_namespace = _get_physx_collision_namespace(api_value) - for attr_name, value in custom_attrs.items(): - attr_token = attr_name if attr_name == "Attribute" else to_camel_case(attr_name, "cC") - safe_set_attribute_on_usd_prim(prim, f"{attr_namespace}:{attr_token}", value, camel_case=False) + # The standard ``UsdPhysics.MeshCollisionAPI`` is already applied above. The base + # ``MeshCollisionBaseCfg`` declares ``_usd_applied_schema = "MeshCollisionAPI"`` so the + # helper would re-apply (idempotent) if any base-namespace write fired. PhysX cooking + # subclasses (ConvexHull / TriangleMesh / SDF / ...) override the schema and namespace + # to author their tuning fields under e.g. ``physxConvexHullCollision:*``; the helper + # gates ``Physx*CollisionAPI`` application on at least one non-None tuning field, so + # Newton-targeted prims stay free of PhysX cooking schemas they did not opt in to. + _apply_namespaced_schemas(prim, cfg, cfg_dict) # success return True diff --git a/source/isaaclab/isaaclab/sim/schemas/schemas_cfg.py b/source/isaaclab/isaaclab/sim/schemas/schemas_cfg.py index 69cbc8bd5304..eae040435429 100644 --- a/source/isaaclab/isaaclab/sim/schemas/schemas_cfg.py +++ b/source/isaaclab/isaaclab/sim/schemas/schemas_cfg.py @@ -5,14 +5,95 @@ from __future__ import annotations -from typing import Literal +import warnings +from typing import ClassVar, Literal from isaaclab.utils import configclass +# Names that moved out of this submodule into ``isaaclab_physx.sim.schemas.schemas_cfg``. +# Resolved lazily so callers using ``from isaaclab.sim.schemas.schemas_cfg import +# RigidBodyPropertiesCfg`` continue to work without importing ``isaaclab_physx`` at module +# load time. +_PHYSX_FORWARDS = frozenset( + { + "RigidBodyPropertiesCfg", + "JointDrivePropertiesCfg", + "PhysxRigidBodyPropertiesCfg", + "PhysxJointDrivePropertiesCfg", + "CollisionPropertiesCfg", + "PhysxCollisionPropertiesCfg", + "PhysXCollisionPropertiesCfg", + "PhysxDeformableCollisionPropertiesCfg", + "ArticulationRootPropertiesCfg", + "PhysxArticulationRootPropertiesCfg", + "MeshCollisionPropertiesCfg", + "ConvexHullPropertiesCfg", + "ConvexDecompositionPropertiesCfg", + "TriangleMeshPropertiesCfg", + "TriangleMeshSimplificationPropertiesCfg", + "SDFMeshPropertiesCfg", + "PhysxConvexHullPropertiesCfg", + "PhysxConvexDecompositionPropertiesCfg", + "PhysxTriangleMeshPropertiesCfg", + "PhysxTriangleMeshSimplificationPropertiesCfg", + "PhysxSDFMeshPropertiesCfg", + "FixedTendonPropertiesCfg", + "SpatialTendonPropertiesCfg", + "PhysxFixedTendonPropertiesCfg", + "PhysxSpatialTendonPropertiesCfg", + } +) + + +def __getattr__(name): + if name in _PHYSX_FORWARDS: + try: + from isaaclab_physx.sim.schemas import schemas_cfg as _physx_cfg + except ImportError as e: + raise ImportError( + f"'isaaclab.sim.schemas.schemas_cfg.{name}' has moved to" + " 'isaaclab_physx.sim.schemas.schemas_cfg'. Install the isaaclab_physx" + " extension or update your import. This forwarding shim is scheduled for" + " removal in 5.0." + ) from e + return getattr(_physx_cfg, name) + raise AttributeError(f"module 'isaaclab.sim.schemas.schemas_cfg' has no attribute {name!r}") + + +def _deprecate_field_alias(cfg, alias: str, canonical: str) -> None: + """Forward a deprecated cfg field to its canonical replacement. + + If ``alias`` is set on the cfg instance, emit a ``DeprecationWarning`` and copy the + value to ``canonical`` (when ``canonical`` is unset). The alias is then nulled so + downstream metadata-driven writers see only the canonical name. + """ + value = getattr(cfg, alias, None) + if value is None: + return + warnings.warn( + f"'{alias}' is deprecated; use '{canonical}' instead. The alias is scheduled for removal in 5.0.", + DeprecationWarning, + stacklevel=3, + ) + if getattr(cfg, canonical, None) is None: + setattr(cfg, canonical, value) + setattr(cfg, alias, None) + @configclass -class ArticulationRootPropertiesCfg: - """Properties to apply to the root of an articulation. +class ArticulationRootBaseCfg: + """Solver-common properties to apply to the root of an articulation. + + Carries :attr:`fix_root_link` (writer-side; materializes a + :class:`UsdPhysics.FixedJoint` between the world frame and the root link) and + :attr:`articulation_enabled` whose only USD path today is the PhysX-namespaced + ``physxArticulation:articulationEnabled`` attribute. The base class itself + declares no USD namespace; the writer consults :attr:`_usd_field_exceptions` + to route ``articulation_enabled`` to its non-base namespace and apply + ``PhysxArticulationAPI`` only when the user authored that one field. + For PhysX-only articulation-root properties (self-collisions, TGS solver + iterations, sleep / stabilization thresholds), use + :class:`~isaaclab_physx.sim.schemas.PhysxArticulationRootPropertiesCfg`. See :meth:`modify_articulation_root_properties` for more information. @@ -21,23 +102,36 @@ class ArticulationRootPropertiesCfg: the properties and leave the rest as-is. """ - articulation_enabled: bool | None = None - """Whether to enable or disable articulation.""" - - enabled_self_collisions: bool | None = None - """Whether to enable or disable self-collisions.""" + # -- Class metadata (not dataclass fields) -- + # No base-native namespace today: every field is either solver-common (typed + # UsdPhysics API) or routed through ``_usd_field_exceptions``. + _usd_namespace: ClassVar[str | None] = None + _usd_applied_schema: ClassVar[str | None] = None + # Per-field exceptions: applied_schema -> (namespace, [cfg_field, ...]). The USD + # attribute name is the auto snake -> camelCase of the cfg field name (project + # convention). When any listed field is non-None at write time, the writer applies + # the schema and writes the attribute under the exception namespace. + _usd_field_exceptions: ClassVar[dict] = { + "PhysxArticulationAPI": ("physxArticulation", ["articulation_enabled"]), + } - solver_position_iteration_count: int | None = None - """Solver position iteration counts for the body.""" + articulation_enabled: bool | None = None + """Whether to enable or disable the articulation. - solver_velocity_iteration_count: int | None = None - """Solver velocity iteration counts for the body.""" + PhysX honors this per-articulation at sim time via + ``physxArticulation:articulationEnabled``: setting False makes PhysX skip + the articulation in its solver passes. - sleep_threshold: float | None = None - """Mass-normalized kinetic energy threshold below which an actor may go to sleep.""" + On Newton, the field is read by the IsaacLab Newton wrapper at spawn time + (``isaaclab_newton/assets/rigid_object/rigid_object.py:1035``) as a guard + against accidentally spawning a ``RigidObject`` over a prim that still has + ``ArticulationRootAPI`` applied; setting False suppresses the guard error. + The Newton solver itself does not consult the flag at sim time. - stabilization_threshold: float | None = None - """The mass-normalized kinetic energy threshold below which an articulation may participate in stabilization.""" + Placed on the solver-common class because the user-facing intent is + universal and both PhysX (sim-time) and the IL Newton wrapper (spawn-time) + honor it. + """ fix_root_link: bool | None = None """Whether to fix the root link of the articulation. @@ -54,16 +148,38 @@ class ArticulationRootPropertiesCfg: @configclass -class RigidBodyPropertiesCfg: - """Properties to apply to a rigid body. +class RigidBodyBaseCfg: + """Solver-common properties to apply to a rigid body. + + Contains properties from the `UsdPhysics.RigidBodyAPI`_ that are common across all + simulation backends, plus :attr:`disable_gravity` whose USD attribute today is + PhysX-namespaced but whose semantics (per-body gravity exclusion) are universal: + PhysX honors it per-body; Newton's importer consumes it at the scene level + (partial honor, documented on the field). For PhysX-only rigid-body properties, + use :class:`PhysxRigidBodyPropertiesCfg`. See :meth:`modify_rigid_body_properties` for more information. .. note:: If the values are None, they are not modified. This is useful when you want to set only a subset of the properties and leave the rest as-is. + + .. _UsdPhysics.RigidBodyAPI: https://openusd.org/dev/api/class_usd_physics_rigid_body_a_p_i.html """ + # -- Class metadata (not dataclass fields) -- + # ``rigid_body_enabled`` and ``kinematic_enabled`` write to ``physics:*`` (UsdPhysics + # standard attributes). The helper's per-declaring-class routing keeps these under + # the base namespace even when the cfg is a PhysX subclass instance. The + # ``UsdPhysics.RigidBodyAPI`` schema is applied upstream by ``define_rigid_body_properties`` + # so ``_usd_applied_schema`` here stays None. ``disable_gravity`` is routed via + # ``_usd_field_exceptions`` to ``physxRigidBody:disableGravity``. + _usd_namespace: ClassVar[str | None] = "physics" + _usd_applied_schema: ClassVar[str | None] = None + _usd_field_exceptions: ClassVar[dict] = { + "PhysxRigidBodyAPI": ("physxRigidBody", ["disable_gravity"]), + } + rigid_body_enabled: bool | None = None """Whether to enable or disable the rigid body.""" @@ -77,85 +193,88 @@ class RigidBodyPropertiesCfg: """ disable_gravity: bool | None = None - """Disable gravity for the actor.""" - - linear_damping: float | None = None - """Linear damping for the body.""" - - angular_damping: float | None = None - """Angular damping for the body.""" + """Disable gravity for the body. - max_linear_velocity: float | None = None - """Maximum linear velocity for rigid bodies (in m/s).""" + PhysX honors this per-body via ``physxRigidBody:disableGravity``: setting True + excludes the body from world gravity integration. - max_angular_velocity: float | None = None - """Maximum angular velocity for rigid bodies (in deg/s).""" + Newton currently consumes the same USD attribute at the **scene level** -- + Newton's importer reads ``physxRigidBody:disableGravity`` on the scene prim + and uses it to drive the scene-wide ``builder.gravity`` flag (``import_usd.py:1212``). + Per-body intent is therefore partially honored on Newton: whichever rigid body + has the attribute authored ends up controlling scene-wide gravity, and other + bodies cannot be selectively excluded. - max_depenetration_velocity: float | None = None - """Maximum depenetration velocity permitted to be introduced by the solver (in m/s).""" - - max_contact_impulse: float | None = None - """The limit on the impulse that may be applied at a contact.""" - - enable_gyroscopic_forces: bool | None = None - """Enables computation of gyroscopic forces on the rigid body.""" - - retain_accelerations: bool | None = None - """Carries over forces/accelerations over sub-steps.""" - - solver_position_iteration_count: int | None = None - """Solver position iteration counts for the body.""" - - solver_velocity_iteration_count: int | None = None - """Solver position iteration counts for the body.""" - - sleep_threshold: float | None = None - """Mass-normalized kinetic energy threshold below which an actor may go to sleep.""" - - stabilization_threshold: float | None = None - """The mass-normalized kinetic energy threshold below which an actor may participate in stabilization.""" + The field is placed on the base because the user-facing intent (per-body + gravity exclusion for markers, sensors, kinematic targets) is universal physics + and PhysX honors it fully. Closing the Newton gap is a kernel-level fix + (introduce ``Model.body_disable_gravity`` boolean array consumed by the + integrator) that does not require a cfg-API change. + """ @configclass -class CollisionPropertiesCfg: - """Properties to apply to colliders in a rigid body. +class CollisionBaseCfg: + """Solver-common properties to apply to colliders. + + Contains :attr:`collision_enabled` from the `UsdPhysics.CollisionAPI`_ and the + :attr:`contact_offset` / :attr:`rest_offset` knobs whose USD attributes today are + PhysX-namespaced (``physxCollision:contactOffset``, ``physxCollision:restOffset``) + but whose semantics (collision-pair generation distance, rest separation gap) are + universal physics: PhysX consumes them natively, Newton's importer consumes them + via the PhysX bridge resolver and populates ``Model.shape_collision_radius`` / + ``Model.shape_collision_thickness`` from the ``gap`` and ``margin`` keys (see + ``import_usd.py:2104, 2111``). For PhysX-only collision properties (e.g. torsional + patch friction), use :class:`~isaaclab_physx.sim.schemas.PhysxCollisionPropertiesCfg`. See :meth:`modify_collision_properties` for more information. .. note:: If the values are None, they are not modified. This is useful when you want to set only a subset of the properties and leave the rest as-is. + + .. _UsdPhysics.CollisionAPI: https://openusd.org/dev/api/class_usd_physics_collision_a_p_i.html """ + # -- Class metadata (not dataclass fields) -- + # ``collision_enabled`` writes to ``physics:collisionEnabled`` (UsdPhysics standard). + # The helper's per-declaring-class routing keeps it under ``physics:*`` even when + # the cfg is a PhysX subclass instance. ``contact_offset`` / ``rest_offset`` are + # routed via ``_usd_field_exceptions`` to ``physxCollision:*``. + _usd_namespace: ClassVar[str | None] = "physics" + _usd_applied_schema: ClassVar[str | None] = None + _usd_field_exceptions: ClassVar[dict] = { + "PhysxCollisionAPI": ("physxCollision", ["contact_offset", "rest_offset"]), + } + collision_enabled: bool | None = None - """Whether to enable or disable collisions.""" + """Whether to enable or disable collisions. + + Writes ``physics:collisionEnabled`` via :class:`UsdPhysics.CollisionAPI`. + """ contact_offset: float | None = None - """Contact offset for the collision shape (in m). + """Contact offset for the collision shape [m]. The collision detector generates contact points as soon as two shapes get closer than the sum of their contact offsets. This quantity should be non-negative which means that contact generation can potentially start before the shapes actually penetrate. + + Writes ``physxCollision:contactOffset``. Newton's USD importer consumes the same + attribute via its PhysX-bridge resolver. """ rest_offset: float | None = None - """Rest offset for the collision shape (in m). + """Rest offset for the collision shape [m]. The rest offset quantifies how close a shape gets to others at rest, At rest, the distance between two vertically stacked objects is the sum of their rest offsets. If a pair of shapes have a positive rest offset, the shapes will be separated at rest by an air gap. - """ - - torsional_patch_radius: float | None = None - """Radius of the contact patch for applying torsional friction (in m). - It is used to approximate rotational friction introduced by the compression of contacting surfaces. - If the radius is zero, no torsional friction is applied. + Writes ``physxCollision:restOffset``. Newton's USD importer consumes the same + attribute via its PhysX-bridge resolver. """ - min_torsional_patch_radius: float | None = None - """Minimum radius of the contact patch for applying torsional friction (in m).""" - @configclass class MassPropertiesCfg: @@ -168,6 +287,13 @@ class MassPropertiesCfg: the properties and leave the rest as-is. """ + # -- Class metadata (not dataclass fields) -- + # ``mass`` / ``density`` write to ``physics:*`` (UsdPhysics standard attributes). + # The ``UsdPhysics.MassAPI`` schema is applied upstream by ``define_mass_properties``. + _usd_namespace: ClassVar[str | None] = "physics" + _usd_applied_schema: ClassVar[str | None] = None + _usd_field_exceptions: ClassVar[dict] = {} + mass: float | None = None """The mass of the rigid body (in kg). @@ -184,16 +310,43 @@ class MassPropertiesCfg: @configclass -class JointDrivePropertiesCfg: - """Properties to define the drive mechanism of a joint. +class JointDriveBaseCfg: + """Solver-common properties to define the drive mechanism of a joint. + + Contains properties from the `UsdPhysics.DriveAPI`_ that are common across all + simulation backends, plus :attr:`max_joint_velocity` whose USD attribute today is + PhysX-namespaced but whose semantics (per-DOF velocity limit) are universal: + Newton's importer consumes ``physxJoint:maxJointVelocity`` and populates + ``Model.joint_velocity_limit``; PhysX consumes it natively. For PhysX-only + drive properties, use :class:`PhysxJointDrivePropertiesCfg`. See :meth:`modify_joint_drive_properties` for more information. .. note:: If the values are None, they are not modified. This is useful when you want to set only a subset of the properties and leave the rest as-is. + + .. _UsdPhysics.DriveAPI: https://openusd.org/dev/api/class_usd_physics_drive_a_p_i.html """ + # -- Class metadata (not dataclass fields) -- + # No base-native namespace today: drive-type / max-effort / stiffness / damping are + # written via the typed ``UsdPhysics.DriveAPI``; ``max_joint_velocity`` is routed + # through ``_usd_field_exceptions`` to ``physxJoint:maxJointVelocity`` (the only + # USD path to ``Model.joint_velocity_limit`` today). + _usd_namespace: ClassVar[str | None] = None + _usd_applied_schema: ClassVar[str | None] = None + _usd_field_exceptions: ClassVar[dict] = { + "PhysxJointAPI": ("physxJoint", ["max_joint_velocity"]), + } + + def __post_init__(self): + # Deprecation aliases: project convention is that python ``snake_case`` cfg field + # names map identity-style to USD ``camelCase`` attrs. Legacy short names that + # diverged are forwarded here. + _deprecate_field_alias(self, "max_velocity", "max_joint_velocity") + _deprecate_field_alias(self, "max_effort", "max_force") + drive_type: Literal["force", "acceleration"] | None = None """Joint drive type to apply. @@ -201,16 +354,20 @@ class JointDrivePropertiesCfg: then the joint is driven by an acceleration (usually used for kinematic joints). """ - max_effort: float | None = None - """Maximum effort that can be applied to the joint (in kg-m^2/s^2).""" + max_force: float | None = None + """Maximum force/torque that can be applied to the joint [N for linear joints, N-m for angular joints]. - max_velocity: float | None = None - """Maximum velocity of the joint. + Writes ``drive::physics:maxForce`` via :class:`UsdPhysics.DriveAPI`. + """ - The unit depends on the joint model: + max_effort: float | None = None + """Deprecated alias for :attr:`max_force`. - * For linear joints, the unit is m/s. - * For angular joints, the unit is rad/s. + .. deprecated:: 4.6.25 + Use :attr:`max_force` instead. The cfg field is renamed so its + snake_case name maps identity-style to the USD camelCase attribute + (``maxForce`` on ``UsdPhysics.DriveAPI``). The alias is forwarded to + :attr:`max_force` in :meth:`__post_init__` and will be removed in 5.0. """ stiffness: float | None = None @@ -243,307 +400,122 @@ class JointDrivePropertiesCfg: overridden later by the actuator model. """ + max_joint_velocity: float | None = None + """Maximum velocity of the joint [m/s for linear joints, rad/s for angular joints]. -@configclass -class FixedTendonPropertiesCfg: - """Properties to define fixed tendons of an articulation. - - See :meth:`modify_fixed_tendon_properties` for more information. - - .. note:: - If the values are None, they are not modified. This is useful when you want to set only a subset of - the properties and leave the rest as-is. + Notes: + Today this writes ``physxJoint:maxJointVelocity`` (a PhysX add-on schema attribute). + Newton's USD importer consumes the same attribute via its PhysX-bridge resolver and + populates ``Model.joint_velocity_limit``; the PhysX engine consumes it natively. The + Kamino solver honors the limit at the simulation step. The XPBD, Featherstone, and + Semi-implicit Newton solvers import the value but do not consume it in their kernels; + the MuJoCo (MJC) solver explicitly drops it. When Newton ships ``newton:maxJointVelocity`` + as a registered applied API, the writer namespace will switch transparently and this + docstring caveat will be removed. """ - tendon_enabled: bool | None = None - """Whether to enable or disable the tendon.""" - - stiffness: float | None = None - """Spring stiffness term acting on the tendon's length.""" - - damping: float | None = None - """The damping term acting on both the tendon length and the tendon-length limits.""" - - limit_stiffness: float | None = None - """Limit stiffness term acting on the tendon's length limits.""" - - offset: float | None = None - """Length offset term for the tendon. + max_velocity: float | None = None + """Deprecated alias for :attr:`max_joint_velocity`. - It defines an amount to be added to the accumulated length computed for the tendon. This allows the application - to actuate the tendon by shortening or lengthening it. + .. deprecated:: 4.6.25 + Use :attr:`max_joint_velocity` instead. The cfg field is renamed so its + snake_case name maps identity-style to the USD camelCase attribute + (``physxJoint:maxJointVelocity``). The alias is forwarded to + :attr:`max_joint_velocity` in :meth:`__post_init__` and will be removed in 5.0. """ - rest_length: float | None = None - """Spring rest length of the tendon.""" - @configclass -class SpatialTendonPropertiesCfg: - """Properties to define spatial tendons of an articulation. +class MeshCollisionBaseCfg: + """Solver-common properties to apply to a mesh in regards to collision. - See :meth:`modify_spatial_tendon_properties` for more information. - - .. note:: - If the values are None, they are not modified. This is useful when you want to set only a subset of - the properties and leave the rest as-is. - """ - - tendon_enabled: bool | None = None - """Whether to enable or disable the tendon.""" - - stiffness: float | None = None - """Spring stiffness term acting on the tendon's length.""" - - damping: float | None = None - """The damping term acting on both the tendon length and the tendon-length limits.""" + Carries only the standard ``UsdPhysics:MeshCollisionAPI`` token + (:attr:`mesh_approximation_name` -> ``physics:approximation``). For PhysX-cooking + tunables (convex hull / decomposition / triangle mesh / SDF), use the + ``Physx*PropertiesCfg`` subclasses in :mod:`isaaclab_physx.sim.schemas`. - limit_stiffness: float | None = None - """Limit stiffness term acting on the tendon's length limits.""" - - offset: float | None = None - """Length offset term for the tendon. - - It defines an amount to be added to the accumulated length computed for the tendon. This allows the application - to actuate the tendon by shortening or lengthening it. - """ - - -@configclass -class MeshCollisionPropertiesCfg: - """Properties to apply to a mesh in regards to collision. - See :meth:`set_mesh_collision_properties` for more information. + See :meth:`modify_mesh_collision_properties` for more information. .. note:: - If the values are None, they are not modified. This is useful when you want to set only a subset of - the properties and leave the rest as-is. + If the values are None, they are not modified. This is useful when you want to + set only a subset of the properties and leave the rest as-is. """ - usd_api: str | None = None - """USD API name for mesh collision (e.g. 'MeshCollisionAPI').""" - - physx_api: str | None = None - """PhysX schema name for mesh collision (e.g. 'PhysxConvexDecompositionCollisionAPI').""" + # -- Class metadata (not dataclass fields) -- + # The standard ``UsdPhysics.MeshCollisionAPI`` is always applied by the writer when a + # mesh-collision cfg is supplied; ``_usd_applied_schema`` here records the standard + # API name so subclasses that author no PhysX namespace can rely on the writer's + # standard-vs-PhysX gating logic. PhysX-cooking subclasses override this. + _usd_applied_schema: ClassVar[str | None] = "MeshCollisionAPI" + # Base class authors no PhysX-namespaced fields, so no namespace is defined. + _usd_namespace: ClassVar[str | None] = None + _usd_attr_name_map: ClassVar[dict] = {} + _usd_field_exceptions: ClassVar[dict] = {} mesh_approximation_name: str = "none" """Name of mesh collision approximation method. Default: "none". - Refer to :const:`schemas.MESH_APPROXIMATION_TOKENS` for available options. - """ - -@configclass -class BoundingCubePropertiesCfg(MeshCollisionPropertiesCfg): - usd_api: str = "MeshCollisionAPI" - """Original USD Documentation: - https://docs.omniverse.nvidia.com/kit/docs/omni_usd_schema_physics/latest/class_usd_physics_mesh_collision_a_p_i.html - """ - - mesh_approximation_name: str = "boundingCube" - """Name of mesh collision approximation method. Default: "boundingCube". + Writes ``physics:approximation`` via :class:`UsdPhysics.MeshCollisionAPI`. Refer to :const:`schemas.MESH_APPROXIMATION_TOKENS` for available options. """ - -@configclass -class BoundingSpherePropertiesCfg(MeshCollisionPropertiesCfg): - usd_api: str = "MeshCollisionAPI" - """Original USD Documentation: - https://docs.omniverse.nvidia.com/kit/docs/omni_usd_schema_physics/latest/class_usd_physics_mesh_collision_a_p_i.html - """ - - mesh_approximation_name: str = "boundingSphere" - """Name of mesh collision approximation method. Default: "boundingSphere". - Refer to :const:`schemas.MESH_APPROXIMATION_TOKENS` for available options. - """ + def __getattr__(self, name: str): + """Deprecated read-only access to the legacy ``usd_api`` / ``physx_api`` instance attrs. + + Falls back here only when the attribute is not found on the dataclass instance. + Returns the legacy-mapped string value derived from the class-level + ``_usd_applied_schema`` metadata and emits a ``DeprecationWarning``. + """ + if name == "usd_api": + warnings.warn( + "'usd_api' attribute is deprecated and will be removed in 5.0. Use class-level" + " metadata via getattr(cfg, '_usd_applied_schema').", + DeprecationWarning, + stacklevel=2, + ) + schema = self.__dict__.get("_usd_applied_schema", None) + # Every PhysX cooking subclass legacy-mapped to ``"MeshCollisionAPI"``; the base + # class also wrote that token. Return ``None`` only when no schema is declared. + return "MeshCollisionAPI" if schema is not None else None + if name == "physx_api": + warnings.warn( + "'physx_api' attribute is deprecated and will be removed in 5.0. Use class-level" + " metadata via getattr(cfg, '_usd_applied_schema').", + DeprecationWarning, + stacklevel=2, + ) + schema = self.__dict__.get("_usd_applied_schema", None) + if schema and schema.startswith("Physx"): + return schema + return None + raise AttributeError(f"{type(self).__name__!r} object has no attribute {name!r}") @configclass -class ConvexDecompositionPropertiesCfg(MeshCollisionPropertiesCfg): - usd_api: str = "MeshCollisionAPI" - """Original USD Documentation: - https://docs.omniverse.nvidia.com/kit/docs/omni_usd_schema_physics/latest/class_usd_physics_mesh_collision_a_p_i.html - """ - - physx_api: str = "PhysxConvexDecompositionCollisionAPI" - """Original PhysX Documentation: - https://docs.omniverse.nvidia.com/kit/docs/omni_usd_schema_physics/latest/class_physx_schema_physx_convex_decomposition_collision_a_p_i.html - """ - - mesh_approximation_name: str = "convexDecomposition" - """Name of mesh collision approximation method. Default: "convexDecomposition". - Refer to :const:`schemas.MESH_APPROXIMATION_TOKENS` for available options. - """ - - hull_vertex_limit: int | None = None - """Convex hull vertex limit used for convex hull cooking. - - Defaults to 64. - """ - max_convex_hulls: int | None = None - """Maximum of convex hulls created during convex decomposition. - Default value is 32. - """ - min_thickness: float | None = None - """Convex hull min thickness. - - Range: [0, inf). Units are distance. Default value is 0.001. - """ - voxel_resolution: int | None = None - """Voxel resolution used for convex decomposition. - - Defaults to 500,000 voxels. - """ - error_percentage: float | None = None - """Convex decomposition error percentage parameter. - - Defaults to 10 percent. Units are percent. - """ - shrink_wrap: bool | None = None - """Attempts to adjust the convex hull points so that they are projected onto the surface of the original graphics - mesh. - - Defaults to False. - """ +class BoundingCubePropertiesCfg(MeshCollisionBaseCfg): + """Bounding-cube mesh collision approximation. USD-only; authors no PhysX schema. + Writes the ``boundingCube`` token to ``physics:approximation`` via + :class:`UsdPhysics.MeshCollisionAPI`. -@configclass -class ConvexHullPropertiesCfg(MeshCollisionPropertiesCfg): - usd_api: str = "MeshCollisionAPI" - """Original USD Documentation: + Original USD Documentation: https://docs.omniverse.nvidia.com/kit/docs/omni_usd_schema_physics/latest/class_usd_physics_mesh_collision_a_p_i.html """ - physx_api: str = "PhysxConvexHullCollisionAPI" - """Original PhysX Documentation: - https://docs.omniverse.nvidia.com/kit/docs/omni_usd_schema_physics/latest/class_physx_schema_physx_convex_hull_collision_a_p_i.html - """ - - mesh_approximation_name: str = "convexHull" - """Name of mesh collision approximation method. Default: "convexHull". - Refer to :const:`schemas.MESH_APPROXIMATION_TOKENS` for available options. - """ - - hull_vertex_limit: int | None = None - """Convex hull vertex limit used for convex hull cooking. - - Defaults to 64. - """ - min_thickness: float | None = None - """Convex hull min thickness. - - Range: [0, inf). Units are distance. Default value is 0.001. - """ + mesh_approximation_name: str = "boundingCube" + """Name of mesh collision approximation method. Default: "boundingCube".""" @configclass -class TriangleMeshPropertiesCfg(MeshCollisionPropertiesCfg): - physx_api: str = "PhysxTriangleMeshCollisionAPI" - """Triangle mesh is only supported by PhysX API. +class BoundingSpherePropertiesCfg(MeshCollisionBaseCfg): + """Bounding-sphere mesh collision approximation. USD-only; authors no PhysX schema. - Original PhysX Documentation: - https://docs.omniverse.nvidia.com/kit/docs/omni_usd_schema_physics/latest/class_physx_schema_physx_triangle_mesh_collision_a_p_i.html - """ + Writes the ``boundingSphere`` token to ``physics:approximation`` via + :class:`UsdPhysics.MeshCollisionAPI`. - mesh_approximation_name: str = "none" - """Name of mesh collision approximation method. Default: "none" (uses triangle mesh). - Refer to :const:`schemas.MESH_APPROXIMATION_TOKENS` for available options. - """ - - weld_tolerance: float | None = None - """Mesh weld tolerance, controls the distance at which vertices are welded. - - Default -inf will autocompute the welding tolerance based on the mesh size. Zero value will disable welding. - Range: [0, inf) Units: distance - """ - - -@configclass -class TriangleMeshSimplificationPropertiesCfg(MeshCollisionPropertiesCfg): - usd_api: str = "MeshCollisionAPI" - """Original USD Documentation: + Original USD Documentation: https://docs.omniverse.nvidia.com/kit/docs/omni_usd_schema_physics/latest/class_usd_physics_mesh_collision_a_p_i.html """ - physx_api: str = "PhysxTriangleMeshSimplificationCollisionAPI" - """Original PhysX Documentation: - https://docs.omniverse.nvidia.com/kit/docs/omni_usd_schema_physics/latest/class_physx_schema_physx_triangle_mesh_simplification_collision_a_p_i.html - """ - - mesh_approximation_name: str = "meshSimplification" - """Name of mesh collision approximation method. Default: "meshSimplification". - Refer to :const:`schemas.MESH_APPROXIMATION_TOKENS` for available options. - """ - - simplification_metric: float | None = None - """Mesh simplification accuracy. - - Defaults to 0.55. - """ - weld_tolerance: float | None = None - """Mesh weld tolerance, controls the distance at which vertices are welded. - - Default -inf will autocompute the welding tolerance based on the mesh size. Zero value will disable welding. - Range: [0, inf) Units: distance - """ - - -@configclass -class SDFMeshPropertiesCfg(MeshCollisionPropertiesCfg): - physx_api: str = "PhysxSDFMeshCollisionAPI" - """SDF mesh is only supported by PhysX API. - - Original PhysX documentation: - https://docs.omniverse.nvidia.com/kit/docs/omni_usd_schema_physics/latest/class_physx_schema_physx_s_d_f_mesh_collision_a_p_i.html - - More details and steps for optimizing SDF results can be found here: - https://nvidia-omniverse.github.io/PhysX/physx/5.2.1/docs/RigidBodyCollision.html#dynamic-triangle-meshes-with-sdfs - """ - - mesh_approximation_name: str = "sdf" - """Name of mesh collision approximation method. Default: "sdf". - Refer to :const:`schemas.MESH_APPROXIMATION_TOKENS` for available options. - """ - - sdf_margin: float | None = None - """Margin to increase the size of the SDF relative to the bounding box diagonal length of the mesh. - - - A sdf margin value of 0.01 means the sdf boundary will be enlarged in any direction by 1% of the mesh's bounding - box diagonal length. Representing the margin relative to the bounding box diagonal length ensures that it is scale - independent. Margins allow for precise distance queries in a region slightly outside of the mesh's bounding box. - - Default value is 0.01. - Range: [0, inf) Units: dimensionless - """ - sdf_narrow_band_thickness: float | None = None - """Size of the narrow band around the mesh surface where high resolution SDF samples are available. - - Outside of the narrow band, only low resolution samples are stored. Representing the narrow band thickness as a - fraction of the mesh's bounding box diagonal length ensures that it is scale independent. A value of 0.01 is - usually large enough. The smaller the narrow band thickness, the smaller the memory consumption of the sparse SDF. - - Default value is 0.01. - Range: [0, 1] Units: dimensionless - """ - sdf_resolution: int | None = None - """The spacing of the uniformly sampled SDF is equal to the largest AABB extent of the mesh, - divided by the resolution. - - Choose the lowest possible resolution that provides acceptable performance; very high resolution results in large - memory consumption, and slower cooking and simulation performance. - - Default value is 256. - Range: (1, inf) - """ - sdf_subgrid_resolution: int | None = None - """A positive subgrid resolution enables sparsity on signed-distance-fields (SDF) while a value of 0 leads to the - usage of a dense SDF. - - A value in the range of 4 to 8 is a reasonable compromise between block size and the overhead introduced by block - addressing. The smaller a block, the more memory is spent on the address table. The bigger a block, the less - precisely the sparse SDF can adapt to the mesh's surface. In most cases sparsity reduces the memory consumption of - a SDF significantly. - - Default value is 6. - Range: [0, inf) - """ + mesh_approximation_name: str = "boundingSphere" + """Name of mesh collision approximation method. Default: "boundingSphere".""" diff --git a/source/isaaclab/isaaclab/sim/spawners/from_files/from_files_cfg.py b/source/isaaclab/isaaclab/sim/spawners/from_files/from_files_cfg.py index 78aaf1b15c94..87fc48de4d30 100644 --- a/source/isaaclab/isaaclab/sim/spawners/from_files/from_files_cfg.py +++ b/source/isaaclab/isaaclab/sim/spawners/from_files/from_files_cfg.py @@ -46,7 +46,7 @@ class FileCfg(RigidObjectSpawnerCfg, DeformableObjectSpawnerCfg): spatial_tendons_props: schemas.SpatialTendonPropertiesCfg | None = None """Properties to apply to the spatial tendons (if any).""" - joint_drive_props: schemas.JointDrivePropertiesCfg | None = None + joint_drive_props: schemas.JointDriveBaseCfg | None = None """Properties to apply to a joint. .. note:: diff --git a/source/isaaclab/isaaclab/sim/spawners/materials/__init__.py b/source/isaaclab/isaaclab/sim/spawners/materials/__init__.py index b86e98599fc0..ae4049c25d21 100644 --- a/source/isaaclab/isaaclab/sim/spawners/materials/__init__.py +++ b/source/isaaclab/isaaclab/sim/spawners/materials/__init__.py @@ -54,4 +54,30 @@ from isaaclab.utils.module import lazy_export -lazy_export() +_stub_getattr, _stub_dir, __all__ = lazy_export() + +# Names that moved out of this module into ``isaaclab_physx.sim.spawners.materials``. +# Resolved lazily on first access so importing ``isaaclab.sim.spawners.materials`` does +# not require ``isaaclab_physx`` to be installed. +_PHYSX_FORWARDS = frozenset({ + "RigidBodyMaterialCfg", + "PhysxRigidBodyMaterialCfg", +}) + + +def __getattr__(name): + if name in _PHYSX_FORWARDS: + try: + from isaaclab_physx.sim.spawners.materials import physics_materials_cfg as _physx_cfg + except ImportError as e: + raise ImportError( + f"'isaaclab.sim.spawners.materials.{name}' has moved to" + " 'isaaclab_physx.sim.spawners.materials'. Install the isaaclab_physx extension" + " or update your import. This forwarding shim is scheduled for removal in 5.0." + ) from e + return getattr(_physx_cfg, name) + return _stub_getattr(name) + + +def __dir__(): + return sorted(set(_stub_dir()) | _PHYSX_FORWARDS) diff --git a/source/isaaclab/isaaclab/sim/spawners/materials/__init__.pyi b/source/isaaclab/isaaclab/sim/spawners/materials/__init__.pyi index 93142ddab389..0dd023c2998f 100644 --- a/source/isaaclab/isaaclab/sim/spawners/materials/__init__.pyi +++ b/source/isaaclab/isaaclab/sim/spawners/materials/__init__.pyi @@ -6,7 +6,7 @@ __all__ = [ "spawn_rigid_body_material", "PhysicsMaterialCfg", - "RigidBodyMaterialCfg", + "RigidBodyMaterialBaseCfg", "spawn_from_mdl_file", "spawn_preview_surface", "GlassMdlCfg", @@ -18,7 +18,7 @@ __all__ = [ from .physics_materials import spawn_rigid_body_material from .physics_materials_cfg import ( PhysicsMaterialCfg, - RigidBodyMaterialCfg, + RigidBodyMaterialBaseCfg, ) from .visual_materials import spawn_from_mdl_file, spawn_preview_surface from .visual_materials_cfg import GlassMdlCfg, MdlFileCfg, PreviewSurfaceCfg, VisualMaterialCfg diff --git a/source/isaaclab/isaaclab/sim/spawners/materials/physics_materials.py b/source/isaaclab/isaaclab/sim/spawners/materials/physics_materials.py index 240a0ff00746..b76077b38bed 100644 --- a/source/isaaclab/isaaclab/sim/spawners/materials/physics_materials.py +++ b/source/isaaclab/isaaclab/sim/spawners/materials/physics_materials.py @@ -5,25 +5,33 @@ from __future__ import annotations +import dataclasses from typing import TYPE_CHECKING from pxr import Usd, UsdPhysics, UsdShade -from isaaclab.sim.utils import clone, safe_set_attribute_on_usd_prim, safe_set_attribute_on_usd_schema +from isaaclab.sim.schemas.schemas import _apply_namespaced_schemas +from isaaclab.sim.utils import clone from isaaclab.sim.utils.stage import get_current_stage -from isaaclab.utils.string import to_camel_case if TYPE_CHECKING: from . import physics_materials_cfg @clone -def spawn_rigid_body_material(prim_path: str, cfg: physics_materials_cfg.RigidBodyMaterialCfg) -> Usd.Prim: +def spawn_rigid_body_material(prim_path: str, cfg: physics_materials_cfg.RigidBodyMaterialBaseCfg) -> Usd.Prim: """Create material with rigid-body physics properties. Rigid body materials are used to define the physical properties to meshes of a rigid body. These - include the friction, restitution, and their respective combination modes. For more information on - rigid body material, please refer to the `documentation on PxMaterial `_. + include the friction, restitution, and (PhysX-only) compliant-contact spring and combine-mode + tokens. For more information on rigid body material, please refer to the `documentation on + PxMaterial `_. + + The writer is metadata-driven: it always applies the standard ``UsdPhysics.MaterialAPI`` and + writes the friction/restitution fields, then reads ``_usd_applied_schema``, ``_usd_namespace``, + and ``_usd_attr_name_map`` from the cfg to author solver-specific attributes. The applied + schema (e.g. ``PhysxMaterialAPI``) is added only when at least one solver-specific field has a + non-``None`` value at the instance level. .. note:: This function is decorated with :func:`clone` that resolves prim path into list of paths @@ -39,7 +47,8 @@ def spawn_rigid_body_material(prim_path: str, cfg: physics_materials_cfg.RigidBo The spawned rigid body material prim. Raises: - ValueError: When a prim already exists at the specified prim path and is not a material. + ValueError: When a prim already exists at the specified prim path and is not a material. + ValueError: When the cfg defines solver-specific fields but does not define ``_usd_namespace``. """ # get stage handle stage = get_current_stage() @@ -53,24 +62,17 @@ def spawn_rigid_body_material(prim_path: str, cfg: physics_materials_cfg.RigidBo # check if prim is a material if not prim.IsA(UsdShade.Material): raise ValueError(f"A prim already exists at path: '{prim_path}' but is not a material.") - # retrieve the USD rigid-body api - usd_physics_material_api = UsdPhysics.MaterialAPI(prim) - if not usd_physics_material_api: - usd_physics_material_api = UsdPhysics.MaterialAPI.Apply(prim) - # ensure PhysX material API is applied - applied = prim.GetAppliedSchemas() - if "PhysxMaterialAPI" not in applied: - prim.AddAppliedSchema("PhysxMaterialAPI") - - # convert to dict - cfg = cfg.to_dict() - del cfg["func"] - # set into USD API - for attr_name in ["static_friction", "dynamic_friction", "restitution"]: - value = cfg.pop(attr_name, None) - safe_set_attribute_on_usd_schema(usd_physics_material_api, attr_name, value, camel_case=True) - # set into PhysX API (prim attributes: physxMaterial:*) - for attr_name, value in cfg.items(): - safe_set_attribute_on_usd_prim(prim, f"physxMaterial:{to_camel_case(attr_name, 'cC')}", value, camel_case=False) + + # apply the standard UsdPhysics MaterialAPI (always) + if not UsdPhysics.MaterialAPI(prim): + UsdPhysics.MaterialAPI.Apply(prim) + + # build cfg dict, dropping underscore-prefixed metadata keys and the spawner ``func`` field + cfg_dict = {f.name: getattr(cfg, f.name) for f in dataclasses.fields(cfg) if f.name != "func"} + + # All fields routed by the helper: base friction/restitution under ``physics:*``, + # PhysX-subclass fields (compliant-contact, combine modes) under ``physxMaterial:*``. + _apply_namespaced_schemas(prim, cfg, cfg_dict) + # return the prim return prim diff --git a/source/isaaclab/isaaclab/sim/spawners/materials/physics_materials_cfg.py b/source/isaaclab/isaaclab/sim/spawners/materials/physics_materials_cfg.py index dde9aec6d905..86437285ee9e 100644 --- a/source/isaaclab/isaaclab/sim/spawners/materials/physics_materials_cfg.py +++ b/source/isaaclab/isaaclab/sim/spawners/materials/physics_materials_cfg.py @@ -7,10 +7,31 @@ from collections.abc import Callable from dataclasses import MISSING -from typing import Literal +from typing import ClassVar from isaaclab.utils import configclass +# Names that moved out of this submodule into ``isaaclab_physx.sim.spawners.materials.physics_materials_cfg``. +# Resolved lazily so callers using ``from isaaclab.sim.spawners.materials.physics_materials_cfg +# import RigidBodyMaterialCfg`` continue to work without importing ``isaaclab_physx`` at module +# load time. +_PHYSX_FORWARDS = frozenset({"RigidBodyMaterialCfg", "PhysxRigidBodyMaterialCfg"}) + + +def __getattr__(name): + if name in _PHYSX_FORWARDS: + try: + from isaaclab_physx.sim.spawners.materials import physics_materials_cfg as _physx_mat_cfg + except ImportError as e: + raise ImportError( + f"'isaaclab.sim.spawners.materials.physics_materials_cfg.{name}' has moved to" + " 'isaaclab_physx.sim.spawners.materials.physics_materials_cfg'. Install the" + " isaaclab_physx extension or update your import. This forwarding shim is scheduled" + " for removal in 5.0." + ) from e + return getattr(_physx_mat_cfg, name) + raise AttributeError(f"module 'isaaclab.sim.spawners.materials.physics_materials_cfg' has no attribute {name!r}") + @configclass class PhysicsMaterialCfg: @@ -27,12 +48,26 @@ class PhysicsMaterialCfg: @configclass -class RigidBodyMaterialCfg(PhysicsMaterialCfg): - """Physics material parameters for rigid bodies. +class RigidBodyMaterialBaseCfg(PhysicsMaterialCfg): + """Solver-common physics-material parameters for rigid bodies. + + Contains the friction and restitution fields from the `UsdPhysics.MaterialAPI`_ that are common + across all simulation backends. For PhysX-only material properties (compliant-contact spring, + combine modes), use :class:`~isaaclab_physx.sim.spawners.materials.PhysxRigidBodyMaterialCfg`. See :meth:`spawn_rigid_body_material` for more information. + + .. _UsdPhysics.MaterialAPI: https://openusd.org/dev/api/class_usd_physics_material_a_p_i.html """ + # -- Class metadata (not dataclass fields) -- + # ``static_friction`` / ``dynamic_friction`` / ``restitution`` write to ``physics:*`` + # (UsdPhysics standard attributes). The helper's per-declaring-class routing keeps + # them under the base namespace even when the cfg is a PhysX subclass instance. + _usd_namespace: ClassVar[str | None] = "physics" + _usd_applied_schema: ClassVar[str | None] = None + _usd_field_exceptions: ClassVar[dict] = {} + func: Callable | str = "{DIR}.physics_materials:spawn_rigid_body_material" static_friction: float = 0.5 @@ -43,37 +78,3 @@ class RigidBodyMaterialCfg(PhysicsMaterialCfg): restitution: float = 0.0 """The restitution coefficient. Defaults to 0.0.""" - - friction_combine_mode: Literal["average", "min", "multiply", "max"] = "average" - """Determines the way friction will be combined during collisions. Defaults to `"average"`. - - .. attention:: - - When two physics materials with different combine modes collide, the combine mode with the higher - priority will be used. The priority order is provided `here - `__. - """ - - restitution_combine_mode: Literal["average", "min", "multiply", "max"] = "average" - """Determines the way restitution coefficient will be combined during collisions. Defaults to `"average"`. - - .. attention:: - - When two physics materials with different combine modes collide, the combine mode with the higher - priority will be used. The priority order is provided `here - `__. - """ - - compliant_contact_stiffness: float = 0.0 - """Spring stiffness for a compliant contact model using implicit springs. Defaults to 0.0. - - A higher stiffness results in behavior closer to a rigid contact. The compliant contact model is only enabled - if the stiffness is larger than 0. - """ - - compliant_contact_damping: float = 0.0 - """Damping coefficient for a compliant contact model using implicit springs. Defaults to 0.0. - - Irrelevant if compliant contacts are disabled when :obj:`compliant_contact_stiffness` is set to zero and - rigid contacts are active. - """ diff --git a/source/isaaclab/isaaclab/sim/spawners/spawner_cfg.py b/source/isaaclab/isaaclab/sim/spawners/spawner_cfg.py index 7a803ad0e0dd..0adf9215f81e 100644 --- a/source/isaaclab/isaaclab/sim/spawners/spawner_cfg.py +++ b/source/isaaclab/isaaclab/sim/spawners/spawner_cfg.py @@ -85,10 +85,10 @@ class RigidObjectSpawnerCfg(SpawnerCfg): mass_props: schemas.MassPropertiesCfg | None = None """Mass properties.""" - rigid_props: schemas.RigidBodyPropertiesCfg | None = None + rigid_props: schemas.RigidBodyBaseCfg | None = None """Rigid body properties. - For making a rigid object static, set the :attr:`schemas.RigidBodyPropertiesCfg.kinematic_enabled` + For making a rigid object static, set the :attr:`schemas.RigidBodyBaseCfg.kinematic_enabled` as True. This will make the object static and will not be affected by gravity or other forces. """ diff --git a/source/isaaclab/isaaclab/utils/configclass.py b/source/isaaclab/isaaclab/utils/configclass.py index 59605f2797cc..f44f1288e017 100644 --- a/source/isaaclab/isaaclab/utils/configclass.py +++ b/source/isaaclab/isaaclab/utils/configclass.py @@ -452,9 +452,13 @@ class State: for key in ann: # find matching field in class value = class_members.get(key, MISSING) - # check if key belongs to ClassVar - # in that case, we cannot use default_factory! - origin = getattr(ann[key], "__origin__", None) + # check if key belongs to ClassVar -- in that case, we cannot use default_factory! + # ``from __future__ import annotations`` turns annotations into strings, so we + # also detect the string form (``"ClassVar[...]"``) for files using PEP 563. + ann_value = ann[key] + if isinstance(ann_value, str) and ann_value.startswith(("ClassVar", "typing.ClassVar")): + continue + origin = getattr(ann_value, "__origin__", None) if origin is ClassVar: continue # check if f is MISSING diff --git a/source/isaaclab/test/sim/test_schemas.py b/source/isaaclab/test/sim/test_schemas.py index 1acda3b149c6..1fb03ede1433 100644 --- a/source/isaaclab/test/sim/test_schemas.py +++ b/source/isaaclab/test/sim/test_schemas.py @@ -13,14 +13,32 @@ """Rest everything follows.""" import math +import warnings import pytest +from isaaclab_physx.sim.schemas import ( + ArticulationRootPropertiesCfg as ArticulationRootDeprecatedAliasCfg, +) +from isaaclab_physx.sim.schemas import ( + CollisionPropertiesCfg as PhysxCollisionPropertiesCfgAlias, +) +from isaaclab_physx.sim.schemas import ( + PhysxArticulationRootPropertiesCfg, + PhysxCollisionPropertiesCfg, + PhysxJointDrivePropertiesCfg, + PhysxRigidBodyPropertiesCfg, +) +from isaaclab_physx.sim.schemas import ( + PhysXCollisionPropertiesCfg as PhysxDeformableCollisionAliasCfg, +) +from isaaclab_physx.sim.spawners.materials import PhysxRigidBodyMaterialCfg, RigidBodyMaterialCfg from pxr import UsdPhysics import isaaclab.sim as sim_utils import isaaclab.sim.schemas as schemas from isaaclab.sim import SimulationCfg, SimulationContext +from isaaclab.sim.spawners.materials import RigidBodyMaterialBaseCfg, spawn_rigid_body_material from isaaclab.utils.assets import ISAAC_NUCLEUS_DIR from isaaclab.utils.string import to_camel_case @@ -44,7 +62,7 @@ def setup_simulation(): stabilization_threshold=5.0, fix_root_link=False, ) - rigid_cfg = schemas.RigidBodyPropertiesCfg( + rigid_cfg = PhysxRigidBodyPropertiesCfg( rigid_body_enabled=True, kinematic_enabled=False, disable_gravity=False, @@ -69,8 +87,8 @@ def setup_simulation(): torsional_patch_radius=1.0, ) mass_cfg = schemas.MassPropertiesCfg(mass=1.0, density=100.0) - joint_cfg = schemas.JointDrivePropertiesCfg( - drive_type="acceleration", max_effort=80.0, max_velocity=10.0, stiffness=10.0, damping=0.1 + joint_cfg = PhysxJointDrivePropertiesCfg( + drive_type="acceleration", max_force=80.0, max_joint_velocity=10.0, stiffness=10.0, damping=0.1 ) yield sim, arti_cfg, rigid_cfg, collision_cfg, mass_cfg, joint_cfg # Teardown @@ -86,12 +104,602 @@ def test_valid_properties_cfg(setup_simulation): This is to ensure that we check that all the properties of the schema are set. """ sim, arti_cfg, rigid_cfg, collision_cfg, mass_cfg, joint_cfg = setup_simulation + # deprecation aliases are nulled by __post_init__ after forwarding to the canonical + # field; exclude them from the all-non-None check. + deprecation_aliases = {"max_velocity", "max_effort"} for cfg in [arti_cfg, rigid_cfg, collision_cfg, mass_cfg, joint_cfg]: - # check nothing is none for k, v in cfg.__dict__.items(): + # skip class-metadata keys (``_usd_*``) and deprecation aliases nulled in __post_init__ + if k.startswith("_") or k in deprecation_aliases: + continue assert v is not None, f"{cfg.__class__.__name__}:{k} is None. Please make sure schemas are valid." +@pytest.mark.isaacsim_ci +def test_max_joint_velocity_on_base_cfg(setup_simulation): + """Setting ``max_joint_velocity`` on the base ``JointDriveBaseCfg`` must author + ``physxJoint:maxJointVelocity`` on the prim, identical to setting it on + the deprecated PhysX subclass. + + Regression test for the Path 2 placement rule: ``max_joint_velocity`` is the + only USD path to ``Model.joint_velocity_limit`` and lives on the base. + """ + sim, _, _, _, _, _ = setup_simulation + stage = sim_utils.get_current_stage() + + base_cfg = schemas.JointDriveBaseCfg( + drive_type="acceleration", + max_force=80.0, + max_joint_velocity=10.0, + stiffness=10.0, + damping=0.1, + ) + + # spawn a minimal articulation with a revolute joint, then write properties. + sim_utils.create_prim("/World/Articulation", prim_type="Xform") + sim_utils.create_prim("/World/Articulation/body0", prim_type="Cube") + sim_utils.create_prim("/World/Articulation/body1", prim_type="Cube") + UsdPhysics.RevoluteJoint.Define(stage, "/World/Articulation/joint_0") + + prim_path = "/World/Articulation/joint_0" + # use unwrapped function (no parent traversal) so this returns the inner bool + schemas.modify_joint_drive_properties.__wrapped__(prim_path, base_cfg) + + # Revolute drives convert rad/s -> deg/s; check the authored value. + attr = stage.GetPrimAtPath(prim_path).GetAttribute("physxJoint:maxJointVelocity") + assert attr.IsValid(), "physxJoint:maxJointVelocity was not authored on the prim" + expected_deg_per_sec = 10.0 * 180.0 / math.pi + assert attr.Get() == pytest.approx(expected_deg_per_sec, rel=1e-6) + + +@pytest.mark.isaacsim_ci +def test_max_velocity_deprecation_alias(setup_simulation): + """Legacy ``max_velocity`` kwarg must forward to ``max_joint_velocity`` and emit + a ``DeprecationWarning``. Behavior must match setting ``max_joint_velocity`` directly. + """ + sim, _, _, _, _, _ = setup_simulation + stage = sim_utils.get_current_stage() + + with pytest.warns(DeprecationWarning, match="max_velocity"): + base_cfg = schemas.JointDriveBaseCfg( + drive_type="acceleration", + max_force=80.0, + max_velocity=10.0, + stiffness=10.0, + damping=0.1, + ) + + assert base_cfg.max_joint_velocity == 10.0 + assert base_cfg.max_velocity is None + + sim_utils.create_prim("/World/Articulation_dep", prim_type="Xform") + sim_utils.create_prim("/World/Articulation_dep/body0", prim_type="Cube") + sim_utils.create_prim("/World/Articulation_dep/body1", prim_type="Cube") + UsdPhysics.RevoluteJoint.Define(stage, "/World/Articulation_dep/joint_0") + prim_path = "/World/Articulation_dep/joint_0" + schemas.modify_joint_drive_properties.__wrapped__(prim_path, base_cfg) + + attr = stage.GetPrimAtPath(prim_path).GetAttribute("physxJoint:maxJointVelocity") + assert attr.IsValid() + assert attr.Get() == pytest.approx(10.0 * 180.0 / math.pi, rel=1e-6) + + +@pytest.mark.isaacsim_ci +def test_max_effort_deprecation_alias(setup_simulation): + """Legacy ``max_effort`` kwarg must forward to ``max_force`` and emit + a ``DeprecationWarning``. Behavior must match setting ``max_force`` directly. + """ + sim, _, _, _, _, _ = setup_simulation + stage = sim_utils.get_current_stage() + + with pytest.warns(DeprecationWarning, match="max_effort"): + base_cfg = schemas.JointDriveBaseCfg( + drive_type="acceleration", + max_effort=42.0, + stiffness=10.0, + damping=0.1, + ) + + assert base_cfg.max_force == 42.0 + assert base_cfg.max_effort is None + + sim_utils.create_prim("/World/Articulation_eff", prim_type="Xform") + sim_utils.create_prim("/World/Articulation_eff/body0", prim_type="Cube") + sim_utils.create_prim("/World/Articulation_eff/body1", prim_type="Cube") + UsdPhysics.PrismaticJoint.Define(stage, "/World/Articulation_eff/joint_0") + prim_path = "/World/Articulation_eff/joint_0" + schemas.modify_joint_drive_properties.__wrapped__(prim_path, base_cfg) + + attr = stage.GetPrimAtPath(prim_path).GetAttribute("drive:linear:physics:maxForce") + assert attr.IsValid() + assert attr.Get() == pytest.approx(42.0, rel=1e-6) + + +@pytest.mark.isaacsim_ci +def test_joint_drive_base_no_physx_schema_when_max_joint_velocity_unset(setup_simulation): + """Regression: setting only UsdPhysics drive fields on JointDriveBaseCfg + must NOT cause PhysxJointAPI to be applied to the prim. Without this, + Newton-targeted users get PhysX schemas stamped on every joint.""" + sim, _, _, _, _, _ = setup_simulation + stage = sim_utils.get_current_stage() + + base_cfg = schemas.JointDriveBaseCfg( + drive_type="acceleration", + max_force=80.0, + stiffness=10.0, + damping=0.1, + # max_joint_velocity intentionally left None + ) + sim_utils.create_prim("/World/Articulation", prim_type="Xform") + sim_utils.create_prim("/World/Articulation/body0", prim_type="Cube") + sim_utils.create_prim("/World/Articulation/body1", prim_type="Cube") + UsdPhysics.RevoluteJoint.Define(stage, "/World/Articulation/joint_0") + + prim_path = "/World/Articulation/joint_0" + schemas.modify_joint_drive_properties.__wrapped__(prim_path, base_cfg) + + applied = stage.GetPrimAtPath(prim_path).GetAppliedSchemas() + assert "PhysxJointAPI" not in applied, ( + f"PhysxJointAPI should not be applied when max_velocity is None; got {list(applied)}" + ) + + +@pytest.mark.isaacsim_ci +def test_disable_gravity_on_base_cfg(setup_simulation): + """Setting disable_gravity on the base RigidBodyBaseCfg must author + physxRigidBody:disableGravity on the prim. PhysX honors per-body; + Newton currently honors at scene level (partial), documented in field + docstring. Regression test for the consumption-gated placement rule.""" + sim, _, _, _, _, _ = setup_simulation + stage = sim_utils.get_current_stage() + + base_cfg = schemas.RigidBodyBaseCfg( + rigid_body_enabled=True, + kinematic_enabled=False, + disable_gravity=True, + ) + sim_utils.create_prim("/World/cube_dg", prim_type="Cube", translation=(0.0, 0.0, 0.62)) + schemas.define_rigid_body_properties("/World/cube_dg", base_cfg) + + prim_path = "/World/cube_dg" + attr = stage.GetPrimAtPath(prim_path).GetAttribute("physxRigidBody:disableGravity") + assert attr.IsValid(), "physxRigidBody:disableGravity was not authored on the prim" + assert attr.Get() is True + applied = stage.GetPrimAtPath(prim_path).GetAppliedSchemas() + assert "PhysxRigidBodyAPI" in applied, ( + f"PhysxRigidBodyAPI must be applied when disable_gravity is set; got {list(applied)}" + ) + + +@pytest.mark.isaacsim_ci +def test_physx_rigid_body_no_physx_schema_when_all_physx_fields_none(setup_simulation): + """Regression: PhysxRigidBodyPropertiesCfg with all PhysX-specific fields + left as None must NOT cause PhysxRigidBodyAPI to be applied to the prim. + The user only authored UsdPhysics-standard fields; the PhysX schema + should not be stamped onto a Newton-targeted asset.""" + sim, _, _, _, _, _ = setup_simulation + stage = sim_utils.get_current_stage() + + cfg = PhysxRigidBodyPropertiesCfg( + rigid_body_enabled=True, + kinematic_enabled=False, + # every PhysX field intentionally left None + ) + sim_utils.create_prim("/World/cube_no_physx", prim_type="Cube", translation=(0.0, 0.0, 0.62)) + schemas.define_rigid_body_properties("/World/cube_no_physx", cfg) + + prim_path = "/World/cube_no_physx" + applied = stage.GetPrimAtPath(prim_path).GetAppliedSchemas() + assert "PhysxRigidBodyAPI" not in applied, ( + f"PhysxRigidBodyAPI should not be applied when no PhysX fields are set; got {list(applied)}" + ) + + +@pytest.mark.isaacsim_ci +def test_rigid_body_material_base_cfg(setup_simulation): + """Setting only UsdPhysics fields on RigidBodyMaterialBaseCfg must author the + three friction/restitution attrs and must NOT apply PhysxMaterialAPI.""" + sim, _, _, _, _, _ = setup_simulation + stage = sim_utils.get_current_stage() + + cfg = RigidBodyMaterialBaseCfg(static_friction=0.7, dynamic_friction=0.6, restitution=0.1) + prim_path = "/World/Looks/BaseMaterial" + spawn_rigid_body_material.__wrapped__(prim_path, cfg) + + prim = stage.GetPrimAtPath(prim_path) + assert prim.GetAttribute("physics:staticFriction").Get() == pytest.approx(0.7) + assert prim.GetAttribute("physics:dynamicFriction").Get() == pytest.approx(0.6) + assert prim.GetAttribute("physics:restitution").Get() == pytest.approx(0.1) + applied = prim.GetAppliedSchemas() + assert "PhysxMaterialAPI" not in applied, ( + f"PhysxMaterialAPI must not be applied for the base cfg; got {list(applied)}" + ) + + +@pytest.mark.isaacsim_ci +def test_physx_rigid_body_material_cfg(setup_simulation): + """Setting a PhysX-namespaced field on PhysxRigidBodyMaterialCfg must author the + namespaced attribute AND apply PhysxMaterialAPI.""" + sim, _, _, _, _, _ = setup_simulation + stage = sim_utils.get_current_stage() + + cfg = PhysxRigidBodyMaterialCfg(static_friction=0.7, compliant_contact_stiffness=100.0) + prim_path = "/World/Looks/PhysxMaterial" + spawn_rigid_body_material.__wrapped__(prim_path, cfg) + + prim = stage.GetPrimAtPath(prim_path) + assert prim.GetAttribute("physics:staticFriction").Get() == pytest.approx(0.7) + assert prim.GetAttribute("physxMaterial:compliantContactStiffness").Get() == pytest.approx(100.0) + applied = prim.GetAppliedSchemas() + assert "PhysxMaterialAPI" in applied, ( + f"PhysxMaterialAPI must be applied when a PhysX field is set; got {list(applied)}" + ) + + +@pytest.mark.isaacsim_ci +def test_rigid_body_material_deprecation_alias(setup_simulation): + """Instantiating the legacy ``RigidBodyMaterialCfg`` name emits exactly one + ``DeprecationWarning`` whose message references the 5.0 removal target.""" + with warnings.catch_warnings(record=True) as caught: + warnings.simplefilter("always") + RigidBodyMaterialCfg() + deprecations = [w for w in caught if issubclass(w.category, DeprecationWarning)] + assert len(deprecations) == 1, f"expected exactly one DeprecationWarning, got {len(deprecations)}" + assert "5.0" in str(deprecations[0].message) + + +@pytest.mark.isaacsim_ci +def test_collision_base_cfg_writes_physx_namespaced_attrs(setup_simulation): + """Setting ``contact_offset`` / ``rest_offset`` on the base ``CollisionBaseCfg`` must + author the ``physxCollision:*`` attributes AND apply ``PhysxCollisionAPI``. Newton's + importer consumes them via the PhysX bridge resolver.""" + sim, _, _, _, _, _ = setup_simulation + stage = sim_utils.get_current_stage() + + base_cfg = schemas.CollisionBaseCfg(collision_enabled=True, contact_offset=0.05, rest_offset=0.001) + sim_utils.create_prim("/World/cube_co", prim_type="Cube", translation=(0.0, 0.0, 0.62)) + schemas.define_collision_properties("/World/cube_co", base_cfg) + + prim = stage.GetPrimAtPath("/World/cube_co") + assert prim.GetAttribute("physxCollision:contactOffset").Get() == pytest.approx(0.05) + assert prim.GetAttribute("physxCollision:restOffset").Get() == pytest.approx(0.001) + applied = prim.GetAppliedSchemas() + assert "PhysxCollisionAPI" in applied, ( + f"PhysxCollisionAPI must be applied when contact_offset/rest_offset are set; got {list(applied)}" + ) + + +@pytest.mark.isaacsim_ci +def test_collision_base_cfg_no_physx_schema_when_only_usd_field_set(setup_simulation): + """Regression: setting only ``collision_enabled`` on ``CollisionBaseCfg`` must NOT + cause ``PhysxCollisionAPI`` to be applied. The user only authored a UsdPhysics-standard + field; the PhysX schema should not be stamped onto a Newton-targeted prim.""" + sim, _, _, _, _, _ = setup_simulation + stage = sim_utils.get_current_stage() + + base_cfg = schemas.CollisionBaseCfg(collision_enabled=True) + sim_utils.create_prim("/World/cube_co_only", prim_type="Cube", translation=(0.0, 0.0, 0.62)) + schemas.define_collision_properties("/World/cube_co_only", base_cfg) + + prim = stage.GetPrimAtPath("/World/cube_co_only") + assert prim.GetAttribute("physics:collisionEnabled").Get() is True + applied = prim.GetAppliedSchemas() + assert "PhysxCollisionAPI" not in applied, ( + f"PhysxCollisionAPI should not be applied when only collision_enabled is set; got {list(applied)}" + ) + + +@pytest.mark.isaacsim_ci +def test_physx_collision_cfg_writes_torsional_patch(setup_simulation): + """Setting ``torsional_patch_radius`` on ``PhysxCollisionPropertiesCfg`` must author + the ``physxCollision:torsionalPatchRadius`` attribute AND apply ``PhysxCollisionAPI``.""" + sim, _, _, _, _, _ = setup_simulation + stage = sim_utils.get_current_stage() + + cfg = PhysxCollisionPropertiesCfg(torsional_patch_radius=1.0) + sim_utils.create_prim("/World/cube_tpr", prim_type="Cube", translation=(0.0, 0.0, 0.62)) + schemas.define_collision_properties("/World/cube_tpr", cfg) + + prim = stage.GetPrimAtPath("/World/cube_tpr") + assert prim.GetAttribute("physxCollision:torsionalPatchRadius").Get() == pytest.approx(1.0) + applied = prim.GetAppliedSchemas() + assert "PhysxCollisionAPI" in applied + + +@pytest.mark.isaacsim_ci +def test_collision_deprecation_alias(setup_simulation): + """Instantiating the legacy ``CollisionPropertiesCfg`` name emits exactly one + ``DeprecationWarning`` whose message references the 5.0 removal target.""" + with warnings.catch_warnings(record=True) as caught: + warnings.simplefilter("always") + PhysxCollisionPropertiesCfgAlias() + deprecations = [w for w in caught if issubclass(w.category, DeprecationWarning)] + assert len(deprecations) == 1, f"expected exactly one DeprecationWarning, got {len(deprecations)}" + assert "5.0" in str(deprecations[0].message) + + +@pytest.mark.isaacsim_ci +def test_physx_capitalx_collision_deprecation_alias(setup_simulation): + """Instantiating the legacy ``PhysXCollisionPropertiesCfg`` (capital X, deformable) + name emits exactly one ``DeprecationWarning`` pointing to + ``PhysxDeformableCollisionPropertiesCfg``.""" + with warnings.catch_warnings(record=True) as caught: + warnings.simplefilter("always") + PhysxDeformableCollisionAliasCfg() + deprecations = [w for w in caught if issubclass(w.category, DeprecationWarning)] + assert len(deprecations) == 1, f"expected exactly one DeprecationWarning, got {len(deprecations)}" + assert "PhysxDeformableCollisionPropertiesCfg" in str(deprecations[0].message) + + +@pytest.mark.isaacsim_ci +def test_articulation_root_base_cfg_writes_articulation_enabled(setup_simulation): + """Setting ``articulation_enabled`` on the base ``ArticulationRootBaseCfg`` must author + ``physxArticulation:articulationEnabled`` AND apply ``PhysxArticulationAPI``. The + PhysX namespace is honored at sim time by PhysX and as a spawn-time guard by the IL + Newton wrapper.""" + sim, _, _, _, _, _ = setup_simulation + stage = sim_utils.get_current_stage() + + base_cfg = schemas.ArticulationRootBaseCfg(articulation_enabled=False) + sim_utils.create_prim("/World/arti_ae", prim_type="Xform") + schemas.define_articulation_root_properties("/World/arti_ae", base_cfg) + + prim = stage.GetPrimAtPath("/World/arti_ae") + assert prim.GetAttribute("physxArticulation:articulationEnabled").Get() is False + applied = prim.GetAppliedSchemas() + assert "PhysxArticulationAPI" in applied, ( + f"PhysxArticulationAPI must be applied when articulation_enabled is set; got {list(applied)}" + ) + + +@pytest.mark.isaacsim_ci +def test_articulation_root_base_no_physx_schema_when_only_fix_root_link_set(setup_simulation): + """Regression: setting only ``fix_root_link`` on ``ArticulationRootBaseCfg`` must NOT + cause ``PhysxArticulationAPI`` to be applied. ``fix_root_link`` is a writer-side flag + materializing ``UsdPhysics.FixedJoint``; it does not author any PhysX-namespaced + attribute. Newton-targeted prims that only set ``fix_root_link`` should not receive + ``PhysxArticulationAPI`` stamping.""" + sim, _, _, _, _, _ = setup_simulation + stage = sim_utils.get_current_stage() + + base_cfg = schemas.ArticulationRootBaseCfg(fix_root_link=False) + sim_utils.create_prim("/World/arti_frl", prim_type="Xform") + schemas.define_articulation_root_properties("/World/arti_frl", base_cfg) + + prim = stage.GetPrimAtPath("/World/arti_frl") + applied = prim.GetAppliedSchemas() + assert "PhysxArticulationAPI" not in applied, ( + f"PhysxArticulationAPI should not be applied when only fix_root_link is set; got {list(applied)}" + ) + + +@pytest.mark.isaacsim_ci +def test_physx_articulation_root_writes_self_collisions(setup_simulation): + """Setting ``enabled_self_collisions`` on ``PhysxArticulationRootPropertiesCfg`` must + author ``physxArticulation:enabledSelfCollisions`` AND apply ``PhysxArticulationAPI``.""" + sim, _, _, _, _, _ = setup_simulation + stage = sim_utils.get_current_stage() + + cfg = PhysxArticulationRootPropertiesCfg(enabled_self_collisions=True) + sim_utils.create_prim("/World/arti_sc", prim_type="Xform") + schemas.define_articulation_root_properties("/World/arti_sc", cfg) + + prim = stage.GetPrimAtPath("/World/arti_sc") + assert prim.GetAttribute("physxArticulation:enabledSelfCollisions").Get() is True + applied = prim.GetAppliedSchemas() + assert "PhysxArticulationAPI" in applied + + +@pytest.mark.isaacsim_ci +def test_articulation_root_deprecation_alias(setup_simulation): + """Instantiating the legacy ``ArticulationRootPropertiesCfg`` name emits exactly one + ``DeprecationWarning`` whose message references the 5.0 removal target.""" + with warnings.catch_warnings(record=True) as caught: + warnings.simplefilter("always") + ArticulationRootDeprecatedAliasCfg() + deprecations = [w for w in caught if issubclass(w.category, DeprecationWarning)] + assert len(deprecations) == 1, f"expected exactly one DeprecationWarning, got {len(deprecations)}" + assert "5.0" in str(deprecations[0].message) + + +@pytest.mark.isaacsim_ci +def test_mesh_collision_base_cfg_writes_approximation_token(setup_simulation): + """``MeshCollisionBaseCfg(mesh_approximation_name="boundingCube")`` authors + ``physics:approximation`` via ``UsdPhysics.MeshCollisionAPI``. No PhysX cooking schema is + applied because the base class declares no PhysX namespace.""" + from pxr import UsdGeom + + sim, _, _, _, _, _ = setup_simulation + stage = sim_utils.get_current_stage() + + UsdGeom.Mesh.Define(stage, "/World/mesh_base") + cfg = schemas.MeshCollisionBaseCfg(mesh_approximation_name="boundingCube") + schemas.define_mesh_collision_properties("/World/mesh_base", cfg) + + prim = stage.GetPrimAtPath("/World/mesh_base") + assert prim.GetAttribute("physics:approximation").Get() == "boundingCube" + applied = prim.GetAppliedSchemas() + # The standard UsdPhysics.MeshCollisionAPI is registered under + # ``PhysicsMeshCollisionAPI`` in the prim's applied-schema list. + assert any("MeshCollisionAPI" in s for s in applied), ( + f"a MeshCollisionAPI schema must be applied; got {list(applied)}" + ) + # no PhysX cooking schema applied for the base class + assert not any(s.startswith("Physx") and "Mesh" in s for s in applied), ( + f"no PhysX mesh schema should be applied for the base class; got {list(applied)}" + ) + + +@pytest.mark.isaacsim_ci +def test_physx_convex_hull_writes_tuning_attrs(setup_simulation): + """Setting tuning fields on ``PhysxConvexHullPropertiesCfg`` authors the + ``physxConvexHullCollision:*`` namespaced attributes AND applies + ``PhysxConvexHullCollisionAPI``.""" + from isaaclab_physx.sim.schemas import PhysxConvexHullPropertiesCfg + + from pxr import UsdGeom + + sim, _, _, _, _, _ = setup_simulation + stage = sim_utils.get_current_stage() + + UsdGeom.Mesh.Define(stage, "/World/mesh_ch") + cfg = PhysxConvexHullPropertiesCfg(hull_vertex_limit=64, min_thickness=0.001) + schemas.define_mesh_collision_properties("/World/mesh_ch", cfg) + + prim = stage.GetPrimAtPath("/World/mesh_ch") + assert prim.GetAttribute("physics:approximation").Get() == "convexHull" + assert prim.GetAttribute("physxConvexHullCollision:hullVertexLimit").Get() == 64 + assert prim.GetAttribute("physxConvexHullCollision:minThickness").Get() == pytest.approx(0.001) + applied = prim.GetAppliedSchemas() + assert "PhysxConvexHullCollisionAPI" in applied + + +@pytest.mark.isaacsim_ci +def test_physx_convex_hull_no_physx_schema_when_no_tuning_fields_set(setup_simulation): + """Regression: ``PhysxConvexHullPropertiesCfg()`` with all tuning fields None must NOT + apply ``PhysxConvexHullCollisionAPI``. The approximation token is still authored on the + standard ``UsdPhysics.MeshCollisionAPI``.""" + from isaaclab_physx.sim.schemas import PhysxConvexHullPropertiesCfg + + from pxr import UsdGeom + + sim, _, _, _, _, _ = setup_simulation + stage = sim_utils.get_current_stage() + + UsdGeom.Mesh.Define(stage, "/World/mesh_ch_default") + cfg = PhysxConvexHullPropertiesCfg() + schemas.define_mesh_collision_properties("/World/mesh_ch_default", cfg) + + prim = stage.GetPrimAtPath("/World/mesh_ch_default") + assert prim.GetAttribute("physics:approximation").Get() == "convexHull" + applied = prim.GetAppliedSchemas() + assert "PhysxConvexHullCollisionAPI" not in applied, ( + f"PhysxConvexHullCollisionAPI should not be applied without tuning fields; got {list(applied)}" + ) + + +@pytest.mark.isaacsim_ci +def test_bounding_cube_default_token(setup_simulation): + """``BoundingCubePropertiesCfg()`` defaults to the ``boundingCube`` token.""" + cfg = schemas.BoundingCubePropertiesCfg() + assert cfg.mesh_approximation_name == "boundingCube" + + +@pytest.mark.isaacsim_ci +@pytest.mark.parametrize( + "name", + [ + "MeshCollisionPropertiesCfg", + "ConvexHullPropertiesCfg", + "ConvexDecompositionPropertiesCfg", + "TriangleMeshPropertiesCfg", + "TriangleMeshSimplificationPropertiesCfg", + "SDFMeshPropertiesCfg", + ], +) +def test_mesh_collision_deprecation_aliases(setup_simulation, name): + """Each legacy mesh-collision class name emits exactly one DeprecationWarning on + instantiation and the warning message references the 5.0 removal target.""" + from isaaclab_physx.sim.schemas import schemas_cfg as physx_cfg + + cls = getattr(physx_cfg, name) + with warnings.catch_warnings(record=True) as caught: + warnings.simplefilter("always") + cls() + deprecations = [w for w in caught if issubclass(w.category, DeprecationWarning)] + assert len(deprecations) == 1, f"{name}: expected one DeprecationWarning, got {len(deprecations)}" + assert "5.0" in str(deprecations[0].message) + + +@pytest.mark.isaacsim_ci +def test_physx_fixed_tendon_relocation(setup_simulation): + """``PhysxFixedTendonPropertiesCfg`` is importable from + :mod:`isaaclab_physx.sim.schemas` and round-trips its fields.""" + from isaaclab_physx.sim.schemas import PhysxFixedTendonPropertiesCfg + + cfg = PhysxFixedTendonPropertiesCfg( + tendon_enabled=True, + stiffness=10.0, + damping=0.5, + limit_stiffness=1.0, + offset=0.1, + rest_length=0.2, + ) + assert cfg.tendon_enabled is True + assert cfg.stiffness == 10.0 + assert cfg.damping == 0.5 + assert cfg.limit_stiffness == 1.0 + assert cfg.offset == 0.1 + assert cfg.rest_length == 0.2 + + +@pytest.mark.isaacsim_ci +def test_fixed_tendon_deprecation_alias(setup_simulation): + """Instantiating the legacy ``FixedTendonPropertiesCfg`` (via the shim) emits exactly + one ``DeprecationWarning`` whose message references the 5.0 removal target.""" + cls = schemas.FixedTendonPropertiesCfg + with warnings.catch_warnings(record=True) as caught: + warnings.simplefilter("always") + cls() + deprecations = [w for w in caught if issubclass(w.category, DeprecationWarning)] + assert len(deprecations) == 1, f"expected one DeprecationWarning, got {len(deprecations)}" + assert "5.0" in str(deprecations[0].message) + + +@pytest.mark.isaacsim_ci +def test_physx_spatial_tendon_relocation(setup_simulation): + """``PhysxSpatialTendonPropertiesCfg`` is importable from + :mod:`isaaclab_physx.sim.schemas` and round-trips its fields.""" + from isaaclab_physx.sim.schemas import PhysxSpatialTendonPropertiesCfg + + cfg = PhysxSpatialTendonPropertiesCfg( + tendon_enabled=True, + stiffness=20.0, + damping=0.25, + limit_stiffness=2.0, + offset=0.05, + ) + assert cfg.tendon_enabled is True + assert cfg.stiffness == 20.0 + assert cfg.damping == 0.25 + assert cfg.limit_stiffness == 2.0 + assert cfg.offset == 0.05 + + +@pytest.mark.isaacsim_ci +def test_spatial_tendon_deprecation_alias(setup_simulation): + """Instantiating the legacy ``SpatialTendonPropertiesCfg`` (via the shim) emits exactly + one ``DeprecationWarning`` whose message references the 5.0 removal target.""" + cls = schemas.SpatialTendonPropertiesCfg + with warnings.catch_warnings(record=True) as caught: + warnings.simplefilter("always") + cls() + deprecations = [w for w in caught if issubclass(w.category, DeprecationWarning)] + assert len(deprecations) == 1, f"expected one DeprecationWarning, got {len(deprecations)}" + assert "5.0" in str(deprecations[0].message) + + +@pytest.mark.isaacsim_ci +def test_usd_api_physx_api_attrs_deprecated(setup_simulation): + """Reading ``cfg.usd_api`` and ``cfg.physx_api`` on the new mesh cfgs emits a + DeprecationWarning and returns the legacy-mapped string value.""" + from isaaclab_physx.sim.schemas import PhysxConvexHullPropertiesCfg + + cfg = PhysxConvexHullPropertiesCfg() + + with warnings.catch_warnings(record=True) as caught: + warnings.simplefilter("always") + usd_api_value = cfg.usd_api + assert any(issubclass(w.category, DeprecationWarning) for w in caught) + assert usd_api_value == "MeshCollisionAPI" + + with warnings.catch_warnings(record=True) as caught: + warnings.simplefilter("always") + physx_api_value = cfg.physx_api + assert any(issubclass(w.category, DeprecationWarning) for w in caught) + assert physx_api_value == "PhysxConvexHullCollisionAPI" + + @pytest.mark.isaacsim_ci def test_modify_properties_on_invalid_prim(setup_simulation): """Test modifying properties on a prim that does not exist.""" @@ -290,8 +898,8 @@ def _validate_articulation_properties_on_prim( root_prim = stage.GetPrimAtPath(prim_path) # check articulation properties are set correctly for attr_name, attr_value in arti_cfg.__dict__.items(): - # skip names we know are not present - if attr_name == "func": + # skip class metadata and names we know are not present + if attr_name.startswith("_") or attr_name == "func": continue # handle fixed root link if attr_name == "fix_root_link" and attr_value is not None: @@ -334,8 +942,12 @@ def _validate_rigid_body_properties_on_prim(prim_path: str, rigid_cfg, verbose: for link_prim in root_prim.GetChildren(): if UsdPhysics.RigidBodyAPI(link_prim): for attr_name, attr_value in rigid_cfg.__dict__.items(): - # skip names we know are not present - if attr_name in ["func", "rigid_body_enabled", "kinematic_enabled"]: + # skip class metadata and names we know are not present + if attr_name.startswith("_") or attr_name in [ + "func", + "rigid_body_enabled", + "kinematic_enabled", + ]: continue # convert attribute name in prim to cfg name prim_prop_name = f"physxRigidBody:{to_camel_case(attr_name, to='cC')}" @@ -363,8 +975,8 @@ def _validate_collision_properties_on_prim(prim_path: str, collision_cfg, verbos for mesh_prim in link_prim.GetChildren(): if UsdPhysics.CollisionAPI(mesh_prim): for attr_name, attr_value in collision_cfg.__dict__.items(): - # skip names we know are not present - if attr_name in ["func", "collision_enabled"]: + # skip names we know are not present and class-metadata keys + if attr_name.startswith("_") or attr_name in ["func", "collision_enabled"]: continue # convert attribute name in prim to cfg name prim_prop_name = f"physxCollision:{to_camel_case(attr_name, to='cC')}" @@ -391,8 +1003,8 @@ def _validate_mass_properties_on_prim(prim_path: str, mass_cfg, verbose: bool = for link_prim in root_prim.GetChildren(): if UsdPhysics.MassAPI(link_prim): for attr_name, attr_value in mass_cfg.__dict__.items(): - # skip names we know are not present - if attr_name in ["func"]: + # skip names we know are not present and class-metadata keys + if attr_name in ["func"] or attr_name.startswith("_"): continue # print(link_prim.GetProperties()) prim_prop_name = f"physics:{to_camel_case(attr_name, to='cC')}" @@ -423,8 +1035,8 @@ def _validate_joint_drive_properties_on_prim(prim_path: str, joint_cfg, verbose: assert joint_prim.HasAPI(UsdPhysics.DriveAPI) # iterate over the joint properties for attr_name, attr_value in joint_cfg.__dict__.items(): - # skip names we know are not present - if attr_name in ["func", "ensure_drives_exist"]: + # skip class metadata and names we know are not present on the USD prim + if attr_name.startswith("_") or attr_name in ["func", "ensure_drives_exist"]: continue # resolve the drive (linear or angular) drive_model = "linear" if joint_prim.IsA(UsdPhysics.PrismaticJoint) else "angular" @@ -437,10 +1049,8 @@ def _validate_joint_drive_properties_on_prim(prim_path: str, joint_cfg, verbose: continue # non-string attributes - if attr_name == "max_velocity": + if attr_name == "max_joint_velocity": prim_attr_name = "physxJoint:maxJointVelocity" - elif attr_name == "max_effort": - prim_attr_name = f"drive:{drive_model}:physics:maxForce" else: prim_attr_name = f"drive:{drive_model}:physics:{to_camel_case(attr_name, to='cC')}" @@ -450,7 +1060,7 @@ def _validate_joint_drive_properties_on_prim(prim_path: str, joint_cfg, verbose: # for angular drives, we expect user to set in radians # the values reported by USD are in degrees if drive_model == "angular": - if attr_name == "max_velocity": + if attr_name == "max_joint_velocity": # deg / s --> rad / s prim_attr_value = prim_attr_value * math.pi / 180.0 elif attr_name in ["stiffness", "damping"]: diff --git a/source/isaaclab/test/sim/test_schemas_shim.py b/source/isaaclab/test/sim/test_schemas_shim.py new file mode 100644 index 000000000000..11e6e5d1ba24 --- /dev/null +++ b/source/isaaclab/test/sim/test_schemas_shim.py @@ -0,0 +1,172 @@ +# Copyright (c) 2022-2026, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md). +# All rights reserved. +# +# SPDX-License-Identifier: BSD-3-Clause + +"""Tests that the forwarding shims resolve the PhysX cfgs that were relocated to +:mod:`isaaclab_physx`. Covers both the schema cfgs (in :mod:`isaaclab.sim.schemas`) and the +material cfgs (in :mod:`isaaclab.sim.spawners.materials`). + +These tests do not require Isaac Sim — only Python import semantics. +""" + +import warnings + +import pytest +from isaaclab_physx.sim.schemas import schemas_cfg as physx_cfg +from isaaclab_physx.sim.spawners.materials import physics_materials_cfg as physx_mat_cfg + +import isaaclab.sim as sim_utils +import isaaclab.sim.schemas as schemas +import isaaclab.sim.schemas.schemas_cfg as schemas_cfg_submodule +import isaaclab.sim.spawners.materials as materials +import isaaclab.sim.spawners.materials.physics_materials_cfg as materials_cfg_submodule + +FORWARDED_NAMES = [ + "RigidBodyPropertiesCfg", + "JointDrivePropertiesCfg", + "PhysxRigidBodyPropertiesCfg", + "PhysxJointDrivePropertiesCfg", + "CollisionPropertiesCfg", + "PhysxCollisionPropertiesCfg", + "PhysxDeformableCollisionPropertiesCfg", + "PhysXCollisionPropertiesCfg", + "ArticulationRootPropertiesCfg", + "PhysxArticulationRootPropertiesCfg", + "MeshCollisionPropertiesCfg", + "ConvexHullPropertiesCfg", + "ConvexDecompositionPropertiesCfg", + "TriangleMeshPropertiesCfg", + "TriangleMeshSimplificationPropertiesCfg", + "SDFMeshPropertiesCfg", + "PhysxConvexHullPropertiesCfg", + "PhysxConvexDecompositionPropertiesCfg", + "PhysxTriangleMeshPropertiesCfg", + "PhysxTriangleMeshSimplificationPropertiesCfg", + "PhysxSDFMeshPropertiesCfg", + "FixedTendonPropertiesCfg", + "SpatialTendonPropertiesCfg", + "PhysxFixedTendonPropertiesCfg", + "PhysxSpatialTendonPropertiesCfg", +] + +DEPRECATED_FORWARDED_NAMES = [ + "RigidBodyPropertiesCfg", + "JointDrivePropertiesCfg", + "CollisionPropertiesCfg", + "PhysXCollisionPropertiesCfg", + "ArticulationRootPropertiesCfg", + "MeshCollisionPropertiesCfg", + "ConvexHullPropertiesCfg", + "ConvexDecompositionPropertiesCfg", + "TriangleMeshPropertiesCfg", + "TriangleMeshSimplificationPropertiesCfg", + "SDFMeshPropertiesCfg", + "FixedTendonPropertiesCfg", + "SpatialTendonPropertiesCfg", +] + +FORWARDED_MATERIAL_NAMES = [ + "RigidBodyMaterialCfg", + "PhysxRigidBodyMaterialCfg", +] + + +@pytest.mark.parametrize("name", FORWARDED_NAMES) +def test_schemas_shim_resolves_to_physx_class(name): + """``isaaclab.sim.schemas.`` resolves to the same class object as the one in + ``isaaclab_physx.sim.schemas.schemas_cfg``.""" + assert getattr(schemas, name) is getattr(physx_cfg, name) + + +@pytest.mark.parametrize("name", FORWARDED_NAMES) +def test_sim_namespace_shim_resolves_to_physx_class(name): + """``isaaclab.sim.`` (i.e. ``sim_utils.``) resolves to the same class object.""" + assert getattr(sim_utils, name) is getattr(physx_cfg, name) + + +@pytest.mark.parametrize("name", FORWARDED_NAMES) +def test_schemas_cfg_submodule_shim_resolves_to_physx_class(name): + """``from isaaclab.sim.schemas.schemas_cfg import `` (direct submodule import path) + resolves to the same class object as the relocated definition.""" + assert getattr(schemas_cfg_submodule, name) is getattr(physx_cfg, name) + + +@pytest.mark.parametrize("name", FORWARDED_MATERIAL_NAMES) +def test_materials_shim_resolves_to_physx_class(name): + """``isaaclab.sim.spawners.materials.`` resolves to the same class object as the + one in ``isaaclab_physx.sim.spawners.materials.physics_materials_cfg``.""" + assert getattr(materials, name) is getattr(physx_mat_cfg, name) + + +@pytest.mark.parametrize("name", FORWARDED_MATERIAL_NAMES) +def test_materials_cfg_submodule_shim_resolves_to_physx_class(name): + """``from isaaclab.sim.spawners.materials.physics_materials_cfg import `` (direct + submodule import path) resolves to the same class object as the relocated definition.""" + assert getattr(materials_cfg_submodule, name) is getattr(physx_mat_cfg, name) + + +@pytest.mark.parametrize("name", FORWARDED_MATERIAL_NAMES) +def test_sim_namespace_material_shim_resolves_to_physx_class(name): + """``isaaclab.sim.`` (i.e. ``sim_utils.``) resolves to the relocated material class.""" + assert getattr(sim_utils, name) is getattr(physx_mat_cfg, name) + + +def test_deprecated_alias_emits_deprecation_warning(): + """Instantiating ``RigidBodyPropertiesCfg`` via the shim still emits ``DeprecationWarning``.""" + with warnings.catch_warnings(record=True) as caught: + warnings.simplefilter("always") + schemas.RigidBodyPropertiesCfg() + assert any(issubclass(w.category, DeprecationWarning) for w in caught) + + +@pytest.mark.parametrize("name", DEPRECATED_FORWARDED_NAMES) +def test_deprecated_aliases_emit_deprecation_warning(name): + """Instantiating each deprecated forwarded alias via the shim emits exactly one + ``DeprecationWarning``.""" + cls = getattr(schemas, name) + with warnings.catch_warnings(record=True) as caught: + warnings.simplefilter("always") + cls() + deprecations = [w for w in caught if issubclass(w.category, DeprecationWarning)] + assert len(deprecations) == 1, f"{name}: expected one DeprecationWarning, got {len(deprecations)}" + + +def test_deprecated_material_alias_emits_deprecation_warning(): + """Instantiating ``RigidBodyMaterialCfg`` via the shim still emits ``DeprecationWarning``.""" + with warnings.catch_warnings(record=True) as caught: + warnings.simplefilter("always") + materials.RigidBodyMaterialCfg() + deprecations = [w for w in caught if issubclass(w.category, DeprecationWarning)] + assert len(deprecations) == 1 + assert "5.0" in str(deprecations[0].message) + + +def test_new_class_does_not_emit_deprecation_warning(): + """Instantiating ``PhysxRigidBodyPropertiesCfg`` directly does NOT emit ``DeprecationWarning``.""" + with warnings.catch_warnings(record=True) as caught: + warnings.simplefilter("always") + schemas.PhysxRigidBodyPropertiesCfg() + assert not any(issubclass(w.category, DeprecationWarning) for w in caught) + + +def test_new_material_class_does_not_emit_deprecation_warning(): + """Instantiating ``PhysxRigidBodyMaterialCfg`` directly does NOT emit ``DeprecationWarning``.""" + with warnings.catch_warnings(record=True) as caught: + warnings.simplefilter("always") + materials.PhysxRigidBodyMaterialCfg() + assert not any(issubclass(w.category, DeprecationWarning) for w in caught) + + +def test_dir_lists_forwarded_names(): + """``dir(isaaclab.sim.schemas)`` includes the forwarded names so IDE autocomplete works.""" + listing = dir(schemas) + for name in FORWARDED_NAMES: + assert name in listing + + +def test_dir_lists_forwarded_material_names(): + """``dir(isaaclab.sim.spawners.materials)`` includes the forwarded names.""" + listing = dir(materials) + for name in FORWARDED_MATERIAL_NAMES: + assert name in listing diff --git a/source/isaaclab_newton/changelog.d/vidur-feature-usd-proprties-refactor.skip b/source/isaaclab_newton/changelog.d/vidur-feature-usd-proprties-refactor.skip new file mode 100644 index 000000000000..e69de29bb2d1 diff --git a/source/isaaclab_newton/test/assets/test_articulation.py b/source/isaaclab_newton/test/assets/test_articulation.py index a5eacf95045e..a392e7773468 100644 --- a/source/isaaclab_newton/test/assets/test_articulation.py +++ b/source/isaaclab_newton/test/assets/test_articulation.py @@ -196,7 +196,7 @@ def generate_articulation_cfg( # we set 80.0 default for max force because default in USD is 10e10 which makes testing annoying. spawn=sim_utils.UsdFileCfg( usd_path=f"{ISAAC_NUCLEUS_DIR}/Robots/IsaacSim/SimpleArticulation/revolute_articulation.usd", - joint_drive_props=sim_utils.JointDrivePropertiesCfg(max_effort=80.0, max_velocity=5.0), + joint_drive_props=sim_utils.JointDrivePropertiesCfg(max_force=80.0, max_joint_velocity=5.0), ), actuators={ "joint": ImplicitActuatorCfg( @@ -220,7 +220,7 @@ def generate_articulation_cfg( articulation_cfg = ArticulationCfg( spawn=sim_utils.UsdFileCfg( usd_path=f"{ISAAC_NUCLEUS_DIR}/Robots/IsaacSim/SimpleArticulation/revolute_articulation.usd", - joint_drive_props=sim_utils.JointDrivePropertiesCfg(max_effort=80.0, max_velocity=5.0), + joint_drive_props=sim_utils.JointDrivePropertiesCfg(max_force=80.0, max_joint_velocity=5.0), ), actuators={ "joint": IdealPDActuatorCfg( @@ -1510,7 +1510,7 @@ def test_setting_velocity_limit_implicit( # Case 3: velocity limit sim is not set but velocity limit is set # For backwards compatibility, we do not set velocity limit to simulation # Thus, both default to USD default value. - limit = articulation_cfg.spawn.joint_drive_props.max_velocity + limit = articulation_cfg.spawn.joint_drive_props.max_joint_velocity else: # Case 4: only velocity limit sim is set # In this case, the velocity limit is set to the USD value @@ -1572,7 +1572,7 @@ def test_setting_velocity_limit_explicit(sim, num_articulations, device, vel_lim if vel_limit_sim is not None: limit = vel_limit_sim else: - limit = articulation_cfg.spawn.joint_drive_props.max_velocity + limit = articulation_cfg.spawn.joint_drive_props.max_joint_velocity # check physx is set to expected value expected_vel_limit = torch.full_like(newton_vel_limit, limit) torch.testing.assert_close(newton_vel_limit, expected_vel_limit) @@ -1625,7 +1625,7 @@ def test_setting_effort_limit_implicit( # decide the limit based on what is set if effort_limit_sim is None and effort_limit is None: - limit = articulation_cfg.spawn.joint_drive_props.max_effort + limit = articulation_cfg.spawn.joint_drive_props.max_force elif effort_limit_sim is not None and effort_limit is None: limit = effort_limit_sim elif effort_limit_sim is None and effort_limit is not None: diff --git a/source/isaaclab_physx/changelog.d/vidur-rebalance-cfg-placement.minor.rst b/source/isaaclab_physx/changelog.d/vidur-rebalance-cfg-placement.minor.rst new file mode 100644 index 000000000000..4233c5d1c720 --- /dev/null +++ b/source/isaaclab_physx/changelog.d/vidur-rebalance-cfg-placement.minor.rst @@ -0,0 +1,77 @@ +Added +^^^^^ + +* Added :class:`PhysxRigidBodyMaterialCfg`, a subclass of + :class:`~isaaclab.sim.spawners.materials.RigidBodyMaterialBaseCfg` carrying the + ``PhysxMaterialAPI`` schema fields (``compliant_contact_stiffness``, + ``compliant_contact_damping``, ``friction_combine_mode``, ``restitution_combine_mode``). + Use this when authoring PhysX-specific material knobs; use the base class when only the + UsdPhysics-standard friction/restitution fields are needed. +* Added :class:`PhysxCollisionPropertiesCfg`, a subclass of + :class:`~isaaclab.sim.schemas.CollisionBaseCfg` carrying the PhysX-specific + ``torsional_patch_radius`` / ``min_torsional_patch_radius`` friction approximations. + These fields have no Newton equivalent. +* Added :class:`PhysxDeformableCollisionPropertiesCfg`, renaming the previous + ``PhysXCollisionPropertiesCfg`` (capital X) for clarity. Used internally by + :class:`DeformableBodyPropertiesCfg`. +* Added :class:`PhysxArticulationRootPropertiesCfg`, a subclass of + :class:`~isaaclab.sim.schemas.ArticulationRootBaseCfg` carrying the PhysX-specific + ``enabled_self_collisions``, ``solver_position_iteration_count``, + ``solver_velocity_iteration_count``, ``sleep_threshold``, ``stabilization_threshold``. +* Added :class:`PhysxConvexHullPropertiesCfg`, :class:`PhysxConvexDecompositionPropertiesCfg`, + :class:`PhysxTriangleMeshPropertiesCfg`, + :class:`PhysxTriangleMeshSimplificationPropertiesCfg`, and + :class:`PhysxSDFMeshPropertiesCfg` -- the PhysX-cooking-specific mesh collision + subclasses. Each declares its own PhysxSchema cooking API via class-level + ``_usd_applied_schema`` metadata and inherits ``mesh_approximation_name`` from + :class:`~isaaclab.sim.schemas.MeshCollisionBaseCfg`. +* Added :class:`PhysxFixedTendonPropertiesCfg` and :class:`PhysxSpatialTendonPropertiesCfg`, + the relocated PhysX-only tendon cfg classes. Same fields as the legacy core-side classes; + no field-level split. + +Changed +^^^^^^^ + +* Removed the ``max_velocity`` field and USD metadata + (``_usd_applied_schema``, ``_usd_namespace``, ``_usd_attr_name_map``) from + :class:`PhysxJointDrivePropertiesCfg`. The field moved to + :class:`~isaaclab.sim.schemas.JointDriveBaseCfg`; ``PhysxJointDrivePropertiesCfg`` + inherits it. Existing instantiations continue to work unchanged. +* Removed the ``disable_gravity`` field from :class:`PhysxRigidBodyPropertiesCfg`. + The field moved to :class:`~isaaclab.sim.schemas.RigidBodyBaseCfg`; + ``PhysxRigidBodyPropertiesCfg`` inherits it. Existing instantiations continue + to work unchanged. + +Deprecated +^^^^^^^^^^ + +* Deprecated :class:`RigidBodyMaterialCfg` in favor of + :class:`PhysxRigidBodyMaterialCfg` (PhysX-specific) or + :class:`~isaaclab.sim.spawners.materials.RigidBodyMaterialBaseCfg` (solver-common). + The legacy name remains as a concrete subclass of :class:`PhysxRigidBodyMaterialCfg` + that emits ``DeprecationWarning`` on instantiation. Scheduled for removal in 5.0. +* Deprecated :class:`CollisionPropertiesCfg` in favor of + :class:`PhysxCollisionPropertiesCfg` (PhysX-specific) or + :class:`~isaaclab.sim.schemas.CollisionBaseCfg` (solver-common). The legacy name remains + as a concrete subclass of :class:`PhysxCollisionPropertiesCfg` that emits + ``DeprecationWarning`` on instantiation. Scheduled for removal in 5.0. +* Deprecated :class:`PhysXCollisionPropertiesCfg` (capital X, deformable-body) in favor of + :class:`PhysxDeformableCollisionPropertiesCfg`. The capital-X name is preserved as a + deprecation alias (concrete subclass) and is scheduled for removal in 5.0. +* Deprecated :class:`ArticulationRootPropertiesCfg` in favor of + :class:`PhysxArticulationRootPropertiesCfg` (PhysX-specific) or + :class:`~isaaclab.sim.schemas.ArticulationRootBaseCfg` (solver-common). The legacy name + remains as a concrete subclass of :class:`PhysxArticulationRootPropertiesCfg` that emits + ``DeprecationWarning`` on instantiation. Scheduled for removal in 5.0. +* Deprecated :class:`MeshCollisionPropertiesCfg`, :class:`ConvexHullPropertiesCfg`, + :class:`ConvexDecompositionPropertiesCfg`, :class:`TriangleMeshPropertiesCfg`, + :class:`TriangleMeshSimplificationPropertiesCfg`, and :class:`SDFMeshPropertiesCfg` in + favor of :class:`~isaaclab.sim.schemas.MeshCollisionBaseCfg` or the new ``Physx*`` + subclasses. Legacy names remain as concrete subclasses that emit ``DeprecationWarning`` + on instantiation. Scheduled for removal in 5.0. +* Deprecated :class:`FixedTendonPropertiesCfg` in favor of + :class:`PhysxFixedTendonPropertiesCfg`. Legacy name remains as a concrete subclass that + emits ``DeprecationWarning`` on instantiation. Scheduled for removal in 5.0. +* Deprecated :class:`SpatialTendonPropertiesCfg` in favor of + :class:`PhysxSpatialTendonPropertiesCfg`. Legacy name remains as a concrete subclass + that emits ``DeprecationWarning`` on instantiation. Scheduled for removal in 5.0. diff --git a/source/isaaclab_physx/isaaclab_physx/sim/__init__.pyi b/source/isaaclab_physx/isaaclab_physx/sim/__init__.pyi index abc8d0087afd..9a522d96ff8f 100644 --- a/source/isaaclab_physx/isaaclab_physx/sim/__init__.pyi +++ b/source/isaaclab_physx/isaaclab_physx/sim/__init__.pyi @@ -7,6 +7,10 @@ __all__ = [ "define_deformable_body_properties", "modify_deformable_body_properties", "DeformableBodyPropertiesCfg", + "JointDrivePropertiesCfg", + "PhysxJointDrivePropertiesCfg", + "PhysxRigidBodyPropertiesCfg", + "RigidBodyPropertiesCfg", "DeformableObjectSpawnerCfg", "spawn_deformable_body_material", "DeformableBodyMaterialCfg", @@ -17,7 +21,11 @@ __all__ = [ from .schemas import ( define_deformable_body_properties, modify_deformable_body_properties, - DeformableBodyPropertiesCfg + DeformableBodyPropertiesCfg, + JointDrivePropertiesCfg, + PhysxJointDrivePropertiesCfg, + PhysxRigidBodyPropertiesCfg, + RigidBodyPropertiesCfg, ) from .spawners import ( DeformableObjectSpawnerCfg, diff --git a/source/isaaclab_physx/isaaclab_physx/sim/schemas/__init__.pyi b/source/isaaclab_physx/isaaclab_physx/sim/schemas/__init__.pyi index bb0e51a19b4b..6d2a05bf803c 100644 --- a/source/isaaclab_physx/isaaclab_physx/sim/schemas/__init__.pyi +++ b/source/isaaclab_physx/isaaclab_physx/sim/schemas/__init__.pyi @@ -6,11 +6,63 @@ __all__ = [ "define_deformable_body_properties", "modify_deformable_body_properties", + "ArticulationRootPropertiesCfg", + "CollisionPropertiesCfg", + "ConvexDecompositionPropertiesCfg", + "ConvexHullPropertiesCfg", "DeformableBodyPropertiesCfg", + "FixedTendonPropertiesCfg", + "JointDrivePropertiesCfg", + "MeshCollisionPropertiesCfg", + "PhysxArticulationRootPropertiesCfg", + "PhysxCollisionPropertiesCfg", + "PhysXCollisionPropertiesCfg", + "PhysxConvexDecompositionPropertiesCfg", + "PhysxConvexHullPropertiesCfg", + "PhysxDeformableCollisionPropertiesCfg", + "PhysxFixedTendonPropertiesCfg", + "PhysxJointDrivePropertiesCfg", + "PhysxRigidBodyPropertiesCfg", + "PhysxSDFMeshPropertiesCfg", + "PhysxSpatialTendonPropertiesCfg", + "PhysxTriangleMeshPropertiesCfg", + "PhysxTriangleMeshSimplificationPropertiesCfg", + "RigidBodyPropertiesCfg", + "SDFMeshPropertiesCfg", + "SpatialTendonPropertiesCfg", + "TriangleMeshPropertiesCfg", + "TriangleMeshSimplificationPropertiesCfg", ] from .schemas import ( define_deformable_body_properties, modify_deformable_body_properties, ) -from .schemas_cfg import DeformableBodyPropertiesCfg +from .schemas_cfg import ( + ArticulationRootPropertiesCfg, + CollisionPropertiesCfg, + ConvexDecompositionPropertiesCfg, + ConvexHullPropertiesCfg, + DeformableBodyPropertiesCfg, + FixedTendonPropertiesCfg, + JointDrivePropertiesCfg, + MeshCollisionPropertiesCfg, + PhysxArticulationRootPropertiesCfg, + PhysxCollisionPropertiesCfg, + PhysXCollisionPropertiesCfg, + PhysxConvexDecompositionPropertiesCfg, + PhysxConvexHullPropertiesCfg, + PhysxDeformableCollisionPropertiesCfg, + PhysxFixedTendonPropertiesCfg, + PhysxJointDrivePropertiesCfg, + PhysxRigidBodyPropertiesCfg, + PhysxSDFMeshPropertiesCfg, + PhysxSpatialTendonPropertiesCfg, + PhysxTriangleMeshPropertiesCfg, + PhysxTriangleMeshSimplificationPropertiesCfg, + RigidBodyPropertiesCfg, + SDFMeshPropertiesCfg, + SpatialTendonPropertiesCfg, + TriangleMeshPropertiesCfg, + TriangleMeshSimplificationPropertiesCfg, +) diff --git a/source/isaaclab_physx/isaaclab_physx/sim/schemas/schemas_cfg.py b/source/isaaclab_physx/isaaclab_physx/sim/schemas/schemas_cfg.py index 6579fee6356a..e6bdea28d24e 100644 --- a/source/isaaclab_physx/isaaclab_physx/sim/schemas/schemas_cfg.py +++ b/source/isaaclab_physx/isaaclab_physx/sim/schemas/schemas_cfg.py @@ -6,7 +6,16 @@ from __future__ import annotations import dataclasses - +import warnings +from typing import ClassVar + +from isaaclab.sim.schemas.schemas_cfg import ( + ArticulationRootBaseCfg, + CollisionBaseCfg, + JointDriveBaseCfg, + MeshCollisionBaseCfg, + RigidBodyBaseCfg, +) from isaaclab.utils import configclass @@ -110,12 +119,19 @@ class PhysXDeformableBodyPropertiesCfg: @configclass -class PhysXCollisionPropertiesCfg: +class PhysxDeformableCollisionPropertiesCfg: """PhysX-specific collision properties for a deformable body. These properties are set with the prefix ``physxCollision:``. See the PhysX documentation for more information on the available properties. + + .. note:: + This class is distinct from + :class:`~isaaclab_physx.sim.schemas.PhysxCollisionPropertiesCfg` (lowercase x), + which is the rigid-body collision cfg layered on + :class:`~isaaclab.sim.schemas.CollisionBaseCfg`. This class is used internally + as a base of :class:`DeformableBodyPropertiesCfg`. """ contact_offset: float | None = None @@ -135,9 +151,30 @@ class PhysXCollisionPropertiesCfg: """ +@configclass +class PhysXCollisionPropertiesCfg(PhysxDeformableCollisionPropertiesCfg): + """Deprecated: use :class:`PhysxDeformableCollisionPropertiesCfg`. + + .. deprecated:: 4.6.23 + ``PhysXCollisionPropertiesCfg`` (capital X) was renamed to + :class:`PhysxDeformableCollisionPropertiesCfg` to clear the namespace for the + new rigid-body :class:`PhysxCollisionPropertiesCfg` (lowercase x). The capital-X + name is preserved as a deprecation alias and is scheduled for removal in 5.0. + """ + + def __post_init__(self): + warnings.warn( + "'PhysXCollisionPropertiesCfg' (capital X) is deprecated and will be removed in 5.0." + " Use 'isaaclab_physx.sim.schemas.PhysxDeformableCollisionPropertiesCfg' instead.", + DeprecationWarning, + stacklevel=2, + ) + super().__post_init__() + + @configclass class DeformableBodyPropertiesCfg( - OmniPhysicsPropertiesCfg, PhysXDeformableBodyPropertiesCfg, PhysXCollisionPropertiesCfg + OmniPhysicsPropertiesCfg, PhysXDeformableBodyPropertiesCfg, PhysxDeformableCollisionPropertiesCfg ): """Properties to apply to a deformable body. @@ -158,6 +195,716 @@ class DeformableBodyPropertiesCfg( _property_prefix: dict[str, list[str]] = { "omniphysics": [field.name for field in dataclasses.fields(OmniPhysicsPropertiesCfg)], "physxDeformableBody": [field.name for field in dataclasses.fields(PhysXDeformableBodyPropertiesCfg)], - "physxCollision": [field.name for field in dataclasses.fields(PhysXCollisionPropertiesCfg)], + "physxCollision": [field.name for field in dataclasses.fields(PhysxDeformableCollisionPropertiesCfg)], } """Mapping between the property prefixes and the properties that fall under each prefix.""" + + +@configclass +class PhysxRigidBodyPropertiesCfg(RigidBodyBaseCfg): + """PhysX-specific rigid body properties. + + Extends :class:`~isaaclab.sim.schemas.RigidBodyBaseCfg` with properties from the `PhysxRigidBodyAPI`_ schema. + + See :meth:`~isaaclab.sim.schemas.modify_rigid_body_properties` for more information. + + .. note:: + If the values are None, they are not modified. This is useful when you want to set only a subset of + the properties and leave the rest as-is. + + .. _PhysxRigidBodyAPI: https://docs.omniverse.nvidia.com/kit/docs/omni_usd_schema_physics/104.2/class_physx_schema_physx_rigid_body_a_p_i.html + """ + + # PhysX-specific fields below all live under the ``PhysxRigidBodyAPI`` schema's + # ``physxRigidBody:*`` namespace. The ``disable_gravity`` field on the base remains + # routed via ``_usd_field_exceptions`` (inherited). + _usd_applied_schema: ClassVar[str | None] = "PhysxRigidBodyAPI" + _usd_namespace: ClassVar[str | None] = "physxRigidBody" + + linear_damping: float | None = None + """Linear damping for the body.""" + + angular_damping: float | None = None + """Angular damping for the body.""" + + max_linear_velocity: float | None = None + """Maximum linear velocity for rigid bodies (in m/s).""" + + max_angular_velocity: float | None = None + """Maximum angular velocity for rigid bodies (in deg/s).""" + + max_depenetration_velocity: float | None = None + """Maximum depenetration velocity permitted to be introduced by the solver (in m/s).""" + + max_contact_impulse: float | None = None + """The limit on the impulse that may be applied at a contact.""" + + enable_gyroscopic_forces: bool | None = None + """Enables computation of gyroscopic forces on the rigid body.""" + + retain_accelerations: bool | None = None + """Carries over forces/accelerations over sub-steps.""" + + solver_position_iteration_count: int | None = None + """Solver position iteration counts for the body.""" + + solver_velocity_iteration_count: int | None = None + """Solver velocity iteration counts for the body.""" + + sleep_threshold: float | None = None + """Mass-normalized kinetic energy threshold below which an actor may go to sleep.""" + + stabilization_threshold: float | None = None + """The mass-normalized kinetic energy threshold below which an actor may participate in stabilization.""" + + +@configclass +class RigidBodyPropertiesCfg(PhysxRigidBodyPropertiesCfg): + """Deprecated: use :class:`PhysxRigidBodyPropertiesCfg` or :class:`~isaaclab.sim.schemas.RigidBodyBaseCfg`. + + .. deprecated:: 4.6.22 + ``RigidBodyPropertiesCfg`` has been split into + :class:`~isaaclab.sim.schemas.RigidBodyBaseCfg` (solver-common) and + :class:`PhysxRigidBodyPropertiesCfg` (PhysX-specific) and relocated to + :mod:`isaaclab_physx.sim.schemas`. This alias preserves backwards compatibility and is + scheduled for removal in 5.0. + """ + + def __post_init__(self): + warnings.warn( + "'RigidBodyPropertiesCfg' is deprecated and will be removed in 5.0. Use" + " 'isaaclab_physx.sim.schemas.PhysxRigidBodyPropertiesCfg' for PhysX properties, or" + " 'isaaclab.sim.schemas.RigidBodyBaseCfg' for solver-common properties only.", + DeprecationWarning, + stacklevel=2, + ) + super().__post_init__() + + +@configclass +class PhysxJointDrivePropertiesCfg(JointDriveBaseCfg): + """PhysX-specific joint drive properties. + + Currently empty after the consumption-gated split moved :attr:`max_joint_velocity` + to :class:`~isaaclab.sim.schemas.JointDriveBaseCfg`. This class is retained + as the deprecation-alias target for the legacy :class:`JointDrivePropertiesCfg` + name and as the home for any future PhysX-only joint-drive fields (e.g. + PhysX-specific drive force-limit modes). + + Inherits all fields and USD metadata from + :class:`~isaaclab.sim.schemas.JointDriveBaseCfg`. + + See :meth:`~isaaclab.sim.schemas.modify_joint_drive_properties` for more information. + + .. _PhysxJointAPI: https://docs.omniverse.nvidia.com/kit/docs/omni_usd_schema_physics/104.2/class_physx_schema_physx_joint_a_p_i.html + """ + + # ``max_joint_velocity`` on the base remains routed via ``_usd_field_exceptions`` + # (inherited). Future PhysX-only joint-drive fields would be written under this + # namespace. + _usd_applied_schema: ClassVar[str | None] = "PhysxJointAPI" + _usd_namespace: ClassVar[str | None] = "physxJoint" + + +@configclass +class JointDrivePropertiesCfg(PhysxJointDrivePropertiesCfg): + """Deprecated: use :class:`PhysxJointDrivePropertiesCfg` or :class:`~isaaclab.sim.schemas.JointDriveBaseCfg`. + + .. deprecated:: 4.6.22 + ``JointDrivePropertiesCfg`` has been split into + :class:`~isaaclab.sim.schemas.JointDriveBaseCfg` (solver-common) and + :class:`PhysxJointDrivePropertiesCfg` (PhysX-specific) and relocated to + :mod:`isaaclab_physx.sim.schemas`. This alias preserves backwards compatibility and is + scheduled for removal in 5.0. + """ + + def __post_init__(self): + warnings.warn( + "'JointDrivePropertiesCfg' is deprecated and will be removed in 5.0. Use" + " 'isaaclab_physx.sim.schemas.PhysxJointDrivePropertiesCfg' for PhysX properties, or" + " 'isaaclab.sim.schemas.JointDriveBaseCfg' for solver-common properties only.", + DeprecationWarning, + stacklevel=2, + ) + super().__post_init__() + + +@configclass +class PhysxCollisionPropertiesCfg(CollisionBaseCfg): + """PhysX-specific rigid-body collision properties. + + Extends :class:`~isaaclab.sim.schemas.CollisionBaseCfg` with the PhysX-only torsional + patch friction approximations (:attr:`torsional_patch_radius`, + :attr:`min_torsional_patch_radius`). These fields have no Newton equivalent and are + consumed only by the PhysX solver. + + See :meth:`~isaaclab.sim.schemas.modify_collision_properties` for more information. + + .. note:: + If the values are None, they are not modified. This is useful when you want to set only a subset of + the properties and leave the rest as-is. + + .. _PhysxCollisionAPI: https://docs.omniverse.nvidia.com/kit/docs/omni_usd_schema_physics/104.2/class_physx_schema_physx_collision_a_p_i.html + """ + + # PhysX torsional-friction fields below live under the ``PhysxCollisionAPI`` schema's + # ``physxCollision:*`` namespace. Base ``contact_offset`` / ``rest_offset`` remain + # routed via ``_usd_field_exceptions`` (inherited). + _usd_applied_schema: ClassVar[str | None] = "PhysxCollisionAPI" + _usd_namespace: ClassVar[str | None] = "physxCollision" + + torsional_patch_radius: float | None = None + """Radius of the contact patch for applying torsional friction [m]. + + It is used to approximate rotational friction introduced by the compression of contacting surfaces. + If the radius is zero, no torsional friction is applied. + """ + + min_torsional_patch_radius: float | None = None + """Minimum radius of the contact patch for applying torsional friction [m].""" + + +@configclass +class PhysxArticulationRootPropertiesCfg(ArticulationRootBaseCfg): + """PhysX-specific articulation-root properties. + + Extends :class:`~isaaclab.sim.schemas.ArticulationRootBaseCfg` with the + `PhysxArticulationAPI`_ schema fields that are PhysX-only or dual-namespace + (Rule 2 — the conceptual quantity also has a ``newton:*`` attribute, and a + future ``NewtonArticulationRootPropertiesCfg`` would carry it on the Newton + side). Use this class when authoring PhysX-specific articulation knobs; + use :class:`~isaaclab.sim.schemas.ArticulationRootBaseCfg` when only the + solver-common ``fix_root_link`` / ``articulation_enabled`` fields are needed. + + See :meth:`~isaaclab.sim.schemas.modify_articulation_root_properties` for more information. + + .. note:: + If the values are None, they are not modified. This is useful when you want to set only a subset of + the properties and leave the rest as-is. + + .. _PhysxArticulationAPI: https://docs.omniverse.nvidia.com/kit/docs/omni_usd_schema_physics/104.2/class_physx_schema_physx_articulation_a_p_i.html + """ + + # PhysX articulation-root fields below live under the ``PhysxArticulationAPI`` schema's + # ``physxArticulation:*`` namespace. Base ``articulation_enabled`` remains routed via + # ``_usd_field_exceptions`` (inherited). + _usd_applied_schema: ClassVar[str | None] = "PhysxArticulationAPI" + _usd_namespace: ClassVar[str | None] = "physxArticulation" + + enabled_self_collisions: bool | None = None + """Whether self-collisions between bodies in the same articulation are enabled. + + The conceptual quantity exists in two USD namespaces simultaneously: + + * ``physxArticulation:enabledSelfCollisions`` (PhysX, ``PhysxArticulationAPI``) + * ``newton:selfCollisionEnabled`` (Newton-native, on a future ``NewtonArticulationRootAPI``) + + Newton's resolver checks the native ``newton:*`` attribute first and falls back + to the PhysX namespace. Both backends honor the field end-to-end. + + Because the conceptual quantity has a dedicated USD attribute in each backend's + namespace, this field is placed on the **PhysX subclass** (one cfg per namespace). + A future ``NewtonArticulationRootPropertiesCfg`` will carry the same field over the + ``newton:*`` namespace. + """ + + solver_position_iteration_count: int | None = None + """Solver position iteration counts for the body.""" + + solver_velocity_iteration_count: int | None = None + """Solver velocity iteration counts for the body.""" + + sleep_threshold: float | None = None + """Mass-normalized kinetic energy threshold below which an actor may go to sleep.""" + + stabilization_threshold: float | None = None + """The mass-normalized kinetic energy threshold below which an articulation may participate in stabilization.""" + + +@configclass +class ArticulationRootPropertiesCfg(PhysxArticulationRootPropertiesCfg): + """Deprecated: use :class:`PhysxArticulationRootPropertiesCfg` or the solver-common base class. + + Use :class:`PhysxArticulationRootPropertiesCfg` for PhysX-specific properties or + :class:`~isaaclab.sim.schemas.ArticulationRootBaseCfg` for solver-common properties only. + + .. deprecated:: 4.6.24 + ``ArticulationRootPropertiesCfg`` has been split into + :class:`~isaaclab.sim.schemas.ArticulationRootBaseCfg` (solver-common + ``fix_root_link`` and the PhysX-namespaced but IL-Newton-consumed + ``articulation_enabled``) and + :class:`PhysxArticulationRootPropertiesCfg` (PhysX-specific + self-collisions, TGS solver iter / sleep / stabilization thresholds) + and relocated to :mod:`isaaclab_physx.sim.schemas`. This alias preserves + backwards compatibility and is scheduled for removal in 5.0. + """ + + def __post_init__(self): + warnings.warn( + "'ArticulationRootPropertiesCfg' is deprecated and will be removed in 5.0. Use" + " 'isaaclab_physx.sim.schemas.PhysxArticulationRootPropertiesCfg' for PhysX properties, or" + " 'isaaclab.sim.schemas.ArticulationRootBaseCfg' for solver-common properties only.", + DeprecationWarning, + stacklevel=2, + ) + super().__post_init__() + + +@configclass +class CollisionPropertiesCfg(PhysxCollisionPropertiesCfg): + """Deprecated: use :class:`PhysxCollisionPropertiesCfg` or :class:`~isaaclab.sim.schemas.CollisionBaseCfg`. + + .. deprecated:: 4.6.23 + ``CollisionPropertiesCfg`` has been split into + :class:`~isaaclab.sim.schemas.CollisionBaseCfg` (solver-common) and + :class:`PhysxCollisionPropertiesCfg` (PhysX-specific) and relocated to + :mod:`isaaclab_physx.sim.schemas`. This alias preserves backwards compatibility and is + scheduled for removal in 5.0. + """ + + def __post_init__(self): + warnings.warn( + "'CollisionPropertiesCfg' is deprecated and will be removed in 5.0. Use" + " 'isaaclab_physx.sim.schemas.PhysxCollisionPropertiesCfg' for PhysX properties, or" + " 'isaaclab.sim.schemas.CollisionBaseCfg' for solver-common properties only.", + DeprecationWarning, + stacklevel=2, + ) + super().__post_init__() + + +@configclass +class PhysxConvexHullPropertiesCfg(MeshCollisionBaseCfg): + """PhysX convex-hull cooking properties for a mesh collider. + + Extends :class:`~isaaclab.sim.schemas.MeshCollisionBaseCfg` with the + ``PhysxConvexHullCollisionAPI`` schema's tuning fields. The ``convexHull`` token is + written to ``physics:approximation``; the cooking schema is applied only when at + least one tuning field is set (consistent with the other consumption-gated writers). + + See :meth:`~isaaclab.sim.schemas.modify_mesh_collision_properties` for more information. + + Original PhysX Documentation: + https://docs.omniverse.nvidia.com/kit/docs/omni_usd_schema_physics/latest/class_physx_schema_physx_convex_hull_collision_a_p_i.html + """ + + _usd_applied_schema: ClassVar[str | None] = "PhysxConvexHullCollisionAPI" + _usd_namespace: ClassVar[str | None] = "physxConvexHullCollision" + + mesh_approximation_name: str = "convexHull" + """Name of mesh collision approximation method. Default: "convexHull".""" + + hull_vertex_limit: int | None = None + """Convex hull vertex limit used for convex hull cooking. + + Defaults to 64. + """ + min_thickness: float | None = None + """Convex hull min thickness. + + Range: [0, inf). Units are distance. Default value is 0.001. + """ + + +@configclass +class PhysxConvexDecompositionPropertiesCfg(MeshCollisionBaseCfg): + """PhysX convex-decomposition cooking properties for a mesh collider. + + See :meth:`~isaaclab.sim.schemas.modify_mesh_collision_properties` for more information. + + Original PhysX Documentation: + https://docs.omniverse.nvidia.com/kit/docs/omni_usd_schema_physics/latest/class_physx_schema_physx_convex_decomposition_collision_a_p_i.html + """ + + _usd_applied_schema: ClassVar[str | None] = "PhysxConvexDecompositionCollisionAPI" + _usd_namespace: ClassVar[str | None] = "physxConvexDecompositionCollision" + + mesh_approximation_name: str = "convexDecomposition" + """Name of mesh collision approximation method. Default: "convexDecomposition".""" + + hull_vertex_limit: int | None = None + """Convex hull vertex limit used for convex hull cooking. + + Defaults to 64. + """ + max_convex_hulls: int | None = None + """Maximum of convex hulls created during convex decomposition. + Default value is 32. + """ + min_thickness: float | None = None + """Convex hull min thickness. + + Range: [0, inf). Units are distance. Default value is 0.001. + """ + voxel_resolution: int | None = None + """Voxel resolution used for convex decomposition. + + Defaults to 500,000 voxels. + """ + error_percentage: float | None = None + """Convex decomposition error percentage parameter. + + Defaults to 10 percent. Units are percent. + """ + shrink_wrap: bool | None = None + """Attempts to adjust the convex hull points so that they are projected onto the surface of the original graphics + mesh. + + Defaults to False. + """ + + +@configclass +class PhysxTriangleMeshPropertiesCfg(MeshCollisionBaseCfg): + """PhysX triangle-mesh cooking properties for a mesh collider. + + Triangle-mesh colliders are PhysX-only. + + See :meth:`~isaaclab.sim.schemas.modify_mesh_collision_properties` for more information. + + Original PhysX Documentation: + https://docs.omniverse.nvidia.com/kit/docs/omni_usd_schema_physics/latest/class_physx_schema_physx_triangle_mesh_collision_a_p_i.html + """ + + _usd_applied_schema: ClassVar[str | None] = "PhysxTriangleMeshCollisionAPI" + _usd_namespace: ClassVar[str | None] = "physxTriangleMeshCollision" + + mesh_approximation_name: str = "none" + """Name of mesh collision approximation method. Default: "none" (uses triangle mesh).""" + + weld_tolerance: float | None = None + """Mesh weld tolerance, controls the distance at which vertices are welded. + + Default -inf will autocompute the welding tolerance based on the mesh size. Zero value will disable welding. + Range: [0, inf) Units: distance + """ + + +@configclass +class PhysxTriangleMeshSimplificationPropertiesCfg(MeshCollisionBaseCfg): + """PhysX triangle-mesh-simplification cooking properties for a mesh collider. + + See :meth:`~isaaclab.sim.schemas.modify_mesh_collision_properties` for more information. + + Original PhysX Documentation: + https://docs.omniverse.nvidia.com/kit/docs/omni_usd_schema_physics/latest/class_physx_schema_physx_triangle_mesh_simplification_collision_a_p_i.html + """ + + _usd_applied_schema: ClassVar[str | None] = "PhysxTriangleMeshSimplificationCollisionAPI" + _usd_namespace: ClassVar[str | None] = "physxTriangleMeshSimplificationCollision" + + mesh_approximation_name: str = "meshSimplification" + """Name of mesh collision approximation method. Default: "meshSimplification".""" + + simplification_metric: float | None = None + """Mesh simplification accuracy. + + Defaults to 0.55. + """ + weld_tolerance: float | None = None + """Mesh weld tolerance, controls the distance at which vertices are welded. + + Default -inf will autocompute the welding tolerance based on the mesh size. Zero value will disable welding. + Range: [0, inf) Units: distance + """ + + +@configclass +class PhysxSDFMeshPropertiesCfg(MeshCollisionBaseCfg): + """PhysX SDF-mesh cooking properties for a mesh collider. + + SDF-mesh colliders are PhysX-only. + + See :meth:`~isaaclab.sim.schemas.modify_mesh_collision_properties` for more information. + + Original PhysX documentation: + https://docs.omniverse.nvidia.com/kit/docs/omni_usd_schema_physics/latest/class_physx_schema_physx_s_d_f_mesh_collision_a_p_i.html + + More details and steps for optimizing SDF results can be found here: + https://nvidia-omniverse.github.io/PhysX/physx/5.2.1/docs/RigidBodyCollision.html#dynamic-triangle-meshes-with-sdfs + """ + + _usd_applied_schema: ClassVar[str | None] = "PhysxSDFMeshCollisionAPI" + _usd_namespace: ClassVar[str | None] = "physxSDFMeshCollision" + + mesh_approximation_name: str = "sdf" + """Name of mesh collision approximation method. Default: "sdf".""" + + sdf_margin: float | None = None + """Margin to increase the size of the SDF relative to the bounding box diagonal length of the mesh. + + A sdf margin value of 0.01 means the sdf boundary will be enlarged in any direction by 1% of the mesh's bounding + box diagonal length. Representing the margin relative to the bounding box diagonal length ensures that it is scale + independent. Margins allow for precise distance queries in a region slightly outside of the mesh's bounding box. + + Default value is 0.01. + Range: [0, inf) Units: dimensionless + """ + sdf_narrow_band_thickness: float | None = None + """Size of the narrow band around the mesh surface where high resolution SDF samples are available. + + Outside of the narrow band, only low resolution samples are stored. Representing the narrow band thickness as a + fraction of the mesh's bounding box diagonal length ensures that it is scale independent. A value of 0.01 is + usually large enough. The smaller the narrow band thickness, the smaller the memory consumption of the sparse SDF. + + Default value is 0.01. + Range: [0, 1] Units: dimensionless + """ + sdf_resolution: int | None = None + """The spacing of the uniformly sampled SDF is equal to the largest AABB extent of the mesh, + divided by the resolution. + + Choose the lowest possible resolution that provides acceptable performance; very high resolution results in large + memory consumption, and slower cooking and simulation performance. + + Default value is 256. + Range: (1, inf) + """ + sdf_subgrid_resolution: int | None = None + """A positive subgrid resolution enables sparsity on signed-distance-fields (SDF) while a value of 0 leads to the + usage of a dense SDF. + + A value in the range of 4 to 8 is a reasonable compromise between block size and the overhead introduced by block + addressing. The smaller a block, the more memory is spent on the address table. The bigger a block, the less + precisely the sparse SDF can adapt to the mesh's surface. In most cases sparsity reduces the memory consumption of + a SDF significantly. + + Default value is 6. + Range: [0, inf) + """ + + +@configclass +class MeshCollisionPropertiesCfg(MeshCollisionBaseCfg): + """Deprecated: use :class:`~isaaclab.sim.schemas.MeshCollisionBaseCfg`. + + .. deprecated:: 4.6.25 + ``MeshCollisionPropertiesCfg`` was the flat (non-leaf) base of the legacy + mesh-collision cfg family. It has been renamed to + :class:`~isaaclab.sim.schemas.MeshCollisionBaseCfg` to match the rest of the + consumption-gated split. This alias preserves backwards compatibility and is + scheduled for removal in 5.0. + """ + + def __post_init__(self): + warnings.warn( + "'MeshCollisionPropertiesCfg' is deprecated and will be removed in 5.0. Use" + " 'isaaclab.sim.schemas.MeshCollisionBaseCfg' instead.", + DeprecationWarning, + stacklevel=2, + ) + super().__post_init__() + + +@configclass +class ConvexHullPropertiesCfg(PhysxConvexHullPropertiesCfg): + """Deprecated: use :class:`PhysxConvexHullPropertiesCfg`. + + .. deprecated:: 4.6.25 + Renamed and relocated. This alias preserves backwards compatibility and is + scheduled for removal in 5.0. + """ + + def __post_init__(self): + warnings.warn( + "'ConvexHullPropertiesCfg' is deprecated and will be removed in 5.0. Use" + " 'isaaclab_physx.sim.schemas.PhysxConvexHullPropertiesCfg' instead.", + DeprecationWarning, + stacklevel=2, + ) + super().__post_init__() + + +@configclass +class ConvexDecompositionPropertiesCfg(PhysxConvexDecompositionPropertiesCfg): + """Deprecated: use :class:`PhysxConvexDecompositionPropertiesCfg`. + + .. deprecated:: 4.6.25 + Renamed and relocated. This alias preserves backwards compatibility and is + scheduled for removal in 5.0. + """ + + def __post_init__(self): + warnings.warn( + "'ConvexDecompositionPropertiesCfg' is deprecated and will be removed in 5.0. Use" + " 'isaaclab_physx.sim.schemas.PhysxConvexDecompositionPropertiesCfg' instead.", + DeprecationWarning, + stacklevel=2, + ) + super().__post_init__() + + +@configclass +class TriangleMeshPropertiesCfg(PhysxTriangleMeshPropertiesCfg): + """Deprecated: use :class:`PhysxTriangleMeshPropertiesCfg`. + + .. deprecated:: 4.6.25 + Renamed and relocated. This alias preserves backwards compatibility and is + scheduled for removal in 5.0. + """ + + def __post_init__(self): + warnings.warn( + "'TriangleMeshPropertiesCfg' is deprecated and will be removed in 5.0. Use" + " 'isaaclab_physx.sim.schemas.PhysxTriangleMeshPropertiesCfg' instead.", + DeprecationWarning, + stacklevel=2, + ) + super().__post_init__() + + +@configclass +class TriangleMeshSimplificationPropertiesCfg(PhysxTriangleMeshSimplificationPropertiesCfg): + """Deprecated: use :class:`PhysxTriangleMeshSimplificationPropertiesCfg`. + + .. deprecated:: 4.6.25 + Renamed and relocated. This alias preserves backwards compatibility and is + scheduled for removal in 5.0. + """ + + def __post_init__(self): + warnings.warn( + "'TriangleMeshSimplificationPropertiesCfg' is deprecated and will be removed in 5.0. Use" + " 'isaaclab_physx.sim.schemas.PhysxTriangleMeshSimplificationPropertiesCfg' instead.", + DeprecationWarning, + stacklevel=2, + ) + super().__post_init__() + + +@configclass +class SDFMeshPropertiesCfg(PhysxSDFMeshPropertiesCfg): + """Deprecated: use :class:`PhysxSDFMeshPropertiesCfg`. + + .. deprecated:: 4.6.25 + Renamed and relocated. This alias preserves backwards compatibility and is + scheduled for removal in 5.0. + """ + + def __post_init__(self): + warnings.warn( + "'SDFMeshPropertiesCfg' is deprecated and will be removed in 5.0. Use" + " 'isaaclab_physx.sim.schemas.PhysxSDFMeshPropertiesCfg' instead.", + DeprecationWarning, + stacklevel=2, + ) + super().__post_init__() + + +@configclass +class PhysxFixedTendonPropertiesCfg: + """PhysX fixed-tendon properties for an articulation. + + Tendons are a PhysX-only feature -- Newton has no tendon system -- so this class + is a pure data carrier that is consumed by the PhysX-specific writer + :func:`~isaaclab.sim.schemas.modify_fixed_tendon_properties`. The writer authors + the multi-instance ``PhysxTendonAxisRootAPI`` schema; this cfg class declares no + metadata-driven writer plumbing of its own. + + See :func:`~isaaclab.sim.schemas.modify_fixed_tendon_properties` for more information. + + .. note:: + If the values are None, they are not modified. This is useful when you want to set only a subset of + the properties and leave the rest as-is. + """ + + tendon_enabled: bool | None = None + """Whether to enable or disable the tendon.""" + + stiffness: float | None = None + """Spring stiffness term acting on the tendon's length.""" + + damping: float | None = None + """The damping term acting on both the tendon length and the tendon-length limits.""" + + limit_stiffness: float | None = None + """Limit stiffness term acting on the tendon's length limits.""" + + offset: float | None = None + """Length offset term for the tendon. + + It defines an amount to be added to the accumulated length computed for the tendon. This allows the application + to actuate the tendon by shortening or lengthening it. + """ + + rest_length: float | None = None + """Spring rest length of the tendon.""" + + +@configclass +class FixedTendonPropertiesCfg(PhysxFixedTendonPropertiesCfg): + """Deprecated: use :class:`PhysxFixedTendonPropertiesCfg`. + + .. deprecated:: 4.6.x + ``FixedTendonPropertiesCfg`` was relocated to + :mod:`isaaclab_physx.sim.schemas` and renamed to + :class:`PhysxFixedTendonPropertiesCfg`. The legacy name remains as a + deprecation alias and is scheduled for removal in 5.0. + """ + + def __post_init__(self): + warnings.warn( + "'FixedTendonPropertiesCfg' is deprecated and will be removed in 5.0. Use" + " 'isaaclab_physx.sim.schemas.PhysxFixedTendonPropertiesCfg' instead.", + DeprecationWarning, + stacklevel=2, + ) + super().__post_init__() + + +@configclass +class PhysxSpatialTendonPropertiesCfg: + """PhysX spatial-tendon properties for an articulation. + + Tendons are a PhysX-only feature -- Newton has no tendon system -- so this class + is a pure data carrier that is consumed by the PhysX-specific writer + :func:`~isaaclab.sim.schemas.modify_spatial_tendon_properties`. The writer authors + the multi-instance ``PhysxTendonAttachmentRootAPI`` / ``PhysxTendonAttachmentLeafAPI`` + schemas; this cfg class declares no metadata-driven writer plumbing of its own. + + See :func:`~isaaclab.sim.schemas.modify_spatial_tendon_properties` for more information. + + .. note:: + If the values are None, they are not modified. This is useful when you want to set only a subset of + the properties and leave the rest as-is. + """ + + tendon_enabled: bool | None = None + """Whether to enable or disable the tendon.""" + + stiffness: float | None = None + """Spring stiffness term acting on the tendon's length.""" + + damping: float | None = None + """The damping term acting on both the tendon length and the tendon-length limits.""" + + limit_stiffness: float | None = None + """Limit stiffness term acting on the tendon's length limits.""" + + offset: float | None = None + """Length offset term for the tendon. + + It defines an amount to be added to the accumulated length computed for the tendon. This allows the application + to actuate the tendon by shortening or lengthening it. + """ + + +@configclass +class SpatialTendonPropertiesCfg(PhysxSpatialTendonPropertiesCfg): + """Deprecated: use :class:`PhysxSpatialTendonPropertiesCfg`. + + .. deprecated:: 4.6.x + ``SpatialTendonPropertiesCfg`` was relocated to + :mod:`isaaclab_physx.sim.schemas` and renamed to + :class:`PhysxSpatialTendonPropertiesCfg`. The legacy name remains as a + deprecation alias and is scheduled for removal in 5.0. + """ + + def __post_init__(self): + warnings.warn( + "'SpatialTendonPropertiesCfg' is deprecated and will be removed in 5.0. Use" + " 'isaaclab_physx.sim.schemas.PhysxSpatialTendonPropertiesCfg' instead.", + DeprecationWarning, + stacklevel=2, + ) + super().__post_init__() diff --git a/source/isaaclab_physx/isaaclab_physx/sim/spawners/materials/__init__.pyi b/source/isaaclab_physx/isaaclab_physx/sim/spawners/materials/__init__.pyi index 6e8a48b2f118..1a3e833d61d9 100644 --- a/source/isaaclab_physx/isaaclab_physx/sim/spawners/materials/__init__.pyi +++ b/source/isaaclab_physx/isaaclab_physx/sim/spawners/materials/__init__.pyi @@ -6,11 +6,15 @@ __all__ = [ "spawn_deformable_body_material", "DeformableBodyMaterialCfg", + "PhysxRigidBodyMaterialCfg", + "RigidBodyMaterialCfg", "SurfaceDeformableBodyMaterialCfg", ] from .physics_materials import spawn_deformable_body_material from .physics_materials_cfg import ( DeformableBodyMaterialCfg, + PhysxRigidBodyMaterialCfg, + RigidBodyMaterialCfg, SurfaceDeformableBodyMaterialCfg, ) diff --git a/source/isaaclab_physx/isaaclab_physx/sim/spawners/materials/physics_materials_cfg.py b/source/isaaclab_physx/isaaclab_physx/sim/spawners/materials/physics_materials_cfg.py index 35b066fa8736..2c8121a5cbee 100644 --- a/source/isaaclab_physx/isaaclab_physx/sim/spawners/materials/physics_materials_cfg.py +++ b/source/isaaclab_physx/isaaclab_physx/sim/spawners/materials/physics_materials_cfg.py @@ -6,9 +6,12 @@ from __future__ import annotations import dataclasses +import warnings from collections.abc import Callable +from typing import ClassVar, Literal from isaaclab.sim.spawners.materials import PhysicsMaterialCfg +from isaaclab.sim.spawners.materials.physics_materials_cfg import RigidBodyMaterialBaseCfg from isaaclab.utils import configclass @@ -120,3 +123,83 @@ class SurfaceDeformableBodyMaterialCfg(DeformableBodyMaterialCfg, OmniPhysicsSur "physxDeformableBody": [field.name for field in dataclasses.fields(PhysXDeformableMaterialCfg)], } """Extend DeformableBodyMaterialCfg properties under each prefix.""" + + +@configclass +class PhysxRigidBodyMaterialCfg(RigidBodyMaterialBaseCfg): + """PhysX-specific physics-material parameters for rigid bodies. + + Extends :class:`~isaaclab.sim.spawners.materials.RigidBodyMaterialBaseCfg` with the + `PhysxMaterialAPI`_ schema fields: compliant-contact spring (stiffness/damping) and the + friction/restitution combine-mode tokens. None of these fields have a Newton consumer + today; they are PhysX-engine-only knobs. + + See :meth:`~isaaclab.sim.spawners.materials.spawn_rigid_body_material` for more information. + + .. _PhysxMaterialAPI: https://docs.omniverse.nvidia.com/kit/docs/omni_usd_schema_physics/104.2/class_physx_schema_physx_material_a_p_i.html + """ + + # -- Class metadata (not dataclass fields) -- + # USD applied schema written when at least one PhysX-namespaced field is set. + _usd_applied_schema: ClassVar[str | None] = "PhysxMaterialAPI" + # Prim attribute namespace for PhysX-specific fields. + _usd_namespace: ClassVar[str | None] = "physxMaterial" + + compliant_contact_stiffness: float | None = None + """Spring stiffness for a compliant contact model using implicit springs. + + A higher stiffness results in behavior closer to a rigid contact. The compliant contact model + is only enabled if the stiffness is larger than 0. PhysX-only; not consumed by Newton. + """ + + compliant_contact_damping: float | None = None + """Damping coefficient for a compliant contact model using implicit springs. + + Irrelevant if compliant contacts are disabled when :attr:`compliant_contact_stiffness` is set + to zero and rigid contacts are active. PhysX-only; not consumed by Newton. + """ + + friction_combine_mode: Literal["average", "min", "multiply", "max"] | None = None + """Determines the way friction will be combined during collisions. + + .. attention:: + + When two physics materials with different combine modes collide, the combine mode with + the higher priority will be used. The priority order is provided `here + `__. + """ + + restitution_combine_mode: Literal["average", "min", "multiply", "max"] | None = None + """Determines the way restitution coefficient will be combined during collisions. + + .. attention:: + + When two physics materials with different combine modes collide, the combine mode with + the higher priority will be used. The priority order is provided `here + `__. + """ + + +@configclass +class RigidBodyMaterialCfg(PhysxRigidBodyMaterialCfg): + """Deprecated: use :class:`PhysxRigidBodyMaterialCfg` or + :class:`~isaaclab.sim.spawners.materials.RigidBodyMaterialBaseCfg`. + + .. deprecated:: 4.6.22 + ``RigidBodyMaterialCfg`` has been split into + :class:`~isaaclab.sim.spawners.materials.RigidBodyMaterialBaseCfg` (solver-common) and + :class:`PhysxRigidBodyMaterialCfg` (PhysX-specific) and relocated to + :mod:`isaaclab_physx.sim.spawners.materials`. This alias preserves backwards compatibility + and is scheduled for removal in 5.0. + """ + + def __post_init__(self): + warnings.warn( + "'RigidBodyMaterialCfg' is deprecated and will be removed in 5.0. Use" + " 'isaaclab_physx.sim.spawners.materials.PhysxRigidBodyMaterialCfg' for PhysX" + " properties, or 'isaaclab.sim.spawners.materials.RigidBodyMaterialBaseCfg' for" + " solver-common properties only.", + DeprecationWarning, + stacklevel=2, + ) + super().__post_init__() diff --git a/source/isaaclab_physx/test/assets/test_articulation.py b/source/isaaclab_physx/test/assets/test_articulation.py index 3687dae5961d..508a10f27c27 100644 --- a/source/isaaclab_physx/test/assets/test_articulation.py +++ b/source/isaaclab_physx/test/assets/test_articulation.py @@ -92,7 +92,7 @@ def generate_articulation_cfg( # we set 80.0 default for max force because default in USD is 10e10 which makes testing annoying. spawn=sim_utils.UsdFileCfg( usd_path=f"{ISAAC_NUCLEUS_DIR}/Robots/IsaacSim/SimpleArticulation/revolute_articulation.usd", - joint_drive_props=sim_utils.JointDrivePropertiesCfg(max_effort=80.0, max_velocity=5.0), + joint_drive_props=sim_utils.JointDrivePropertiesCfg(max_force=80.0, max_joint_velocity=5.0), ), actuators={ "joint": ImplicitActuatorCfg( @@ -116,7 +116,7 @@ def generate_articulation_cfg( articulation_cfg = ArticulationCfg( spawn=sim_utils.UsdFileCfg( usd_path=f"{ISAAC_NUCLEUS_DIR}/Robots/IsaacSim/SimpleArticulation/revolute_articulation.usd", - joint_drive_props=sim_utils.JointDrivePropertiesCfg(max_effort=80.0, max_velocity=5.0), + joint_drive_props=sim_utils.JointDrivePropertiesCfg(max_force=80.0, max_joint_velocity=5.0), ), actuators={ "joint": IdealPDActuatorCfg( @@ -1359,7 +1359,7 @@ def test_setting_velocity_limit_implicit(sim, num_articulations, device, vel_lim # Case 3: velocity limit sim is not set but velocity limit is set # For backwards compatibility, we do not set velocity limit to simulation # Thus, both default to USD default value. - limit = articulation_cfg.spawn.joint_drive_props.max_velocity + limit = articulation_cfg.spawn.joint_drive_props.max_joint_velocity else: # Case 4: only velocity limit sim is set # In this case, the velocity limit is set to the USD value @@ -1418,7 +1418,7 @@ def test_setting_velocity_limit_explicit(sim, num_articulations, device, vel_lim if vel_limit_sim is not None: limit = vel_limit_sim else: - limit = articulation_cfg.spawn.joint_drive_props.max_velocity + limit = articulation_cfg.spawn.joint_drive_props.max_joint_velocity # check physx is set to expected value expected_vel_limit = torch.full_like(physx_vel_limit, limit) torch.testing.assert_close(physx_vel_limit, expected_vel_limit) @@ -1466,7 +1466,7 @@ def test_setting_effort_limit_implicit(sim, num_articulations, device, effort_li # decide the limit based on what is set if effort_limit_sim is None and effort_limit is None: - limit = articulation_cfg.spawn.joint_drive_props.max_effort + limit = articulation_cfg.spawn.joint_drive_props.max_force elif effort_limit_sim is not None and effort_limit is None: limit = effort_limit_sim elif effort_limit_sim is None and effort_limit is not None: From 238817880733b801c7666554bcba5e03da069b2a Mon Sep 17 00:00:00 2001 From: Yuchen Deng Date: Thu, 7 May 2026 13:45:44 -0700 Subject: [PATCH 09/51] Updates docs for using nurec background in locomanipulation sdg (#5301) Updates docs for using nurec background in locomanipulation sdg ## Type of change - Documentation update ## Checklist - [ ] I have read and understood the [contribution guidelines](https://isaac-sim.github.io/IsaacLab/main/source/refs/contributing.html) - [x] I have run the [`pre-commit` checks](https://pre-commit.com/) with `./isaaclab.sh --format` - [ ] I have made corresponding changes to the documentation - [ ] My changes generate no new warnings - [ ] I have added tests that prove my fix is effective or that my feature works - [ ] I have updated the changelog and the corresponding version in the extension's `config/extension.toml` file - [ ] I have added my name to the `CONTRIBUTORS.md` or my name already exists there --------- Co-authored-by: Kelly Guo --- .../humanoids_imitation.rst | 143 ++++++++++++++---- .../locomanipulation_sdg/generate_data.py | 4 +- .../locomanipulation_sdg/scene_utils.py | 4 +- 3 files changed, 116 insertions(+), 35 deletions(-) diff --git a/docs/source/overview/imitation-learning/humanoids_imitation.rst b/docs/source/overview/imitation-learning/humanoids_imitation.rst index ae9989ddd8de..68fc22e75f9b 100644 --- a/docs/source/overview/imitation-learning/humanoids_imitation.rst +++ b/docs/source/overview/imitation-learning/humanoids_imitation.rst @@ -107,7 +107,7 @@ You can replay the collected demonstrations by running the following command: --dataset_file ./datasets/dataset_gr1.hdf5 .. note:: - Non-determinism may be observed during replay as physics in IsaacLab are not determimnistically reproducible when using ``env.reset``. + Non-determinism may be observed during replay as physics in IsaacLab are not deterministically reproducible when using ``env.reset``. Annotate the demonstrations @@ -405,7 +405,7 @@ The robot picks up an object at the initial location (point A) and places it at AGILE is an officially supported humanoid control training pipeline that leverages the manager based environment in Isaac Lab. It will also be seamlessly integrated with other evaluation and deployment tools across Isaac products. This allows teams to rely on a single, maintained stack covering all necessary infrastructure and tooling for policy training, with easy export to real-world deployment. The AGILE repository contains - updated pre-trained policies with separate upper and lower body policies for flexibtility. They have been verified in the real world and can be + updated pre-trained policies with separate upper and lower body policies for flexibility. They have been verified in the real world and can be directly deployed. Users can also train their own locomotion or whole-body control policies using the AGILE framework. .. _generate-the-manipulation-dataset: @@ -531,6 +531,8 @@ Visualize the trained policy performance: * Behavior Cloning (BC) policy success is typically 75-85% (evaluated on 50 rollouts) when trained on 1000 generated demonstrations for 2000 epochs (default), depending on demonstration quality. Training takes approximately 40 minutes on a RTX ADA 6000. * **Recommendation:** Train for 2000 epochs with 1000 generated demonstrations, and **evaluate multiple checkpoints saved between the 1000th and 2000th epochs** to select the best-performing policy. Testing various epochs is essential for finding optimal performance. +.. _generate-the-dataset-with-manipulation-and-point-to-point-navigation: + Generate the dataset with manipulation and point-to-point navigation ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ @@ -580,7 +582,7 @@ To generate the locomanipulation dataset, use the following command: The key parameters for locomanipulation dataset generation are: * ``--lift_step 60``: Number of steps for the lifting phase of the manipulation task. This should mark the point immediately after the robot has grasped the object. -* ``--navigate_step 130``: Number of steps for the navigation phase between locations. This should make the point where the robot has lifted the object and is ready to walk. +* ``--navigate_step 130``: Number of steps for the navigation phase between locations. This should mark the point where the robot has lifted the object and is ready to walk. * ``--output_file``: Name of the output dataset file .. note:: @@ -600,6 +602,8 @@ This process creates a dataset where the robot performs the manipulation task at The data generated from this locomanipulation pipeline can also be used to finetune an imitation learning policy using GR00T N1.5. The following steps describe how to install GR00T, convert the dataset to LeRobot format, finetune the policy, and run rollouts in Isaac Lab. +.. _finetune-groot-n15-for-locomanipulation: + Finetune GR00T N1.5 policy for locomanipulation ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ @@ -699,37 +703,99 @@ Optional arguments include ``--randomize_placement`` and ``--policy_quat_format The policy shown above uses the camera image, hand poses, hand joint positions, object pose, and base goal pose as inputs. The output of the model is the target base velocity, hand poses, and hand joint positions for the next several timesteps. -Use NuRec Background in Locomanipulation SDG -^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Integrating 3D Gaussian Splatting into SDG +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -**Prerequisites:** Generate a manipulation dataset or download a pre-recorded annotated dataset from :ref:`Generate the manipulation dataset `. +This section extends +:ref:`locomanipulation SDG ` +by replacing the synthetic background with a 3D Gaussian Splatting (NuRec) scene. As in the +base pipeline, the workflow takes a manipulation dataset as input and produces a combined +navigation and manipulation dataset as an HDF5 file — but here the robot navigates and +manipulates objects inside a neurally-rendered environment, and an ego-centric camera +captures the result, producing more realistic training data than a purely synthetic scene. +NVIDIA Isaac Sim renders 3DGS models stored as USD assets; see +`Neural Volume Rendering `__ +for details. -The `NuRec assets `__ -are neural volumes reconstructed from real-world captures. When integrated into the locomanipulation SDG workflow, these -assets allow you to generate synthetic data in photorealistic environments that mirror real-world. +.. note:: -Custom NuRec Asset Requirements -""""""""""""""""""""""""""""""" + This section focuses on data generation with a 3DGS background. To train a policy on the + generated data, see :ref:`Finetune GR00T N1.5 policy for locomanipulation `. -To load a custom USD asset, ensure it meets the following specifications: +.. note:: -- Neural Rendering: Include neural reconstruction for rendering. -- Navigation: Include a pre-computed occupancy map for path planning and navigation. You can use the `Occupancy Map Generator `_ to generate the occupancy map. -- Orientation: Transform the asset so that the ground aligns with the z=0 plane. -- Collision Mesh (optional): If a collision mesh is included, set it to invisible. + The locomanipulation SDG pipeline currently runs a single environment. Parallel environment + support is not yet available for this workflow. -Using Pre-constructed Assets -"""""""""""""""""""""""""""" +Setup: downloading example assets +""""""""""""""""""""""""""""""""" + +We provide a sample asset, ``hand_hold-voyager-babyboom``, on +`Hugging Face `__. -Pre-constructed assets are available via the `PhysicalAI Robotics NuRec `__ -dataset. Some of them are captured from a humanoid-viewpoint to match the camera view of the humanoid robot. +Log in to Hugging Face: -For example, when using the asset ``hand_hold-voyager-babyboom``, the relevant files are: +.. code:: bash -- `stage.usdz `__: a USDZ archive that bundles 3D Gaussian splatting (``volume.nurec``), a collision mesh (``mesh.usd``), etc. -- `occupancy_map.yaml `__ and `occupancy_map.png `__: occupancy map for path planning and navigation. + hf auth login --token -Download the files and place them under ````, then run the following command to generate a new dataset with background: +Download the required USDZ stage files and occupancy maps: + +.. code:: bash + + hf download nvidia/PhysicalAI-Robotics-NuRec \ + hand_hold-voyager-babyboom/stage_volume.usdz \ + hand_hold-voyager-babyboom/stage_particle.usdz \ + hand_hold-voyager-babyboom/occupancy_map.png \ + hand_hold-voyager-babyboom/occupancy_map.yaml \ + --repo-type dataset \ + --local-dir + +The sample includes both a volume-based USD (``stage_volume.usdz``) and a particle-field USD +(``stage_particle.usdz``). Either can be used as the background asset. + +Asset requirements +"""""""""""""""""" + +If you are using custom 3D Gaussian assets, ensure they meet these specifications to be +compatible with the SDG pipeline: + +- The scene has sufficient free space (e.g. 5m x 5m) for asset placement and robot navigation. +- The ground surface is aligned with the z=0 plane, as the pipeline assumes this elevation for + object placement. +- An occupancy map is required for path planning. + + - If your scene was reconstructed using the `Stereo Workflow `__, + the occupancy map is generated via ``nvblox``. + - If your background includes a mesh, use the `Occupancy Map Generator `__ + to create a map via physical simulation. + +Generating the dataset +"""""""""""""""""""""" + +Before proceeding, ensure you have generated a manipulation dataset or downloaded the sample +dataset provided in the +:ref:`Generate the manipulation dataset ` section. + +Once you have gathered: + +- A manipulation dataset +- A background USD asset +- A matched occupancy map + +you can run the generation command. At runtime, the script adds a ground plane at ``z=0`` to +the scene. It then proceeds through four stages: + +1. **Pick**: The robot picks up an object at the start location by replaying the manipulation + trajectory. ``--lift_step`` marks the end of this stage (immediately after grasp). +2. **Navigate**: The robot travels to the target location using occupancy-map path planning and + its locomotion policy. ``--navigate_step`` marks the end of this stage (when the robot is in + place to release the object). +3. **Place**: The robot places the object at the target location, completing the trajectory. +4. **Record**: Joint states, poses, and the ego-centric video are saved to the HDF5 file + specified by ``--output_file``. + +Run the generation command: .. code:: bash @@ -741,36 +807,49 @@ Download the files and place them under ````, then run the fo --num_runs 1 \ --lift_step 60 \ --navigate_step 130 \ - --output_file /generated_dataset_g1_locomanipulation_sdg_with_background.hdf5 \ + --output_file /generated_dataset_g1_locomanipulation_sdg_gaussian_background.hdf5 \ --enable_cameras \ --visualizer kit \ - --background_usd_path /stage.usdz \ + --background_usd_path /stage_particle.usdz \ --background_occupancy_yaml_file /occupancy_map.yaml \ --randomize_placement \ --high_res_video The key parameters are: -- ``--background_usd_path``: Path to the NuRec USD asset. +- ``--background_usd_path``: Path to the 3D Gaussian background USD asset. - ``--background_occupancy_yaml_file``: Path to the occupancy map file. -- ``--high_res_video``: Generate a higher resolution video (540x960) for the ego-centric camera view. -- ``--sensor_camera_view``: Optionally set the Sim GUI viewport to the ``robot_pov_cam`` sensor view. +- ``--high_res_video``: Capture the ego-centric camera at 960×540 instead of the default + 256×160. -On successful task completion, an HDF5 dataset is generated containing camera observations. You can convert -the ego-centric camera view to MP4. +When the run completes successfully, an HDF5 dataset is generated containing camera +observations. You can convert the ego-centric camera view to MP4: .. code:: bash ./isaaclab.sh -p scripts/tools/hdf5_to_mp4.py \ - --input_file /generated_dataset_g1_locomanipulation_sdg_with_background.hdf5 \ + --input_file /generated_dataset_g1_locomanipulation_sdg_gaussian_background.hdf5 \ --output_dir / \ --input_keys robot_pov_cam \ --video_width 960 \ --video_height 540 +Set ``--video_width`` and ``--video_height`` to match the resolution captured during +generation: 960×540 with ``--high_res_video``, or 256×160 without it. + To play the generated MP4 video on Ubuntu, install the following multimedia packages: .. code:: bash sudo apt update sudo apt install libavcodec-extra gstreamer1.0-libav gstreamer1.0-plugins-ugly + + +.. figure:: https://download.isaacsim.omniverse.nvidia.com/isaaclab/images/locomanipulation_sdg_gaussian_background_2x.webp + :width: 100% + :align: center + :alt: locomanipulation SDG with a 3D Gaussian background + :figclass: align-center + +The figure above shows recorded ego-centric camera views in the 3D Gaussian background +when the robot replays the pick and place trajectory and navigates to the target location. diff --git a/scripts/imitation_learning/locomanipulation_sdg/generate_data.py b/scripts/imitation_learning/locomanipulation_sdg/generate_data.py index bbae0689ff65..99014e75ff1d 100644 --- a/scripts/imitation_learning/locomanipulation_sdg/generate_data.py +++ b/scripts/imitation_learning/locomanipulation_sdg/generate_data.py @@ -331,8 +331,8 @@ def project_robot_state_into_env(env: LocomanipulationSDGEnv, input_episode_data object = env.scene["object"] current_object_pose = torch.cat( [ - torch.as_tensor(object.data.root_pos_w[0:1], device=env.device, dtype=torch.float32), - torch.as_tensor(object.data.root_quat_w[0:1], device=env.device, dtype=torch.float32), + torch.as_tensor(object.data.root_pos_w.torch[0:1], device=env.device, dtype=torch.float32), + torch.as_tensor(object.data.root_quat_w.torch[0:1], device=env.device, dtype=torch.float32), ], dim=-1, ) # (1, 7) diff --git a/source/isaaclab_mimic/isaaclab_mimic/locomanipulation_sdg/scene_utils.py b/source/isaaclab_mimic/isaaclab_mimic/locomanipulation_sdg/scene_utils.py index a0eb00fb4a58..4ba068fc8f56 100644 --- a/source/isaaclab_mimic/isaaclab_mimic/locomanipulation_sdg/scene_utils.py +++ b/source/isaaclab_mimic/isaaclab_mimic/locomanipulation_sdg/scene_utils.py @@ -106,7 +106,9 @@ def _get_xform_view(self) -> FrameView: xform_prim = self.scene[self.entity_name] if xform_prim.count == 0: # The view was created before environment cloning; rebuild it now that prims exist. - xform_prim = FrameView(xform_prim._prim_path, device=xform_prim.device) + # FabricFrameView composes UsdFrameView; the template prim_path lives on the inner USD view. + inner = getattr(xform_prim, "_usd_view", xform_prim) + xform_prim = FrameView(inner._prim_path, device=xform_prim.device) self.scene.extras[self.entity_name] = xform_prim return xform_prim From a7514be502f1d7441db7fa3f5e4727998fa9e440 Mon Sep 17 00:00:00 2001 From: "isaaclab-bot[bot]" <282401363+isaaclab-bot[bot]@users.noreply.github.com> Date: Fri, 8 May 2026 01:17:22 +0000 Subject: [PATCH 10/51] [CI][Auto Version Bump] Compile changelog fragments (workflow_dispatch) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Bumped packages: - isaaclab: 4.6.28 → 4.7.0 - isaaclab_newton: 0.5.26 → 0.6.0 - isaaclab_ov: 0.1.3 → 0.1.4 - isaaclab_ovphysx: 0.1.2 → 0.1.3 - isaaclab_physx: 0.5.29 → 0.6.0 - isaaclab_rl: 0.5.1 → 0.5.2 - isaaclab_tasks: 1.5.34 → 1.5.35 - isaaclab_teleop: 0.3.9 → 0.3.10 --- .../antoiner-rename-newton-presets.skip | 1 - .../clone-plan-visualizer-cleanup.minor.rst | 43 --- .../fix-fabric-prepare-for-reuse.rst | 8 - .../changelog.d/leapp_export_integration.rst | 15 -- .../mtrepte-expand_viz_markers-2.skip | 0 .../mtrepte-expand_viz_markers.minor.rst | 5 - .../changelog.d/omniverseclient-pin.rst | 4 - .../changelog.d/pr-5458-merge-develop.rst | 15 -- .../rschmitt_decouple_renderer_camera.rst | 33 --- .../rschmitt_default_cameracfg_renderer.rst | 11 - .../vidur-cfg-exception-table.minor.rst | 27 -- .../vidur-rebalance-cfg-placement.minor.rst | 122 --------- source/isaaclab/config/extension.toml | 2 +- source/isaaclab/docs/CHANGELOG.rst | 245 ++++++++++++++++++ .../clone-plan-visualizer-cleanup.minor.rst | 9 - .../mtrepte-expand_viz_markers.skip | 1 - .../mym-newton-manager-abstraction.rst | 14 - .../changelog.d/pr-5458-merge-develop.rst | 13 - .../rschmitt_decouple_rednerer_camera.rst | 4 - .../vidur-feature-usd-proprties-refactor.skip | 0 source/isaaclab_newton/config/extension.toml | 2 +- source/isaaclab_newton/docs/CHANGELOG.rst | 40 +++ .../changelog.d/pbarejko-open-usd.rst | 7 - .../rschmitt_decouple_renderer_camera.rst | 4 - source/isaaclab_ov/config/extension.toml | 2 +- source/isaaclab_ov/docs/CHANGELOG.rst | 17 ++ .../changelog.d/pr-5458-merge-develop.rst | 7 - source/isaaclab_ovphysx/config/extension.toml | 2 +- source/isaaclab_ovphysx/docs/CHANGELOG.rst | 12 + .../clone-plan-visualizer-cleanup.skip | 0 .../fix-fabric-prepare-for-reuse.rst | 12 - .../mtrepte-expand_viz_markers.skip | 2 - .../changelog.d/pr-5458-merge-develop.rst | 16 -- .../rschmitt_decouple_renderer_camera.rst | 4 - .../changelog.d/test-articulation-timeout.rst | 6 - .../vidur-rebalance-cfg-placement.minor.rst | 77 ------ source/isaaclab_physx/config/extension.toml | 2 +- source/isaaclab_physx/docs/CHANGELOG.rst | 112 ++++++++ .../changelog.d/leapp_export_integration.rst | 5 - source/isaaclab_rl/config/extension.toml | 2 +- source/isaaclab_rl/docs/CHANGELOG.rst | 10 + .../antoiner-rename-newton-presets.rst | 25 -- .../changelog.d/g1-rough-terrain-wip.rst | 11 - .../changelog.d/huidongc-flaky-mark.skip | 0 .../changelog.d/leapp_export_integration.rst | 5 - .../mtrepte-expand_viz_markers.skip | 1 - .../changelog.d/pr-5458-merge-develop.rst | 10 - .../changelog.d/rendering-test-flakiness.skip | 0 .../rwiltz-restore-legacy-teleop.rst | 8 - source/isaaclab_tasks/config/extension.toml | 2 +- source/isaaclab_tasks/docs/CHANGELOG.rst | 56 ++++ .../rwiltz-restore-legacy-teleop.rst | 11 - source/isaaclab_teleop/config/extension.toml | 2 +- source/isaaclab_teleop/docs/CHANGELOG.rst | 16 ++ 54 files changed, 516 insertions(+), 544 deletions(-) delete mode 100644 source/isaaclab/changelog.d/antoiner-rename-newton-presets.skip delete mode 100644 source/isaaclab/changelog.d/clone-plan-visualizer-cleanup.minor.rst delete mode 100644 source/isaaclab/changelog.d/fix-fabric-prepare-for-reuse.rst delete mode 100644 source/isaaclab/changelog.d/leapp_export_integration.rst delete mode 100644 source/isaaclab/changelog.d/mtrepte-expand_viz_markers-2.skip delete mode 100644 source/isaaclab/changelog.d/mtrepte-expand_viz_markers.minor.rst delete mode 100644 source/isaaclab/changelog.d/omniverseclient-pin.rst delete mode 100644 source/isaaclab/changelog.d/pr-5458-merge-develop.rst delete mode 100644 source/isaaclab/changelog.d/rschmitt_decouple_renderer_camera.rst delete mode 100644 source/isaaclab/changelog.d/rschmitt_default_cameracfg_renderer.rst delete mode 100644 source/isaaclab/changelog.d/vidur-cfg-exception-table.minor.rst delete mode 100644 source/isaaclab/changelog.d/vidur-rebalance-cfg-placement.minor.rst delete mode 100644 source/isaaclab_newton/changelog.d/clone-plan-visualizer-cleanup.minor.rst delete mode 100644 source/isaaclab_newton/changelog.d/mtrepte-expand_viz_markers.skip delete mode 100644 source/isaaclab_newton/changelog.d/mym-newton-manager-abstraction.rst delete mode 100644 source/isaaclab_newton/changelog.d/pr-5458-merge-develop.rst delete mode 100644 source/isaaclab_newton/changelog.d/rschmitt_decouple_rednerer_camera.rst delete mode 100644 source/isaaclab_newton/changelog.d/vidur-feature-usd-proprties-refactor.skip delete mode 100644 source/isaaclab_ov/changelog.d/pbarejko-open-usd.rst delete mode 100644 source/isaaclab_ov/changelog.d/rschmitt_decouple_renderer_camera.rst delete mode 100644 source/isaaclab_ovphysx/changelog.d/pr-5458-merge-develop.rst delete mode 100644 source/isaaclab_physx/changelog.d/clone-plan-visualizer-cleanup.skip delete mode 100644 source/isaaclab_physx/changelog.d/fix-fabric-prepare-for-reuse.rst delete mode 100644 source/isaaclab_physx/changelog.d/mtrepte-expand_viz_markers.skip delete mode 100644 source/isaaclab_physx/changelog.d/pr-5458-merge-develop.rst delete mode 100644 source/isaaclab_physx/changelog.d/rschmitt_decouple_renderer_camera.rst delete mode 100644 source/isaaclab_physx/changelog.d/test-articulation-timeout.rst delete mode 100644 source/isaaclab_physx/changelog.d/vidur-rebalance-cfg-placement.minor.rst delete mode 100644 source/isaaclab_rl/changelog.d/leapp_export_integration.rst delete mode 100644 source/isaaclab_tasks/changelog.d/antoiner-rename-newton-presets.rst delete mode 100644 source/isaaclab_tasks/changelog.d/g1-rough-terrain-wip.rst delete mode 100644 source/isaaclab_tasks/changelog.d/huidongc-flaky-mark.skip delete mode 100644 source/isaaclab_tasks/changelog.d/leapp_export_integration.rst delete mode 100644 source/isaaclab_tasks/changelog.d/mtrepte-expand_viz_markers.skip delete mode 100644 source/isaaclab_tasks/changelog.d/pr-5458-merge-develop.rst delete mode 100644 source/isaaclab_tasks/changelog.d/rendering-test-flakiness.skip delete mode 100644 source/isaaclab_tasks/changelog.d/rwiltz-restore-legacy-teleop.rst delete mode 100644 source/isaaclab_teleop/changelog.d/rwiltz-restore-legacy-teleop.rst diff --git a/source/isaaclab/changelog.d/antoiner-rename-newton-presets.skip b/source/isaaclab/changelog.d/antoiner-rename-newton-presets.skip deleted file mode 100644 index e32e76dd5f0e..000000000000 --- a/source/isaaclab/changelog.d/antoiner-rename-newton-presets.skip +++ /dev/null @@ -1 +0,0 @@ -skip diff --git a/source/isaaclab/changelog.d/clone-plan-visualizer-cleanup.minor.rst b/source/isaaclab/changelog.d/clone-plan-visualizer-cleanup.minor.rst deleted file mode 100644 index 8a8a74cb6267..000000000000 --- a/source/isaaclab/changelog.d/clone-plan-visualizer-cleanup.minor.rst +++ /dev/null @@ -1,43 +0,0 @@ -Added -^^^^^ - -* Added :class:`~isaaclab.cloner.ClonePlan` frozen dataclass capturing per-group - prototype-to-environment mappings (``dest_template``, ``prototype_paths``, - ``clone_mask``). Lets downstream consumers (scene data providers, mesh samplers) - read prototype geometry once and scatter to environments via the per-group mask - instead of walking per-env USD paths. -* Added :meth:`~isaaclab.sim.SimulationContext.get_clone_plans` and - :meth:`~isaaclab.sim.SimulationContext.set_clone_plans` for publishing and - consuming the cloner's per-group plan map. -* Added :attr:`~isaaclab.scene.InteractiveScene.clone_plans` property (forwards to - :meth:`~isaaclab.sim.SimulationContext.get_clone_plans`) so consumers holding a - scene reference can read the published plans without going through the sim - context. - -Changed -^^^^^^^ - -* **Breaking:** :func:`~isaaclab.cloner.clone_from_template` now returns - ``dict[str, ClonePlan]`` instead of ``None``. Bind the result and publish it - through :meth:`~isaaclab.sim.SimulationContext.set_clone_plans` if downstream - consumers (e.g. the PhysX scene data provider's Newton-visualizer build path) - need to read the plan. - -Removed -^^^^^^^ - -* **Breaking:** Removed - :attr:`~isaaclab.cloner.TemplateCloneCfg.visualizer_clone_fn`, - :func:`~isaaclab.cloner.resolve_visualizer_clone_fn`, and - :class:`~isaaclab.physics.scene_data_requirements.VisualizerPrebuiltArtifacts`. - Scene data providers now build backend models from the - :class:`~isaaclab.cloner.ClonePlan` map via - :meth:`~isaaclab.sim.SimulationContext.get_clone_plans` instead of receiving a - prebuilt artifact through a clone-time callback. -* **Breaking:** Removed - :meth:`~isaaclab.sim.SimulationContext.get_scene_data_visualizer_prebuilt_artifact`, - :meth:`~isaaclab.sim.SimulationContext.set_scene_data_visualizer_prebuilt_artifact`, - and - :meth:`~isaaclab.sim.SimulationContext.clear_scene_data_visualizer_prebuilt_artifact`. - Use :meth:`~isaaclab.sim.SimulationContext.get_clone_plans` / - :meth:`~isaaclab.sim.SimulationContext.set_clone_plans` instead. diff --git a/source/isaaclab/changelog.d/fix-fabric-prepare-for-reuse.rst b/source/isaaclab/changelog.d/fix-fabric-prepare-for-reuse.rst deleted file mode 100644 index 20a6d385c094..000000000000 --- a/source/isaaclab/changelog.d/fix-fabric-prepare-for-reuse.rst +++ /dev/null @@ -1,8 +0,0 @@ -Changed -^^^^^^^ - -* Updated :class:`~isaaclab.sensors.camera.Camera` to construct its internal - :class:`~isaaclab.sim.views.FrameView` without the now-removed - ``sync_usd_on_fabric_write`` kwarg. USD attributes on camera prims are - no longer kept in sync with Fabric writes; read poses through the view's - getters instead. diff --git a/source/isaaclab/changelog.d/leapp_export_integration.rst b/source/isaaclab/changelog.d/leapp_export_integration.rst deleted file mode 100644 index ea2de5e5d029..000000000000 --- a/source/isaaclab/changelog.d/leapp_export_integration.rst +++ /dev/null @@ -1,15 +0,0 @@ -Added -^^^^^ - -* Added LEAPP export support for manager-based RSL-RL policies, including - export-time observation/action annotation, recurrent actor-state handling, and - deployment through :mod:`scripts.reinforcement_learning.leapp.deploy`. -* Added a Direct workflow LEAPP export tutorial and annotated ANYmal-C example - script showing how to mark policy inputs, outputs, and persistent state with - LEAPP annotations. Direct workflow policies can be exported with - :mod:`scripts.reinforcement_learning.leapp.rsl_rl.export`, but are not yet - supported by :mod:`scripts.reinforcement_learning.leapp.deploy`. -* Added LEAPP deployment documentation describing the exported-policy validation - flow and linking the manager-based and Direct workflow export paths. -* Added LEAPP export annotations, proxy utilities, and deployment environment - support for Isaac Lab assets, sensors, commands, and manager-based environments. diff --git a/source/isaaclab/changelog.d/mtrepte-expand_viz_markers-2.skip b/source/isaaclab/changelog.d/mtrepte-expand_viz_markers-2.skip deleted file mode 100644 index e69de29bb2d1..000000000000 diff --git a/source/isaaclab/changelog.d/mtrepte-expand_viz_markers.minor.rst b/source/isaaclab/changelog.d/mtrepte-expand_viz_markers.minor.rst deleted file mode 100644 index 8975a9178b83..000000000000 --- a/source/isaaclab/changelog.d/mtrepte-expand_viz_markers.minor.rst +++ /dev/null @@ -1,5 +0,0 @@ -Added -^^^^^ - -* Added backend-agnostic :class:`~isaaclab.markers.VisualizationMarkers` support for - marker-capable Kit, Newton, Rerun, and Viser visualizers. diff --git a/source/isaaclab/changelog.d/omniverseclient-pin.rst b/source/isaaclab/changelog.d/omniverseclient-pin.rst deleted file mode 100644 index 832820b64a47..000000000000 --- a/source/isaaclab/changelog.d/omniverseclient-pin.rst +++ /dev/null @@ -1,4 +0,0 @@ -Fixed -^^^^^ - -* Pinned ``omniverseclient`` to ``2.71.1.7015``. diff --git a/source/isaaclab/changelog.d/pr-5458-merge-develop.rst b/source/isaaclab/changelog.d/pr-5458-merge-develop.rst deleted file mode 100644 index c94e6b8921a6..000000000000 --- a/source/isaaclab/changelog.d/pr-5458-merge-develop.rst +++ /dev/null @@ -1,15 +0,0 @@ -Changed -^^^^^^^ - -* Changed :func:`~isaaclab.envs.mdp.body_incoming_wrench` to read from - :class:`~isaaclab.sensors.JointWrenchSensor`. Pass - ``sensor_cfg=SceneEntityCfg("joint_wrench", body_names=...)`` instead of an - articulation asset config. - -Removed -^^^^^^^ - -* Removed ``BaseArticulationData.body_incoming_joint_wrench_b``. Add - :class:`~isaaclab.sensors.JointWrenchSensorCfg` to the scene and read - :attr:`~isaaclab.sensors.JointWrenchSensorData.force` and - :attr:`~isaaclab.sensors.JointWrenchSensorData.torque` instead. diff --git a/source/isaaclab/changelog.d/rschmitt_decouple_renderer_camera.rst b/source/isaaclab/changelog.d/rschmitt_decouple_renderer_camera.rst deleted file mode 100644 index 337b7f55b6a3..000000000000 --- a/source/isaaclab/changelog.d/rschmitt_decouple_renderer_camera.rst +++ /dev/null @@ -1,33 +0,0 @@ -Added -^^^^^ - -* Added :class:`~isaaclab.renderers.camera_render_spec.CameraRenderSpec` so render backends - take explicit camera inputs (USD paths, :class:`~isaaclab.sensors.camera.CameraCfg`, device, - counts) instead of the :class:`~isaaclab.sensors.camera.Camera` instance. -* Added :class:`~isaaclab.renderers.render_context.RenderContext` (accessed as - :attr:`~isaaclab.sim.simulation_context.SimulationContext.render_context`) to own one or - more :class:`~isaaclab.renderers.base_renderer.BaseRenderer` instances: configurations that - compare equal under ``==`` and share the same concrete - :class:`~isaaclab.renderers.renderer_cfg.RendererCfg` class reuse a backend; distinct - types (e.g. Isaac RTX and Newton) register separate backends, each with - :meth:`~isaaclab.renderers.base_renderer.BaseRenderer.prepare_stage` the first time a camera - with that configuration initializes. -* Added :meth:`~isaaclab.renderers.render_context.RenderContext.render_into_camera` to run - :meth:`~isaaclab.renderers.render_context.RenderContext.update_transforms` (at most once - per physics step), then :meth:`~isaaclab.renderers.base_renderer.BaseRenderer.render` and - :meth:`~isaaclab.renderers.base_renderer.BaseRenderer.read_output`. -* Added :meth:`~isaaclab.sim.simulation_context.SimulationContext.get_physics_step_count`. - -Changed -^^^^^^^ - -* :class:`~isaaclab.sensors.camera.Camera` obtains a backend via - :meth:`~isaaclab.renderers.render_context.RenderContext.get_renderer` and calls - :meth:`~isaaclab.renderers.base_renderer.BaseRenderer.create_render_data` with - a :class:`~isaaclab.renderers.camera_render_spec.CameraRenderSpec` (no - :class:`~isaaclab.sensors.sensor_base.SensorBase` reference on the public API). -* :class:`~isaaclab.scene.interactive_scene.InteractiveScene` calls - :meth:`~isaaclab.renderers.render_context.RenderContext.update_transforms` once at the start - of :meth:`~isaaclab.scene.interactive_scene.InteractiveScene.update` when - ``lazy_sensor_update`` is false; fetches that render still dedupe the same way via - ``physics_step_count`` in :class:`~isaaclab.renderers.render_context.RenderContext`. diff --git a/source/isaaclab/changelog.d/rschmitt_default_cameracfg_renderer.rst b/source/isaaclab/changelog.d/rschmitt_default_cameracfg_renderer.rst deleted file mode 100644 index e11891e307b5..000000000000 --- a/source/isaaclab/changelog.d/rschmitt_default_cameracfg_renderer.rst +++ /dev/null @@ -1,11 +0,0 @@ -Added -^^^^^ - -* Added :meth:`~isaaclab.utils.backend_utils.get_default_renderer_cfg`. to lazy load the IsaacRtxRendererCfg - -Changed -^^^^^^^ - -* :class:`~isaaclab.sensors.camera.CameraCfg` now defaults its render_cfg to :class:`~isaaclab.renderers.RenderCfg` - :meth:`~isaaclab.utils.backend_utils.get_default_renderer_cfg` is called during __post_init__ to replace - the generic RenderCfg with the default config :class:`~isaaclab_physx.renderers.IsaacRtxRendererCfg` diff --git a/source/isaaclab/changelog.d/vidur-cfg-exception-table.minor.rst b/source/isaaclab/changelog.d/vidur-cfg-exception-table.minor.rst deleted file mode 100644 index de2d19065b61..000000000000 --- a/source/isaaclab/changelog.d/vidur-cfg-exception-table.minor.rst +++ /dev/null @@ -1,27 +0,0 @@ -Changed -^^^^^^^ - -* Cleaned up the schema-cfg base classes to no longer carry PhysX namespace metadata. - :class:`~isaaclab.sim.schemas.RigidBodyBaseCfg`, - :class:`~isaaclab.sim.schemas.CollisionBaseCfg`, - :class:`~isaaclab.sim.schemas.ArticulationRootBaseCfg`, and - :class:`~isaaclab.sim.schemas.JointDriveBaseCfg` now declare ``_usd_namespace = None`` and - ``_usd_applied_schema = None``. Per-field PhysX overrides for fields whose only USD path - today is the ``physx*:*`` namespace (``disable_gravity``, ``contact_offset``, - ``rest_offset``, ``articulation_enabled``, ``max_velocity``) are declared via a new - ``_usd_field_exceptions`` mapping ``applied_schema -> (namespace, {cfg_field: usd_attr})``. - When any listed field is non-None at write time, the writer applies that schema and writes - the attribute under the exception namespace; otherwise the schema is not stamped onto the - prim. PhysX subclasses (:class:`PhysxRigidBodyPropertiesCfg`, - :class:`PhysxCollisionPropertiesCfg`, :class:`PhysxArticulationRootPropertiesCfg`, - :class:`PhysxJointDrivePropertiesCfg`) now self-declare ``_usd_namespace`` and - ``_usd_applied_schema`` for their own fields. Observable behavior on standard inputs is - unchanged. -* Consolidated the per-writer schema-application loop in - :mod:`isaaclab.sim.schemas` into a single shared helper ``_apply_namespaced_schemas``. - ``modify_articulation_root_properties``, ``modify_rigid_body_properties``, - ``modify_collision_properties``, ``modify_joint_drive_properties``, - ``modify_mesh_collision_properties``, and ``spawn_rigid_body_material`` all delegate to the - helper after writing their typed-API ``UsdPhysics`` fields. The canonical exception-table - + main-namespace gating logic now lives in one place instead of being duplicated across - six call sites. diff --git a/source/isaaclab/changelog.d/vidur-rebalance-cfg-placement.minor.rst b/source/isaaclab/changelog.d/vidur-rebalance-cfg-placement.minor.rst deleted file mode 100644 index 72be33772d9d..000000000000 --- a/source/isaaclab/changelog.d/vidur-rebalance-cfg-placement.minor.rst +++ /dev/null @@ -1,122 +0,0 @@ -Added -^^^^^ - -* Added :class:`~isaaclab.sim.spawners.materials.RigidBodyMaterialBaseCfg`, the solver-common - base class for rigid-body physics materials. Carries the ``UsdPhysics.MaterialAPI`` standard - fields (``static_friction``, ``dynamic_friction``, ``restitution``). The PhysX-specific - compliant-contact and combine-mode fields moved to - :class:`~isaaclab_physx.sim.spawners.materials.PhysxRigidBodyMaterialCfg`. -* Added :class:`~isaaclab.sim.schemas.CollisionBaseCfg`, the solver-common base class for - collision properties. Carries :attr:`collision_enabled` (``UsdPhysics.CollisionAPI``) plus - :attr:`contact_offset` and :attr:`rest_offset` whose USD attributes are PhysX-namespaced - but are consumed by Newton's importer via the PhysX bridge resolver - (``import_usd.py:2104, 2111``). -* Added :class:`~isaaclab.sim.schemas.ArticulationRootBaseCfg`, the solver-common base class - for articulation root properties (``fix_root_link``, ``articulation_enabled``). -* Added :class:`~isaaclab.sim.schemas.MeshCollisionBaseCfg`, the solver-common base class for - mesh collision properties carrying ``mesh_approximation_name`` (writes - ``physics:approximation`` via :class:`UsdPhysics.MeshCollisionAPI`). The class-level - ``_usd_applied_schema`` metadata replaces the deprecated ``usd_api`` / ``physx_api`` - instance-field dispatch. - -Changed -^^^^^^^ - -* Moved the ``max_velocity`` field from :class:`~isaaclab_physx.sim.schemas.PhysxJointDrivePropertiesCfg` - to :class:`~isaaclab.sim.schemas.JointDriveBaseCfg`. The field is the only USD path to set - Newton's ``Model.joint_velocity_limit`` and is consumed by Newton's importer. The USD - attribute written is unchanged (``physxJoint:maxJointVelocity``); existing code using - ``PhysxJointDrivePropertiesCfg(max_velocity=...)`` continues to work because the field - is inherited. -* Moved the ``disable_gravity`` field from :class:`~isaaclab_physx.sim.schemas.PhysxRigidBodyPropertiesCfg` - to :class:`~isaaclab.sim.schemas.RigidBodyBaseCfg`. PhysX honors per-body via - ``physxRigidBody:disableGravity``; Newton currently honors at scene level (partial), - documented in the field docstring. Existing code using - ``PhysxRigidBodyPropertiesCfg(disable_gravity=...)`` continues to work via inheritance. -* Documented :attr:`~isaaclab.sim.schemas.ArticulationRootPropertiesCfg.articulation_enabled` - and :attr:`~isaaclab.sim.schemas.ArticulationRootPropertiesCfg.enabled_self_collisions` - to lock their placement for the future :class:`ArticulationRootBaseCfg` / - ``PhysxArticulationRootPropertiesCfg`` split: ``articulation_enabled`` stays on the base - (single-namespace USD with verified Newton consumer); ``enabled_self_collisions`` moves - to the PhysX subclass (dual-namespace USD, with a future Newton sibling cfg owning the - ``newton:*`` namespace). -* Changed the defaults of :attr:`~isaaclab_physx.sim.spawners.materials.PhysxRigidBodyMaterialCfg.compliant_contact_stiffness`, - :attr:`compliant_contact_damping`, :attr:`friction_combine_mode`, and - :attr:`restitution_combine_mode` from concrete values (``0.0``, ``0.0``, ``"average"``, - ``"average"``) to ``None``. PhysX engine defaults match the previous concrete values, so - user-observable simulation behavior is unchanged; the difference is that these attributes - are now authored on the prim only when the user explicitly sets them (consistent with the - rest of the consumption-gated cfg layer). -* Relocated :class:`RigidBodyMaterialCfg` to :mod:`isaaclab_physx.sim.spawners.materials` and - split its fields between the new :class:`~isaaclab.sim.spawners.materials.RigidBodyMaterialBaseCfg` - (UsdPhysics-standard friction/restitution) and - :class:`~isaaclab_physx.sim.spawners.materials.PhysxRigidBodyMaterialCfg` - (PhysX-specific compliant-contact and combine-mode fields). A forwarding shim on - :mod:`isaaclab.sim.spawners.materials` and :mod:`isaaclab.sim` preserves existing imports. -* Refactored :func:`~isaaclab.sim.spawners.materials.spawn_rigid_body_material` to be - metadata-driven: it reads ``_usd_applied_schema``, ``_usd_namespace``, and - ``_usd_attr_name_map`` from the cfg class and gates ``PhysxMaterialAPI`` application on - whether the user authored at least one PhysX-namespaced field with a non-``None`` value. - Previously, the writer applied ``PhysxMaterialAPI`` unconditionally on every material spawn. -* Relocated :class:`CollisionPropertiesCfg` to :mod:`isaaclab_physx.sim.schemas` and split - its fields between the new :class:`~isaaclab.sim.schemas.CollisionBaseCfg` (solver-common - ``collision_enabled`` plus the PhysX-namespaced but Newton-consumed - ``contact_offset`` / ``rest_offset``) and - :class:`~isaaclab_physx.sim.schemas.PhysxCollisionPropertiesCfg` (PhysX-only - ``torsional_patch_radius`` / ``min_torsional_patch_radius``). A forwarding shim on - :mod:`isaaclab.sim.schemas`, :mod:`isaaclab.sim.schemas.schemas_cfg`, and - :mod:`isaaclab.sim` preserves existing imports. -* Refactored :func:`~isaaclab.sim.schemas.modify_collision_properties` to be metadata-driven - and to gate ``PhysxCollisionAPI`` application on whether the user authored at least one - PhysX-namespaced field with a non-``None`` value. Previously, the writer applied - ``PhysxCollisionAPI`` unconditionally on every collision prim, stamping the schema onto - Newton-targeted prims that only set ``collision_enabled``. -* Relocated :class:`ArticulationRootPropertiesCfg` to :mod:`isaaclab_physx.sim.schemas` and - split its fields between the new :class:`~isaaclab.sim.schemas.ArticulationRootBaseCfg` - (solver-common ``fix_root_link`` plus the PhysX-namespaced ``articulation_enabled`` which - is consumed by the IL Newton wrapper as a spawn-time guard) and - :class:`~isaaclab_physx.sim.schemas.PhysxArticulationRootPropertiesCfg` - (``enabled_self_collisions`` and PhysX TGS solver iter / sleep / stabilization thresholds). - A forwarding shim on :mod:`isaaclab.sim.schemas`, - :mod:`isaaclab.sim.schemas.schemas_cfg`, and :mod:`isaaclab.sim` preserves existing imports. -* Refactored :func:`~isaaclab.sim.schemas.modify_articulation_root_properties` to be - metadata-driven and to gate ``PhysxArticulationAPI`` application on whether the user - authored at least one PhysX-namespaced field with a non-``None`` value. Previously, the - writer applied ``PhysxArticulationAPI`` unconditionally on every articulation root, - stamping the schema onto Newton-targeted prims that only set ``fix_root_link``. -* Relocated :class:`MeshCollisionPropertiesCfg`, :class:`ConvexHullPropertiesCfg`, - :class:`ConvexDecompositionPropertiesCfg`, :class:`TriangleMeshPropertiesCfg`, - :class:`TriangleMeshSimplificationPropertiesCfg`, and :class:`SDFMeshPropertiesCfg` to - :mod:`isaaclab_physx.sim.schemas`. :class:`BoundingCubePropertiesCfg` and - :class:`BoundingSpherePropertiesCfg` stay in core because they author no PhysX schema. - A forwarding shim preserves existing imports. -* Refactored :func:`~isaaclab.sim.schemas.modify_mesh_collision_properties` to be - metadata-driven. The writer now reads ``_usd_applied_schema`` and ``_usd_namespace`` from - the cfg class instead of consulting instance-level ``usd_api`` / ``physx_api`` fields. - The standard :class:`UsdPhysics.MeshCollisionAPI` is always applied; PhysX cooking - schemas (``PhysxConvexHullCollisionAPI`` etc.) are gated on at least one - PhysX-namespaced tuning field being set. -* Relocated :class:`FixedTendonPropertiesCfg` and :class:`SpatialTendonPropertiesCfg` to - :mod:`isaaclab_physx.sim.schemas` as :class:`PhysxFixedTendonPropertiesCfg` and - :class:`PhysxSpatialTendonPropertiesCfg`. Tendons are a PhysX-only feature; no Newton - equivalent exists. A forwarding shim on :mod:`isaaclab.sim.schemas`, - :mod:`isaaclab.sim.schemas.schemas_cfg`, and :mod:`isaaclab.sim` preserves existing - imports. - -Deprecated -^^^^^^^^^^ - -* Deprecated the ``usd_api`` and ``physx_api`` instance attributes on the mesh-collision - cfg classes in favor of class-level ``_usd_applied_schema`` metadata. Reading these - attributes still works through one minor version but emits a ``DeprecationWarning``. - Scheduled for removal in 5.0. - -Fixed -^^^^^ - -* Fixed :meth:`~isaaclab.sim.schemas.modify_joint_drive_properties` and - :meth:`~isaaclab.sim.schemas.modify_rigid_body_properties` so that ``PhysxJointAPI`` and - ``PhysxRigidBodyAPI`` are applied only when the user authored at least one PhysX-namespaced - field with a non-``None`` value. Previously, schema application was gated on class-level - metadata being defined, which caused Newton-targeted prims to receive PhysX schemas even - when the user only set base ``UsdPhysics``-standard fields. diff --git a/source/isaaclab/config/extension.toml b/source/isaaclab/config/extension.toml index 95993d71590f..e1620d629745 100644 --- a/source/isaaclab/config/extension.toml +++ b/source/isaaclab/config/extension.toml @@ -1,7 +1,7 @@ [package] # Note: Semantic Versioning is used: https://semver.org/ -version = "4.6.28" +version = "4.7.0" # Description title = "Isaac Lab framework for Robot Learning" diff --git a/source/isaaclab/docs/CHANGELOG.rst b/source/isaaclab/docs/CHANGELOG.rst index 701f53744f84..1bb6a29060fa 100644 --- a/source/isaaclab/docs/CHANGELOG.rst +++ b/source/isaaclab/docs/CHANGELOG.rst @@ -1,6 +1,251 @@ Changelog --------- +4.7.0 (2026-05-08) +~~~~~~~~~~~~~~~~~~ + +Added +^^^^^ + +* Added LEAPP export support for manager-based RSL-RL policies, including + export-time observation/action annotation, recurrent actor-state handling, and + deployment through :mod:`scripts.reinforcement_learning.leapp.deploy`. +* Added a Direct workflow LEAPP export tutorial and annotated ANYmal-C example + script showing how to mark policy inputs, outputs, and persistent state with + LEAPP annotations. Direct workflow policies can be exported with + :mod:`scripts.reinforcement_learning.leapp.rsl_rl.export`, but are not yet + supported by :mod:`scripts.reinforcement_learning.leapp.deploy`. +* Added LEAPP deployment documentation describing the exported-policy validation + flow and linking the manager-based and Direct workflow export paths. +* Added LEAPP export annotations, proxy utilities, and deployment environment + support for Isaac Lab assets, sensors, commands, and manager-based environments. +* Added :class:`~isaaclab.renderers.camera_render_spec.CameraRenderSpec` so render backends + take explicit camera inputs (USD paths, :class:`~isaaclab.sensors.camera.CameraCfg`, device, + counts) instead of the :class:`~isaaclab.sensors.camera.Camera` instance. +* Added :class:`~isaaclab.renderers.render_context.RenderContext` (accessed as + :attr:`~isaaclab.sim.simulation_context.SimulationContext.render_context`) to own one or + more :class:`~isaaclab.renderers.base_renderer.BaseRenderer` instances: configurations that + compare equal under ``==`` and share the same concrete + :class:`~isaaclab.renderers.renderer_cfg.RendererCfg` class reuse a backend; distinct + types (e.g. Isaac RTX and Newton) register separate backends, each with + :meth:`~isaaclab.renderers.base_renderer.BaseRenderer.prepare_stage` the first time a camera + with that configuration initializes. +* Added :meth:`~isaaclab.renderers.render_context.RenderContext.render_into_camera` to run + :meth:`~isaaclab.renderers.render_context.RenderContext.update_transforms` (at most once + per physics step), then :meth:`~isaaclab.renderers.base_renderer.BaseRenderer.render` and + :meth:`~isaaclab.renderers.base_renderer.BaseRenderer.read_output`. +* Added :meth:`~isaaclab.sim.simulation_context.SimulationContext.get_physics_step_count`. +* Added :class:`~isaaclab.cloner.ClonePlan` frozen dataclass capturing per-group + prototype-to-environment mappings (``dest_template``, ``prototype_paths``, + ``clone_mask``). Lets downstream consumers (scene data providers, mesh samplers) + read prototype geometry once and scatter to environments via the per-group mask + instead of walking per-env USD paths. +* Added :meth:`~isaaclab.sim.SimulationContext.get_clone_plans` and + :meth:`~isaaclab.sim.SimulationContext.set_clone_plans` for publishing and + consuming the cloner's per-group plan map. +* Added :attr:`~isaaclab.scene.InteractiveScene.clone_plans` property (forwards to + :meth:`~isaaclab.sim.SimulationContext.get_clone_plans`) so consumers holding a + scene reference can read the published plans without going through the sim + context. +* Added backend-agnostic :class:`~isaaclab.markers.VisualizationMarkers` support for + marker-capable Kit, Newton, Rerun, and Viser visualizers. +* Added :meth:`~isaaclab.utils.backend_utils.get_default_renderer_cfg`. to lazy load the IsaacRtxRendererCfg +* Added :class:`~isaaclab.sim.spawners.materials.RigidBodyMaterialBaseCfg`, the solver-common + base class for rigid-body physics materials. Carries the ``UsdPhysics.MaterialAPI`` standard + fields (``static_friction``, ``dynamic_friction``, ``restitution``). The PhysX-specific + compliant-contact and combine-mode fields moved to + :class:`~isaaclab_physx.sim.spawners.materials.PhysxRigidBodyMaterialCfg`. +* Added :class:`~isaaclab.sim.schemas.CollisionBaseCfg`, the solver-common base class for + collision properties. Carries :attr:`collision_enabled` (``UsdPhysics.CollisionAPI``) plus + :attr:`contact_offset` and :attr:`rest_offset` whose USD attributes are PhysX-namespaced + but are consumed by Newton's importer via the PhysX bridge resolver + (``import_usd.py:2104, 2111``). +* Added :class:`~isaaclab.sim.schemas.ArticulationRootBaseCfg`, the solver-common base class + for articulation root properties (``fix_root_link``, ``articulation_enabled``). +* Added :class:`~isaaclab.sim.schemas.MeshCollisionBaseCfg`, the solver-common base class for + mesh collision properties carrying ``mesh_approximation_name`` (writes + ``physics:approximation`` via :class:`UsdPhysics.MeshCollisionAPI`). The class-level + ``_usd_applied_schema`` metadata replaces the deprecated ``usd_api`` / ``physx_api`` + instance-field dispatch. + +Changed +^^^^^^^ + +* :class:`~isaaclab.sensors.camera.Camera` obtains a backend via + :meth:`~isaaclab.renderers.render_context.RenderContext.get_renderer` and calls + :meth:`~isaaclab.renderers.base_renderer.BaseRenderer.create_render_data` with + a :class:`~isaaclab.renderers.camera_render_spec.CameraRenderSpec` (no + :class:`~isaaclab.sensors.sensor_base.SensorBase` reference on the public API). +* :class:`~isaaclab.scene.interactive_scene.InteractiveScene` calls + :meth:`~isaaclab.renderers.render_context.RenderContext.update_transforms` once at the start + of :meth:`~isaaclab.scene.interactive_scene.InteractiveScene.update` when + ``lazy_sensor_update`` is false; fetches that render still dedupe the same way via + ``physics_step_count`` in :class:`~isaaclab.renderers.render_context.RenderContext`. +* **Breaking:** :func:`~isaaclab.cloner.clone_from_template` now returns + ``dict[str, ClonePlan]`` instead of ``None``. Bind the result and publish it + through :meth:`~isaaclab.sim.SimulationContext.set_clone_plans` if downstream + consumers (e.g. the PhysX scene data provider's Newton-visualizer build path) + need to read the plan. +* Changed :func:`~isaaclab.envs.mdp.body_incoming_wrench` to read from + :class:`~isaaclab.sensors.JointWrenchSensor`. Pass + ``sensor_cfg=SceneEntityCfg("joint_wrench", body_names=...)`` instead of an + articulation asset config. +* Updated :class:`~isaaclab.sensors.camera.Camera` to construct its internal + :class:`~isaaclab.sim.views.FrameView` without the now-removed + ``sync_usd_on_fabric_write`` kwarg. USD attributes on camera prims are + no longer kept in sync with Fabric writes; read poses through the view's + getters instead. +* :class:`~isaaclab.sensors.camera.CameraCfg` now defaults its render_cfg to :class:`~isaaclab.renderers.RenderCfg` + :meth:`~isaaclab.utils.backend_utils.get_default_renderer_cfg` is called during __post_init__ to replace + the generic RenderCfg with the default config :class:`~isaaclab_physx.renderers.IsaacRtxRendererCfg` +* Cleaned up the schema-cfg base classes to no longer carry PhysX namespace metadata. + :class:`~isaaclab.sim.schemas.RigidBodyBaseCfg`, + :class:`~isaaclab.sim.schemas.CollisionBaseCfg`, + :class:`~isaaclab.sim.schemas.ArticulationRootBaseCfg`, and + :class:`~isaaclab.sim.schemas.JointDriveBaseCfg` now declare ``_usd_namespace = None`` and + ``_usd_applied_schema = None``. Per-field PhysX overrides for fields whose only USD path + today is the ``physx*:*`` namespace (``disable_gravity``, ``contact_offset``, + ``rest_offset``, ``articulation_enabled``, ``max_velocity``) are declared via a new + ``_usd_field_exceptions`` mapping ``applied_schema -> (namespace, {cfg_field: usd_attr})``. + When any listed field is non-None at write time, the writer applies that schema and writes + the attribute under the exception namespace; otherwise the schema is not stamped onto the + prim. PhysX subclasses (:class:`PhysxRigidBodyPropertiesCfg`, + :class:`PhysxCollisionPropertiesCfg`, :class:`PhysxArticulationRootPropertiesCfg`, + :class:`PhysxJointDrivePropertiesCfg`) now self-declare ``_usd_namespace`` and + ``_usd_applied_schema`` for their own fields. Observable behavior on standard inputs is + unchanged. +* Consolidated the per-writer schema-application loop in + :mod:`isaaclab.sim.schemas` into a single shared helper ``_apply_namespaced_schemas``. + ``modify_articulation_root_properties``, ``modify_rigid_body_properties``, + ``modify_collision_properties``, ``modify_joint_drive_properties``, + ``modify_mesh_collision_properties``, and ``spawn_rigid_body_material`` all delegate to the + helper after writing their typed-API ``UsdPhysics`` fields. The canonical exception-table + + main-namespace gating logic now lives in one place instead of being duplicated across + six call sites. +* Moved the ``max_velocity`` field from :class:`~isaaclab_physx.sim.schemas.PhysxJointDrivePropertiesCfg` + to :class:`~isaaclab.sim.schemas.JointDriveBaseCfg`. The field is the only USD path to set + Newton's ``Model.joint_velocity_limit`` and is consumed by Newton's importer. The USD + attribute written is unchanged (``physxJoint:maxJointVelocity``); existing code using + ``PhysxJointDrivePropertiesCfg(max_velocity=...)`` continues to work because the field + is inherited. +* Moved the ``disable_gravity`` field from :class:`~isaaclab_physx.sim.schemas.PhysxRigidBodyPropertiesCfg` + to :class:`~isaaclab.sim.schemas.RigidBodyBaseCfg`. PhysX honors per-body via + ``physxRigidBody:disableGravity``; Newton currently honors at scene level (partial), + documented in the field docstring. Existing code using + ``PhysxRigidBodyPropertiesCfg(disable_gravity=...)`` continues to work via inheritance. +* Documented :attr:`~isaaclab.sim.schemas.ArticulationRootPropertiesCfg.articulation_enabled` + and :attr:`~isaaclab.sim.schemas.ArticulationRootPropertiesCfg.enabled_self_collisions` + to lock their placement for the future :class:`ArticulationRootBaseCfg` / + ``PhysxArticulationRootPropertiesCfg`` split: ``articulation_enabled`` stays on the base + (single-namespace USD with verified Newton consumer); ``enabled_self_collisions`` moves + to the PhysX subclass (dual-namespace USD, with a future Newton sibling cfg owning the + ``newton:*`` namespace). +* Changed the defaults of :attr:`~isaaclab_physx.sim.spawners.materials.PhysxRigidBodyMaterialCfg.compliant_contact_stiffness`, + :attr:`compliant_contact_damping`, :attr:`friction_combine_mode`, and + :attr:`restitution_combine_mode` from concrete values (``0.0``, ``0.0``, ``"average"``, + ``"average"``) to ``None``. PhysX engine defaults match the previous concrete values, so + user-observable simulation behavior is unchanged; the difference is that these attributes + are now authored on the prim only when the user explicitly sets them (consistent with the + rest of the consumption-gated cfg layer). +* Relocated :class:`RigidBodyMaterialCfg` to :mod:`isaaclab_physx.sim.spawners.materials` and + split its fields between the new :class:`~isaaclab.sim.spawners.materials.RigidBodyMaterialBaseCfg` + (UsdPhysics-standard friction/restitution) and + :class:`~isaaclab_physx.sim.spawners.materials.PhysxRigidBodyMaterialCfg` + (PhysX-specific compliant-contact and combine-mode fields). A forwarding shim on + :mod:`isaaclab.sim.spawners.materials` and :mod:`isaaclab.sim` preserves existing imports. +* Refactored :func:`~isaaclab.sim.spawners.materials.spawn_rigid_body_material` to be + metadata-driven: it reads ``_usd_applied_schema``, ``_usd_namespace``, and + ``_usd_attr_name_map`` from the cfg class and gates ``PhysxMaterialAPI`` application on + whether the user authored at least one PhysX-namespaced field with a non-``None`` value. + Previously, the writer applied ``PhysxMaterialAPI`` unconditionally on every material spawn. +* Relocated :class:`CollisionPropertiesCfg` to :mod:`isaaclab_physx.sim.schemas` and split + its fields between the new :class:`~isaaclab.sim.schemas.CollisionBaseCfg` (solver-common + ``collision_enabled`` plus the PhysX-namespaced but Newton-consumed + ``contact_offset`` / ``rest_offset``) and + :class:`~isaaclab_physx.sim.schemas.PhysxCollisionPropertiesCfg` (PhysX-only + ``torsional_patch_radius`` / ``min_torsional_patch_radius``). A forwarding shim on + :mod:`isaaclab.sim.schemas`, :mod:`isaaclab.sim.schemas.schemas_cfg`, and + :mod:`isaaclab.sim` preserves existing imports. +* Refactored :func:`~isaaclab.sim.schemas.modify_collision_properties` to be metadata-driven + and to gate ``PhysxCollisionAPI`` application on whether the user authored at least one + PhysX-namespaced field with a non-``None`` value. Previously, the writer applied + ``PhysxCollisionAPI`` unconditionally on every collision prim, stamping the schema onto + Newton-targeted prims that only set ``collision_enabled``. +* Relocated :class:`ArticulationRootPropertiesCfg` to :mod:`isaaclab_physx.sim.schemas` and + split its fields between the new :class:`~isaaclab.sim.schemas.ArticulationRootBaseCfg` + (solver-common ``fix_root_link`` plus the PhysX-namespaced ``articulation_enabled`` which + is consumed by the IL Newton wrapper as a spawn-time guard) and + :class:`~isaaclab_physx.sim.schemas.PhysxArticulationRootPropertiesCfg` + (``enabled_self_collisions`` and PhysX TGS solver iter / sleep / stabilization thresholds). + A forwarding shim on :mod:`isaaclab.sim.schemas`, + :mod:`isaaclab.sim.schemas.schemas_cfg`, and :mod:`isaaclab.sim` preserves existing imports. +* Refactored :func:`~isaaclab.sim.schemas.modify_articulation_root_properties` to be + metadata-driven and to gate ``PhysxArticulationAPI`` application on whether the user + authored at least one PhysX-namespaced field with a non-``None`` value. Previously, the + writer applied ``PhysxArticulationAPI`` unconditionally on every articulation root, + stamping the schema onto Newton-targeted prims that only set ``fix_root_link``. +* Relocated :class:`MeshCollisionPropertiesCfg`, :class:`ConvexHullPropertiesCfg`, + :class:`ConvexDecompositionPropertiesCfg`, :class:`TriangleMeshPropertiesCfg`, + :class:`TriangleMeshSimplificationPropertiesCfg`, and :class:`SDFMeshPropertiesCfg` to + :mod:`isaaclab_physx.sim.schemas`. :class:`BoundingCubePropertiesCfg` and + :class:`BoundingSpherePropertiesCfg` stay in core because they author no PhysX schema. + A forwarding shim preserves existing imports. +* Refactored :func:`~isaaclab.sim.schemas.modify_mesh_collision_properties` to be + metadata-driven. The writer now reads ``_usd_applied_schema`` and ``_usd_namespace`` from + the cfg class instead of consulting instance-level ``usd_api`` / ``physx_api`` fields. + The standard :class:`UsdPhysics.MeshCollisionAPI` is always applied; PhysX cooking + schemas (``PhysxConvexHullCollisionAPI`` etc.) are gated on at least one + PhysX-namespaced tuning field being set. +* Relocated :class:`FixedTendonPropertiesCfg` and :class:`SpatialTendonPropertiesCfg` to + :mod:`isaaclab_physx.sim.schemas` as :class:`PhysxFixedTendonPropertiesCfg` and + :class:`PhysxSpatialTendonPropertiesCfg`. Tendons are a PhysX-only feature; no Newton + equivalent exists. A forwarding shim on :mod:`isaaclab.sim.schemas`, + :mod:`isaaclab.sim.schemas.schemas_cfg`, and :mod:`isaaclab.sim` preserves existing + imports. + +Deprecated +^^^^^^^^^^ + +* Deprecated the ``usd_api`` and ``physx_api`` instance attributes on the mesh-collision + cfg classes in favor of class-level ``_usd_applied_schema`` metadata. Reading these + attributes still works through one minor version but emits a ``DeprecationWarning``. + Scheduled for removal in 5.0. + +Removed +^^^^^^^ + +* **Breaking:** Removed + :attr:`~isaaclab.cloner.TemplateCloneCfg.visualizer_clone_fn`, + :func:`~isaaclab.cloner.resolve_visualizer_clone_fn`, and + :class:`~isaaclab.physics.scene_data_requirements.VisualizerPrebuiltArtifacts`. + Scene data providers now build backend models from the + :class:`~isaaclab.cloner.ClonePlan` map via + :meth:`~isaaclab.sim.SimulationContext.get_clone_plans` instead of receiving a + prebuilt artifact through a clone-time callback. +* **Breaking:** Removed + :meth:`~isaaclab.sim.SimulationContext.get_scene_data_visualizer_prebuilt_artifact`, + :meth:`~isaaclab.sim.SimulationContext.set_scene_data_visualizer_prebuilt_artifact`, + and + :meth:`~isaaclab.sim.SimulationContext.clear_scene_data_visualizer_prebuilt_artifact`. + Use :meth:`~isaaclab.sim.SimulationContext.get_clone_plans` / + :meth:`~isaaclab.sim.SimulationContext.set_clone_plans` instead. +* Removed ``BaseArticulationData.body_incoming_joint_wrench_b``. Add + :class:`~isaaclab.sensors.JointWrenchSensorCfg` to the scene and read + :attr:`~isaaclab.sensors.JointWrenchSensorData.force` and + :attr:`~isaaclab.sensors.JointWrenchSensorData.torque` instead. + +Fixed +^^^^^ + +* Pinned ``omniverseclient`` to ``2.71.1.7015``. +* Fixed :meth:`~isaaclab.sim.schemas.modify_joint_drive_properties` and + :meth:`~isaaclab.sim.schemas.modify_rigid_body_properties` so that ``PhysxJointAPI`` and + ``PhysxRigidBodyAPI`` are applied only when the user authored at least one PhysX-namespaced + field with a non-``None`` value. Previously, schema application was gated on class-level + metadata being defined, which caused Newton-targeted prims to receive PhysX schemas even + when the user only set base ``UsdPhysics``-standard fields. + + 4.6.27 (2026-05-01) ~~~~~~~~~~~~~~~~~~~ diff --git a/source/isaaclab_newton/changelog.d/clone-plan-visualizer-cleanup.minor.rst b/source/isaaclab_newton/changelog.d/clone-plan-visualizer-cleanup.minor.rst deleted file mode 100644 index 6fed4677a471..000000000000 --- a/source/isaaclab_newton/changelog.d/clone-plan-visualizer-cleanup.minor.rst +++ /dev/null @@ -1,9 +0,0 @@ -Removed -^^^^^^^ - -* **Breaking:** Removed - ``isaaclab_newton.cloner.newton_replicate.create_newton_visualizer_prebuild_clone_fn``. - Callers that need a Newton model for visualization should call - :func:`~isaaclab_newton.cloner.newton_replicate.newton_visualizer_prebuild` - directly with the ``(sources, destinations, env_ids, mask, positions)`` bundle - derived from :meth:`~isaaclab.sim.SimulationContext.get_clone_plans`. diff --git a/source/isaaclab_newton/changelog.d/mtrepte-expand_viz_markers.skip b/source/isaaclab_newton/changelog.d/mtrepte-expand_viz_markers.skip deleted file mode 100644 index a23b7c7322b3..000000000000 --- a/source/isaaclab_newton/changelog.d/mtrepte-expand_viz_markers.skip +++ /dev/null @@ -1 +0,0 @@ -Marker visualization changes are covered by the isaaclab fragment. diff --git a/source/isaaclab_newton/changelog.d/mym-newton-manager-abstraction.rst b/source/isaaclab_newton/changelog.d/mym-newton-manager-abstraction.rst deleted file mode 100644 index 1ad8a9265830..000000000000 --- a/source/isaaclab_newton/changelog.d/mym-newton-manager-abstraction.rst +++ /dev/null @@ -1,14 +0,0 @@ -Changed -^^^^^^^ - -* Changed :class:`~isaaclab_newton.physics.NewtonManager` to dispatch through - solver-specific manager subclasses while preserving the existing - ``NewtonCfg(solver_cfg=...)`` configuration pattern. - -Deprecated -^^^^^^^^^^ - -* Deprecated :attr:`~isaaclab_newton.physics.NewtonSolverCfg.solver_type` for - manager dispatch in favor of - :attr:`~isaaclab_newton.physics.NewtonSolverCfg.class_type`. Existing configs - remain valid, but new code should rely on ``class_type``. diff --git a/source/isaaclab_newton/changelog.d/pr-5458-merge-develop.rst b/source/isaaclab_newton/changelog.d/pr-5458-merge-develop.rst deleted file mode 100644 index 30eb959531c2..000000000000 --- a/source/isaaclab_newton/changelog.d/pr-5458-merge-develop.rst +++ /dev/null @@ -1,13 +0,0 @@ -Removed -^^^^^^^ - -* Removed the unimplemented ``ArticulationData.body_incoming_joint_wrench_b`` - accessor. Add :class:`~isaaclab.sensors.JointWrenchSensorCfg` to the scene - and read :attr:`~isaaclab.sensors.JointWrenchSensorData.force` and - :attr:`~isaaclab.sensors.JointWrenchSensorData.torque` instead. - -Fixed -^^^^^ - -* Fixed :class:`~isaaclab_newton.sensors.JointWrenchSensor` initialization for - USD assets whose articulation root is nested below the configured asset prim. diff --git a/source/isaaclab_newton/changelog.d/rschmitt_decouple_rednerer_camera.rst b/source/isaaclab_newton/changelog.d/rschmitt_decouple_rednerer_camera.rst deleted file mode 100644 index 1c3efcb5c33e..000000000000 --- a/source/isaaclab_newton/changelog.d/rschmitt_decouple_rednerer_camera.rst +++ /dev/null @@ -1,4 +0,0 @@ -Changed -^^^^^^^^ - -* Modified the newton renderer to use the new patterns from renderer/camera decoupling. diff --git a/source/isaaclab_newton/changelog.d/vidur-feature-usd-proprties-refactor.skip b/source/isaaclab_newton/changelog.d/vidur-feature-usd-proprties-refactor.skip deleted file mode 100644 index e69de29bb2d1..000000000000 diff --git a/source/isaaclab_newton/config/extension.toml b/source/isaaclab_newton/config/extension.toml index 0a8eed8000c2..4837c3f7ae03 100644 --- a/source/isaaclab_newton/config/extension.toml +++ b/source/isaaclab_newton/config/extension.toml @@ -1,7 +1,7 @@ [package] # Note: Semantic Versioning is used: https://semver.org/ -version = "0.5.26" +version = "0.6.0" # Description title = "Newton simulation interfaces for IsaacLab core package" diff --git a/source/isaaclab_newton/docs/CHANGELOG.rst b/source/isaaclab_newton/docs/CHANGELOG.rst index d9626a890476..0f81a9effc43 100644 --- a/source/isaaclab_newton/docs/CHANGELOG.rst +++ b/source/isaaclab_newton/docs/CHANGELOG.rst @@ -1,6 +1,46 @@ Changelog --------- +0.6.0 (2026-05-08) +~~~~~~~~~~~~~~~~~~ + +Changed +^^^^^^^ + +* Modified the newton renderer to use the new patterns from renderer/camera decoupling. +* Changed :class:`~isaaclab_newton.physics.NewtonManager` to dispatch through + solver-specific manager subclasses while preserving the existing + ``NewtonCfg(solver_cfg=...)`` configuration pattern. + +Deprecated +^^^^^^^^^^ + +* Deprecated :attr:`~isaaclab_newton.physics.NewtonSolverCfg.solver_type` for + manager dispatch in favor of + :attr:`~isaaclab_newton.physics.NewtonSolverCfg.class_type`. Existing configs + remain valid, but new code should rely on ``class_type``. + +Removed +^^^^^^^ + +* **Breaking:** Removed + ``isaaclab_newton.cloner.newton_replicate.create_newton_visualizer_prebuild_clone_fn``. + Callers that need a Newton model for visualization should call + :func:`~isaaclab_newton.cloner.newton_replicate.newton_visualizer_prebuild` + directly with the ``(sources, destinations, env_ids, mask, positions)`` bundle + derived from :meth:`~isaaclab.sim.SimulationContext.get_clone_plans`. +* Removed the unimplemented ``ArticulationData.body_incoming_joint_wrench_b`` + accessor. Add :class:`~isaaclab.sensors.JointWrenchSensorCfg` to the scene + and read :attr:`~isaaclab.sensors.JointWrenchSensorData.force` and + :attr:`~isaaclab.sensors.JointWrenchSensorData.torque` instead. + +Fixed +^^^^^ + +* Fixed :class:`~isaaclab_newton.sensors.JointWrenchSensor` initialization for + USD assets whose articulation root is nested below the configured asset prim. + + 0.5.26 (2026-04-30) ~~~~~~~~~~~~~~~~~~~ diff --git a/source/isaaclab_ov/changelog.d/pbarejko-open-usd.rst b/source/isaaclab_ov/changelog.d/pbarejko-open-usd.rst deleted file mode 100644 index 455768ad5a5c..000000000000 --- a/source/isaaclab_ov/changelog.d/pbarejko-open-usd.rst +++ /dev/null @@ -1,7 +0,0 @@ -Fixed -^^^^^ - -* Fixed ``AttributeError: 'Renderer' object has no attribute 'add_usd'`` in - :class:`~isaaclab_ov.renderers.OVRTXRenderer` when using ``ovrtx`` 0.3.0 or - newer. The renderer now calls :meth:`ovrtx.Renderer.open_usd` on 0.3.0+ and - falls back to ``Renderer.add_usd`` on older versions. diff --git a/source/isaaclab_ov/changelog.d/rschmitt_decouple_renderer_camera.rst b/source/isaaclab_ov/changelog.d/rschmitt_decouple_renderer_camera.rst deleted file mode 100644 index 1de2259dc2c3..000000000000 --- a/source/isaaclab_ov/changelog.d/rschmitt_decouple_renderer_camera.rst +++ /dev/null @@ -1,4 +0,0 @@ -Changed -^^^^^^^^ - -* Modified the OVRTX renderer to use the new patterns from renderer/camera decoupling. diff --git a/source/isaaclab_ov/config/extension.toml b/source/isaaclab_ov/config/extension.toml index ba8f5046c4eb..88756787ecc1 100644 --- a/source/isaaclab_ov/config/extension.toml +++ b/source/isaaclab_ov/config/extension.toml @@ -1,5 +1,5 @@ [package] -version = "0.1.3" +version = "0.1.4" title = "Omniverse renderers for IsaacLab" description = "Extension providing Omniverse renderers (OVRTX, ovphysx, etc.) for tiled camera rendering." readme = "docs/README.md" diff --git a/source/isaaclab_ov/docs/CHANGELOG.rst b/source/isaaclab_ov/docs/CHANGELOG.rst index e8afeda30bda..9d558d295876 100644 --- a/source/isaaclab_ov/docs/CHANGELOG.rst +++ b/source/isaaclab_ov/docs/CHANGELOG.rst @@ -1,6 +1,23 @@ Changelog --------- +0.1.4 (2026-05-08) +~~~~~~~~~~~~~~~~~~ + +Changed +^^^^^^^ + +* Modified the OVRTX renderer to use the new patterns from renderer/camera decoupling. + +Fixed +^^^^^ + +* Fixed ``AttributeError: 'Renderer' object has no attribute 'add_usd'`` in + :class:`~isaaclab_ov.renderers.OVRTXRenderer` when using ``ovrtx`` 0.3.0 or + newer. The renderer now calls :meth:`ovrtx.Renderer.open_usd` on 0.3.0+ and + falls back to ``Renderer.add_usd`` on older versions. + + 0.1.3 (2026-04-30) ~~~~~~~~~~~~~~~~~~ diff --git a/source/isaaclab_ovphysx/changelog.d/pr-5458-merge-develop.rst b/source/isaaclab_ovphysx/changelog.d/pr-5458-merge-develop.rst deleted file mode 100644 index 546cb8acc1c7..000000000000 --- a/source/isaaclab_ovphysx/changelog.d/pr-5458-merge-develop.rst +++ /dev/null @@ -1,7 +0,0 @@ -Removed -^^^^^^^ - -* Removed ``ArticulationData.body_incoming_joint_wrench_b`` to match the - shared articulation data API. Code that needs incoming joint reaction - wrenches should use a backend joint-wrench sensor instead of the articulation - data object. diff --git a/source/isaaclab_ovphysx/config/extension.toml b/source/isaaclab_ovphysx/config/extension.toml index 8648b7fa9587..1e541402d828 100644 --- a/source/isaaclab_ovphysx/config/extension.toml +++ b/source/isaaclab_ovphysx/config/extension.toml @@ -1,7 +1,7 @@ [package] # Note: Semantic Versioning is used: https://semver.org/ -version = "0.1.2" +version = "0.1.3" # Description title = "OvPhysX simulation interfaces for IsaacLab core package" diff --git a/source/isaaclab_ovphysx/docs/CHANGELOG.rst b/source/isaaclab_ovphysx/docs/CHANGELOG.rst index b2eb969d7845..8eef22620a69 100644 --- a/source/isaaclab_ovphysx/docs/CHANGELOG.rst +++ b/source/isaaclab_ovphysx/docs/CHANGELOG.rst @@ -1,6 +1,18 @@ Changelog --------- +0.1.3 (2026-05-08) +~~~~~~~~~~~~~~~~~~ + +Removed +^^^^^^^ + +* Removed ``ArticulationData.body_incoming_joint_wrench_b`` to match the + shared articulation data API. Code that needs incoming joint reaction + wrenches should use a backend joint-wrench sensor instead of the articulation + data object. + + 0.1.2 (2026-04-23) ~~~~~~~~~~~~~~~~~~ diff --git a/source/isaaclab_physx/changelog.d/clone-plan-visualizer-cleanup.skip b/source/isaaclab_physx/changelog.d/clone-plan-visualizer-cleanup.skip deleted file mode 100644 index e69de29bb2d1..000000000000 diff --git a/source/isaaclab_physx/changelog.d/fix-fabric-prepare-for-reuse.rst b/source/isaaclab_physx/changelog.d/fix-fabric-prepare-for-reuse.rst deleted file mode 100644 index e7d842da72bd..000000000000 --- a/source/isaaclab_physx/changelog.d/fix-fabric-prepare-for-reuse.rst +++ /dev/null @@ -1,12 +0,0 @@ -Changed -^^^^^^^ - -* **Breaking:** Removed the ``sync_usd_on_fabric_write`` keyword argument from - :class:`~isaaclab_physx.sim.views.FabricFrameView`. Fabric writes - (``set_world_poses``, ``set_scales``) now notify the renderer via - ``PrepareForReuse()`` on the underlying ``PrimSelection`` instead of writing - back to USD, which is ~200x faster and avoids the stale USD shadow state the - old path produced. Callers passing ``sync_usd_on_fabric_write=True`` should - remove the argument; if they relied on USD reflecting Fabric writes, they - should now read Fabric poses directly via the view's getters or refresh USD - explicitly. diff --git a/source/isaaclab_physx/changelog.d/mtrepte-expand_viz_markers.skip b/source/isaaclab_physx/changelog.d/mtrepte-expand_viz_markers.skip deleted file mode 100644 index 4f6915f6b47b..000000000000 --- a/source/isaaclab_physx/changelog.d/mtrepte-expand_viz_markers.skip +++ /dev/null @@ -1,2 +0,0 @@ -Marker visualization changes are covered by the isaaclab fragment. -Marker visualization changes are covered by the isaaclab fragment. diff --git a/source/isaaclab_physx/changelog.d/pr-5458-merge-develop.rst b/source/isaaclab_physx/changelog.d/pr-5458-merge-develop.rst deleted file mode 100644 index 1fe6a600bb99..000000000000 --- a/source/isaaclab_physx/changelog.d/pr-5458-merge-develop.rst +++ /dev/null @@ -1,16 +0,0 @@ -Added -^^^^^ - -* Added :class:`~isaaclab_physx.sensors.JointWrenchSensor` for reading PhysX - incoming joint reaction wrenches as split force [N] and torque [N·m] buffers. - The sensor accepts asset prim paths whose articulation root is nested below - the configured prim and converts PhysX's native body-frame wrench to the - shared child-side joint-frame convention. - -Removed -^^^^^^^ - -* Removed ``ArticulationData.body_incoming_joint_wrench_b``. Add - :class:`~isaaclab.sensors.JointWrenchSensorCfg` to the scene and read - :attr:`~isaaclab.sensors.JointWrenchSensorData.force` and - :attr:`~isaaclab.sensors.JointWrenchSensorData.torque` instead. diff --git a/source/isaaclab_physx/changelog.d/rschmitt_decouple_renderer_camera.rst b/source/isaaclab_physx/changelog.d/rschmitt_decouple_renderer_camera.rst deleted file mode 100644 index eada0bbb809c..000000000000 --- a/source/isaaclab_physx/changelog.d/rschmitt_decouple_renderer_camera.rst +++ /dev/null @@ -1,4 +0,0 @@ -Changed -^^^^^^^^ - -* Modified the isaac rtx renderer to use the new patterns from renderer/camera decoupling. diff --git a/source/isaaclab_physx/changelog.d/test-articulation-timeout.rst b/source/isaaclab_physx/changelog.d/test-articulation-timeout.rst deleted file mode 100644 index e0c1b96870c2..000000000000 --- a/source/isaaclab_physx/changelog.d/test-articulation-timeout.rst +++ /dev/null @@ -1,6 +0,0 @@ -Fixed -^^^^^ - -* Fixed :class:`~isaaclab_physx.assets.SurfaceGripper` initialization on - non-CPU simulation backends to raise before loading the surface gripper - extension, avoiding hangs during startup. diff --git a/source/isaaclab_physx/changelog.d/vidur-rebalance-cfg-placement.minor.rst b/source/isaaclab_physx/changelog.d/vidur-rebalance-cfg-placement.minor.rst deleted file mode 100644 index 4233c5d1c720..000000000000 --- a/source/isaaclab_physx/changelog.d/vidur-rebalance-cfg-placement.minor.rst +++ /dev/null @@ -1,77 +0,0 @@ -Added -^^^^^ - -* Added :class:`PhysxRigidBodyMaterialCfg`, a subclass of - :class:`~isaaclab.sim.spawners.materials.RigidBodyMaterialBaseCfg` carrying the - ``PhysxMaterialAPI`` schema fields (``compliant_contact_stiffness``, - ``compliant_contact_damping``, ``friction_combine_mode``, ``restitution_combine_mode``). - Use this when authoring PhysX-specific material knobs; use the base class when only the - UsdPhysics-standard friction/restitution fields are needed. -* Added :class:`PhysxCollisionPropertiesCfg`, a subclass of - :class:`~isaaclab.sim.schemas.CollisionBaseCfg` carrying the PhysX-specific - ``torsional_patch_radius`` / ``min_torsional_patch_radius`` friction approximations. - These fields have no Newton equivalent. -* Added :class:`PhysxDeformableCollisionPropertiesCfg`, renaming the previous - ``PhysXCollisionPropertiesCfg`` (capital X) for clarity. Used internally by - :class:`DeformableBodyPropertiesCfg`. -* Added :class:`PhysxArticulationRootPropertiesCfg`, a subclass of - :class:`~isaaclab.sim.schemas.ArticulationRootBaseCfg` carrying the PhysX-specific - ``enabled_self_collisions``, ``solver_position_iteration_count``, - ``solver_velocity_iteration_count``, ``sleep_threshold``, ``stabilization_threshold``. -* Added :class:`PhysxConvexHullPropertiesCfg`, :class:`PhysxConvexDecompositionPropertiesCfg`, - :class:`PhysxTriangleMeshPropertiesCfg`, - :class:`PhysxTriangleMeshSimplificationPropertiesCfg`, and - :class:`PhysxSDFMeshPropertiesCfg` -- the PhysX-cooking-specific mesh collision - subclasses. Each declares its own PhysxSchema cooking API via class-level - ``_usd_applied_schema`` metadata and inherits ``mesh_approximation_name`` from - :class:`~isaaclab.sim.schemas.MeshCollisionBaseCfg`. -* Added :class:`PhysxFixedTendonPropertiesCfg` and :class:`PhysxSpatialTendonPropertiesCfg`, - the relocated PhysX-only tendon cfg classes. Same fields as the legacy core-side classes; - no field-level split. - -Changed -^^^^^^^ - -* Removed the ``max_velocity`` field and USD metadata - (``_usd_applied_schema``, ``_usd_namespace``, ``_usd_attr_name_map``) from - :class:`PhysxJointDrivePropertiesCfg`. The field moved to - :class:`~isaaclab.sim.schemas.JointDriveBaseCfg`; ``PhysxJointDrivePropertiesCfg`` - inherits it. Existing instantiations continue to work unchanged. -* Removed the ``disable_gravity`` field from :class:`PhysxRigidBodyPropertiesCfg`. - The field moved to :class:`~isaaclab.sim.schemas.RigidBodyBaseCfg`; - ``PhysxRigidBodyPropertiesCfg`` inherits it. Existing instantiations continue - to work unchanged. - -Deprecated -^^^^^^^^^^ - -* Deprecated :class:`RigidBodyMaterialCfg` in favor of - :class:`PhysxRigidBodyMaterialCfg` (PhysX-specific) or - :class:`~isaaclab.sim.spawners.materials.RigidBodyMaterialBaseCfg` (solver-common). - The legacy name remains as a concrete subclass of :class:`PhysxRigidBodyMaterialCfg` - that emits ``DeprecationWarning`` on instantiation. Scheduled for removal in 5.0. -* Deprecated :class:`CollisionPropertiesCfg` in favor of - :class:`PhysxCollisionPropertiesCfg` (PhysX-specific) or - :class:`~isaaclab.sim.schemas.CollisionBaseCfg` (solver-common). The legacy name remains - as a concrete subclass of :class:`PhysxCollisionPropertiesCfg` that emits - ``DeprecationWarning`` on instantiation. Scheduled for removal in 5.0. -* Deprecated :class:`PhysXCollisionPropertiesCfg` (capital X, deformable-body) in favor of - :class:`PhysxDeformableCollisionPropertiesCfg`. The capital-X name is preserved as a - deprecation alias (concrete subclass) and is scheduled for removal in 5.0. -* Deprecated :class:`ArticulationRootPropertiesCfg` in favor of - :class:`PhysxArticulationRootPropertiesCfg` (PhysX-specific) or - :class:`~isaaclab.sim.schemas.ArticulationRootBaseCfg` (solver-common). The legacy name - remains as a concrete subclass of :class:`PhysxArticulationRootPropertiesCfg` that emits - ``DeprecationWarning`` on instantiation. Scheduled for removal in 5.0. -* Deprecated :class:`MeshCollisionPropertiesCfg`, :class:`ConvexHullPropertiesCfg`, - :class:`ConvexDecompositionPropertiesCfg`, :class:`TriangleMeshPropertiesCfg`, - :class:`TriangleMeshSimplificationPropertiesCfg`, and :class:`SDFMeshPropertiesCfg` in - favor of :class:`~isaaclab.sim.schemas.MeshCollisionBaseCfg` or the new ``Physx*`` - subclasses. Legacy names remain as concrete subclasses that emit ``DeprecationWarning`` - on instantiation. Scheduled for removal in 5.0. -* Deprecated :class:`FixedTendonPropertiesCfg` in favor of - :class:`PhysxFixedTendonPropertiesCfg`. Legacy name remains as a concrete subclass that - emits ``DeprecationWarning`` on instantiation. Scheduled for removal in 5.0. -* Deprecated :class:`SpatialTendonPropertiesCfg` in favor of - :class:`PhysxSpatialTendonPropertiesCfg`. Legacy name remains as a concrete subclass - that emits ``DeprecationWarning`` on instantiation. Scheduled for removal in 5.0. diff --git a/source/isaaclab_physx/config/extension.toml b/source/isaaclab_physx/config/extension.toml index 5c63b0e6322f..2e6fbc7360fc 100644 --- a/source/isaaclab_physx/config/extension.toml +++ b/source/isaaclab_physx/config/extension.toml @@ -1,7 +1,7 @@ [package] # Note: Semantic Versioning is used: https://semver.org/ -version = "0.5.29" +version = "0.6.0" # Description title = "PhysX simulation interfaces for IsaacLab core package" diff --git a/source/isaaclab_physx/docs/CHANGELOG.rst b/source/isaaclab_physx/docs/CHANGELOG.rst index 14425eb74869..f99368bd5be5 100644 --- a/source/isaaclab_physx/docs/CHANGELOG.rst +++ b/source/isaaclab_physx/docs/CHANGELOG.rst @@ -1,6 +1,118 @@ Changelog --------- +0.6.0 (2026-05-08) +~~~~~~~~~~~~~~~~~~ + +Added +^^^^^ + +* Added :class:`~isaaclab_physx.sensors.JointWrenchSensor` for reading PhysX + incoming joint reaction wrenches as split force [N] and torque [N·m] buffers. + The sensor accepts asset prim paths whose articulation root is nested below + the configured prim and converts PhysX's native body-frame wrench to the + shared child-side joint-frame convention. +* Added :class:`PhysxRigidBodyMaterialCfg`, a subclass of + :class:`~isaaclab.sim.spawners.materials.RigidBodyMaterialBaseCfg` carrying the + ``PhysxMaterialAPI`` schema fields (``compliant_contact_stiffness``, + ``compliant_contact_damping``, ``friction_combine_mode``, ``restitution_combine_mode``). + Use this when authoring PhysX-specific material knobs; use the base class when only the + UsdPhysics-standard friction/restitution fields are needed. +* Added :class:`PhysxCollisionPropertiesCfg`, a subclass of + :class:`~isaaclab.sim.schemas.CollisionBaseCfg` carrying the PhysX-specific + ``torsional_patch_radius`` / ``min_torsional_patch_radius`` friction approximations. + These fields have no Newton equivalent. +* Added :class:`PhysxDeformableCollisionPropertiesCfg`, renaming the previous + ``PhysXCollisionPropertiesCfg`` (capital X) for clarity. Used internally by + :class:`DeformableBodyPropertiesCfg`. +* Added :class:`PhysxArticulationRootPropertiesCfg`, a subclass of + :class:`~isaaclab.sim.schemas.ArticulationRootBaseCfg` carrying the PhysX-specific + ``enabled_self_collisions``, ``solver_position_iteration_count``, + ``solver_velocity_iteration_count``, ``sleep_threshold``, ``stabilization_threshold``. +* Added :class:`PhysxConvexHullPropertiesCfg`, :class:`PhysxConvexDecompositionPropertiesCfg`, + :class:`PhysxTriangleMeshPropertiesCfg`, + :class:`PhysxTriangleMeshSimplificationPropertiesCfg`, and + :class:`PhysxSDFMeshPropertiesCfg` -- the PhysX-cooking-specific mesh collision + subclasses. Each declares its own PhysxSchema cooking API via class-level + ``_usd_applied_schema`` metadata and inherits ``mesh_approximation_name`` from + :class:`~isaaclab.sim.schemas.MeshCollisionBaseCfg`. +* Added :class:`PhysxFixedTendonPropertiesCfg` and :class:`PhysxSpatialTendonPropertiesCfg`, + the relocated PhysX-only tendon cfg classes. Same fields as the legacy core-side classes; + no field-level split. + +Changed +^^^^^^^ + +* Modified the isaac rtx renderer to use the new patterns from renderer/camera decoupling. +* **Breaking:** Removed the ``sync_usd_on_fabric_write`` keyword argument from + :class:`~isaaclab_physx.sim.views.FabricFrameView`. Fabric writes + (``set_world_poses``, ``set_scales``) now notify the renderer via + ``PrepareForReuse()`` on the underlying ``PrimSelection`` instead of writing + back to USD, which is ~200x faster and avoids the stale USD shadow state the + old path produced. Callers passing ``sync_usd_on_fabric_write=True`` should + remove the argument; if they relied on USD reflecting Fabric writes, they + should now read Fabric poses directly via the view's getters or refresh USD + explicitly. +* Removed the ``max_velocity`` field and USD metadata + (``_usd_applied_schema``, ``_usd_namespace``, ``_usd_attr_name_map``) from + :class:`PhysxJointDrivePropertiesCfg`. The field moved to + :class:`~isaaclab.sim.schemas.JointDriveBaseCfg`; ``PhysxJointDrivePropertiesCfg`` + inherits it. Existing instantiations continue to work unchanged. +* Removed the ``disable_gravity`` field from :class:`PhysxRigidBodyPropertiesCfg`. + The field moved to :class:`~isaaclab.sim.schemas.RigidBodyBaseCfg`; + ``PhysxRigidBodyPropertiesCfg`` inherits it. Existing instantiations continue + to work unchanged. + +Deprecated +^^^^^^^^^^ + +* Deprecated :class:`RigidBodyMaterialCfg` in favor of + :class:`PhysxRigidBodyMaterialCfg` (PhysX-specific) or + :class:`~isaaclab.sim.spawners.materials.RigidBodyMaterialBaseCfg` (solver-common). + The legacy name remains as a concrete subclass of :class:`PhysxRigidBodyMaterialCfg` + that emits ``DeprecationWarning`` on instantiation. Scheduled for removal in 5.0. +* Deprecated :class:`CollisionPropertiesCfg` in favor of + :class:`PhysxCollisionPropertiesCfg` (PhysX-specific) or + :class:`~isaaclab.sim.schemas.CollisionBaseCfg` (solver-common). The legacy name remains + as a concrete subclass of :class:`PhysxCollisionPropertiesCfg` that emits + ``DeprecationWarning`` on instantiation. Scheduled for removal in 5.0. +* Deprecated :class:`PhysXCollisionPropertiesCfg` (capital X, deformable-body) in favor of + :class:`PhysxDeformableCollisionPropertiesCfg`. The capital-X name is preserved as a + deprecation alias (concrete subclass) and is scheduled for removal in 5.0. +* Deprecated :class:`ArticulationRootPropertiesCfg` in favor of + :class:`PhysxArticulationRootPropertiesCfg` (PhysX-specific) or + :class:`~isaaclab.sim.schemas.ArticulationRootBaseCfg` (solver-common). The legacy name + remains as a concrete subclass of :class:`PhysxArticulationRootPropertiesCfg` that emits + ``DeprecationWarning`` on instantiation. Scheduled for removal in 5.0. +* Deprecated :class:`MeshCollisionPropertiesCfg`, :class:`ConvexHullPropertiesCfg`, + :class:`ConvexDecompositionPropertiesCfg`, :class:`TriangleMeshPropertiesCfg`, + :class:`TriangleMeshSimplificationPropertiesCfg`, and :class:`SDFMeshPropertiesCfg` in + favor of :class:`~isaaclab.sim.schemas.MeshCollisionBaseCfg` or the new ``Physx*`` + subclasses. Legacy names remain as concrete subclasses that emit ``DeprecationWarning`` + on instantiation. Scheduled for removal in 5.0. +* Deprecated :class:`FixedTendonPropertiesCfg` in favor of + :class:`PhysxFixedTendonPropertiesCfg`. Legacy name remains as a concrete subclass that + emits ``DeprecationWarning`` on instantiation. Scheduled for removal in 5.0. +* Deprecated :class:`SpatialTendonPropertiesCfg` in favor of + :class:`PhysxSpatialTendonPropertiesCfg`. Legacy name remains as a concrete subclass + that emits ``DeprecationWarning`` on instantiation. Scheduled for removal in 5.0. + +Removed +^^^^^^^ + +* Removed ``ArticulationData.body_incoming_joint_wrench_b``. Add + :class:`~isaaclab.sensors.JointWrenchSensorCfg` to the scene and read + :attr:`~isaaclab.sensors.JointWrenchSensorData.force` and + :attr:`~isaaclab.sensors.JointWrenchSensorData.torque` instead. + +Fixed +^^^^^ + +* Fixed :class:`~isaaclab_physx.assets.SurfaceGripper` initialization on + non-CPU simulation backends to raise before loading the surface gripper + extension, avoiding hangs during startup. + + 0.5.29 (2026-04-30) ~~~~~~~~~~~~~~~~~~~ diff --git a/source/isaaclab_rl/changelog.d/leapp_export_integration.rst b/source/isaaclab_rl/changelog.d/leapp_export_integration.rst deleted file mode 100644 index 8a9a65b18d7f..000000000000 --- a/source/isaaclab_rl/changelog.d/leapp_export_integration.rst +++ /dev/null @@ -1,5 +0,0 @@ -Added -^^^^^ - -* Added RSL-RL LEAPP export scripts and integration tests for exporting trained - policies with semantic input, output, and state annotations. diff --git a/source/isaaclab_rl/config/extension.toml b/source/isaaclab_rl/config/extension.toml index 6b5ae668f03e..df9fe2b03612 100644 --- a/source/isaaclab_rl/config/extension.toml +++ b/source/isaaclab_rl/config/extension.toml @@ -1,7 +1,7 @@ [package] # Note: Semantic Versioning is used: https://semver.org/ -version = "0.5.1" +version = "0.5.2" # Description title = "Isaac Lab RL" diff --git a/source/isaaclab_rl/docs/CHANGELOG.rst b/source/isaaclab_rl/docs/CHANGELOG.rst index 0c4c4323ced7..ad62d198ad0b 100644 --- a/source/isaaclab_rl/docs/CHANGELOG.rst +++ b/source/isaaclab_rl/docs/CHANGELOG.rst @@ -1,6 +1,16 @@ Changelog --------- +0.5.2 (2026-05-08) +~~~~~~~~~~~~~~~~~~ + +Added +^^^^^ + +* Added RSL-RL LEAPP export scripts and integration tests for exporting trained + policies with semantic input, output, and state annotations. + + 0.5.1 (2026-04-21) ~~~~~~~~~~~~~~~~~~ diff --git a/source/isaaclab_tasks/changelog.d/antoiner-rename-newton-presets.rst b/source/isaaclab_tasks/changelog.d/antoiner-rename-newton-presets.rst deleted file mode 100644 index ae311dd1071b..000000000000 --- a/source/isaaclab_tasks/changelog.d/antoiner-rename-newton-presets.rst +++ /dev/null @@ -1,25 +0,0 @@ -Changed -^^^^^^^ - -* **Breaking:** Renamed the Newton-backend solver presets to a ``newton_`` - prefix so they group together in autocomplete and read distinctly from the - Newton backend label, package, and visualizer. The change is shimmed by - deprecation aliases (see ``Deprecated`` below), but workflows that iterate - ``__dataclass_fields__`` directly or treat :exc:`FutureWarning` as an error - will need updates. Migration: rename the field in any - :class:`~isaaclab_tasks.utils.hydra.PresetCfg` subclass and update CLI - invocations (``presets=...`` and ``env.=...``): - - - ``newton`` -> ``newton_mjwarp`` - - ``kamino`` -> ``newton_kamino`` - -Deprecated -^^^^^^^^^^ - -* Deprecated the legacy ``newton`` and ``kamino`` preset names. They still - resolve to ``newton_mjwarp`` and ``newton_kamino`` respectively but emit a - :exc:`FutureWarning` and will be removed in a future release. Update CLI - overrides (``presets=newton`` -> ``presets=newton_mjwarp``; - ``presets=kamino`` -> ``presets=newton_kamino``) and any - :class:`~isaaclab_tasks.utils.hydra.PresetCfg` field declarations - (``newton: NewtonCfg = ...`` -> ``newton_mjwarp: NewtonCfg = ...``). diff --git a/source/isaaclab_tasks/changelog.d/g1-rough-terrain-wip.rst b/source/isaaclab_tasks/changelog.d/g1-rough-terrain-wip.rst deleted file mode 100644 index 9efbf82b8bf6..000000000000 --- a/source/isaaclab_tasks/changelog.d/g1-rough-terrain-wip.rst +++ /dev/null @@ -1,11 +0,0 @@ -Added -^^^^^ - -* Added Newton rough terrain support for the G1 biped locomotion velocity - env. The only engine-specific change is a ~1.7x ``max_iterations`` preset on - :class:`~isaaclab_tasks.manager_based.locomotion.velocity.config.g1.agents.rsl_rl_ppo_cfg.G1RoughPPORunnerCfg` - (Newton = 5000, PhysX = 3000). PhysX saturates near iter 3000 on both - reward (≈ +18) and episode length (≈ 980) and does not meaningfully - improve further; Newton reaches the same (reward, ep_len) quality at - iter 5000. The iteration budget is bumped rather than tuning physics - or reward terms. diff --git a/source/isaaclab_tasks/changelog.d/huidongc-flaky-mark.skip b/source/isaaclab_tasks/changelog.d/huidongc-flaky-mark.skip deleted file mode 100644 index e69de29bb2d1..000000000000 diff --git a/source/isaaclab_tasks/changelog.d/leapp_export_integration.rst b/source/isaaclab_tasks/changelog.d/leapp_export_integration.rst deleted file mode 100644 index 94a128b6416f..000000000000 --- a/source/isaaclab_tasks/changelog.d/leapp_export_integration.rst +++ /dev/null @@ -1,5 +0,0 @@ -Added -^^^^^ - -* Added LEAPP-compatible policy deployment tutorials and tracing-compatible task - observation helpers for exported policy workflows. diff --git a/source/isaaclab_tasks/changelog.d/mtrepte-expand_viz_markers.skip b/source/isaaclab_tasks/changelog.d/mtrepte-expand_viz_markers.skip deleted file mode 100644 index a23b7c7322b3..000000000000 --- a/source/isaaclab_tasks/changelog.d/mtrepte-expand_viz_markers.skip +++ /dev/null @@ -1 +0,0 @@ -Marker visualization changes are covered by the isaaclab fragment. diff --git a/source/isaaclab_tasks/changelog.d/pr-5458-merge-develop.rst b/source/isaaclab_tasks/changelog.d/pr-5458-merge-develop.rst deleted file mode 100644 index cd4dc7e674d4..000000000000 --- a/source/isaaclab_tasks/changelog.d/pr-5458-merge-develop.rst +++ /dev/null @@ -1,10 +0,0 @@ -Changed -^^^^^^^ - -* Updated classic Ant/Humanoid manager-based environments and direct in-hand - manipulation environments to read body incoming wrenches from - :class:`~isaaclab.sensors.JointWrenchSensor` instead of - ``ArticulationData.body_incoming_joint_wrench_b``. Add a - :class:`~isaaclab.sensors.JointWrenchSensorCfg` to the scene and pass its - :class:`~isaaclab.managers.SceneEntityCfg` as ``sensor_cfg``. The classic - Ant/Humanoid Newton presets now use the same wrench observations as PhysX. diff --git a/source/isaaclab_tasks/changelog.d/rendering-test-flakiness.skip b/source/isaaclab_tasks/changelog.d/rendering-test-flakiness.skip deleted file mode 100644 index e69de29bb2d1..000000000000 diff --git a/source/isaaclab_tasks/changelog.d/rwiltz-restore-legacy-teleop.rst b/source/isaaclab_tasks/changelog.d/rwiltz-restore-legacy-teleop.rst deleted file mode 100644 index 59e71ddc3984..000000000000 --- a/source/isaaclab_tasks/changelog.d/rwiltz-restore-legacy-teleop.rst +++ /dev/null @@ -1,8 +0,0 @@ -Added -^^^^^ - -* Added legacy ``teleop_devices`` configuration (``OpenXRDeviceCfg``, - ``ManusViveCfg``, ``GR1T2RetargeterCfg``) to - :class:`~isaaclab_tasks.manager_based.manipulation.pick_place.pickplace_gr1t2_env_cfg.PickPlaceGR1T2EnvCfg` - alongside the existing ``isaac_teleop`` pipeline, enabling CI validation - via ``--teleop_device=handtracking``. diff --git a/source/isaaclab_tasks/config/extension.toml b/source/isaaclab_tasks/config/extension.toml index 273ae57d2cb9..c797fcdb2cb9 100644 --- a/source/isaaclab_tasks/config/extension.toml +++ b/source/isaaclab_tasks/config/extension.toml @@ -1,7 +1,7 @@ [package] # Note: Semantic Versioning is used: https://semver.org/ -version = "1.5.34" +version = "1.5.35" # Description title = "Isaac Lab Environments" diff --git a/source/isaaclab_tasks/docs/CHANGELOG.rst b/source/isaaclab_tasks/docs/CHANGELOG.rst index 2044f807afc5..cc3f6a513120 100644 --- a/source/isaaclab_tasks/docs/CHANGELOG.rst +++ b/source/isaaclab_tasks/docs/CHANGELOG.rst @@ -1,6 +1,62 @@ Changelog --------- +1.5.35 (2026-05-08) +~~~~~~~~~~~~~~~~~~~ + +Added +^^^^^ + +* Added LEAPP-compatible policy deployment tutorials and tracing-compatible task + observation helpers for exported policy workflows. +* Added Newton rough terrain support for the G1 biped locomotion velocity + env. The only engine-specific change is a ~1.7x ``max_iterations`` preset on + :class:`~isaaclab_tasks.manager_based.locomotion.velocity.config.g1.agents.rsl_rl_ppo_cfg.G1RoughPPORunnerCfg` + (Newton = 5000, PhysX = 3000). PhysX saturates near iter 3000 on both + reward (≈ +18) and episode length (≈ 980) and does not meaningfully + improve further; Newton reaches the same (reward, ep_len) quality at + iter 5000. The iteration budget is bumped rather than tuning physics + or reward terms. +* Added legacy ``teleop_devices`` configuration (``OpenXRDeviceCfg``, + ``ManusViveCfg``, ``GR1T2RetargeterCfg``) to + :class:`~isaaclab_tasks.manager_based.manipulation.pick_place.pickplace_gr1t2_env_cfg.PickPlaceGR1T2EnvCfg` + alongside the existing ``isaac_teleop`` pipeline, enabling CI validation + via ``--teleop_device=handtracking``. + +Changed +^^^^^^^ + +* Updated classic Ant/Humanoid manager-based environments and direct in-hand + manipulation environments to read body incoming wrenches from + :class:`~isaaclab.sensors.JointWrenchSensor` instead of + ``ArticulationData.body_incoming_joint_wrench_b``. Add a + :class:`~isaaclab.sensors.JointWrenchSensorCfg` to the scene and pass its + :class:`~isaaclab.managers.SceneEntityCfg` as ``sensor_cfg``. The classic + Ant/Humanoid Newton presets now use the same wrench observations as PhysX. +* **Breaking:** Renamed the Newton-backend solver presets to a ``newton_`` + prefix so they group together in autocomplete and read distinctly from the + Newton backend label, package, and visualizer. The change is shimmed by + deprecation aliases (see ``Deprecated`` below), but workflows that iterate + ``__dataclass_fields__`` directly or treat :exc:`FutureWarning` as an error + will need updates. Migration: rename the field in any + :class:`~isaaclab_tasks.utils.hydra.PresetCfg` subclass and update CLI + invocations (``presets=...`` and ``env.=...``): + + - ``newton`` -> ``newton_mjwarp`` + - ``kamino`` -> ``newton_kamino`` + +Deprecated +^^^^^^^^^^ + +* Deprecated the legacy ``newton`` and ``kamino`` preset names. They still + resolve to ``newton_mjwarp`` and ``newton_kamino`` respectively but emit a + :exc:`FutureWarning` and will be removed in a future release. Update CLI + overrides (``presets=newton`` -> ``presets=newton_mjwarp``; + ``presets=kamino`` -> ``presets=newton_kamino``) and any + :class:`~isaaclab_tasks.utils.hydra.PresetCfg` field declarations + (``newton: NewtonCfg = ...`` -> ``newton_mjwarp: NewtonCfg = ...``). + + 1.5.34 (2026-04-30) ~~~~~~~~~~~~~~~~~~~ Added diff --git a/source/isaaclab_teleop/changelog.d/rwiltz-restore-legacy-teleop.rst b/source/isaaclab_teleop/changelog.d/rwiltz-restore-legacy-teleop.rst deleted file mode 100644 index 4c534f674c8a..000000000000 --- a/source/isaaclab_teleop/changelog.d/rwiltz-restore-legacy-teleop.rst +++ /dev/null @@ -1,11 +0,0 @@ -Changed -^^^^^^^ - -* Changed ``--teleop_device`` default to ``None`` in ``teleop_se3_agent.py`` - and ``record_demos.py``. When omitted, the IsaacTeleop pipeline is used if - the env configures ``isaac_teleop``; otherwise keyboard is used as fallback. - When explicitly provided, the scripts use the legacy ``teleop_devices`` path - and error out if no matching entry exists. -* Removed automatic ``--xr`` detection from ``--teleop_device`` containing - ``"handtracking"``. Users who need XR with the legacy path should pass - ``--xr`` explicitly. diff --git a/source/isaaclab_teleop/config/extension.toml b/source/isaaclab_teleop/config/extension.toml index 947103618b9a..48415f4bf5eb 100644 --- a/source/isaaclab_teleop/config/extension.toml +++ b/source/isaaclab_teleop/config/extension.toml @@ -1,6 +1,6 @@ [package] # Semantic Versioning is used: https://semver.org/ -version = "0.3.9" +version = "0.3.10" # Description title = "Isaac Lab Teleop" diff --git a/source/isaaclab_teleop/docs/CHANGELOG.rst b/source/isaaclab_teleop/docs/CHANGELOG.rst index 3856e6ec1346..01465486d63e 100644 --- a/source/isaaclab_teleop/docs/CHANGELOG.rst +++ b/source/isaaclab_teleop/docs/CHANGELOG.rst @@ -1,6 +1,22 @@ Changelog --------- +0.3.10 (2026-05-08) +~~~~~~~~~~~~~~~~~~~ + +Changed +^^^^^^^ + +* Changed ``--teleop_device`` default to ``None`` in ``teleop_se3_agent.py`` + and ``record_demos.py``. When omitted, the IsaacTeleop pipeline is used if + the env configures ``isaac_teleop``; otherwise keyboard is used as fallback. + When explicitly provided, the scripts use the legacy ``teleop_devices`` path + and error out if no matching entry exists. +* Removed automatic ``--xr`` detection from ``--teleop_device`` containing + ``"handtracking"``. Users who need XR with the legacy path should pass + ``--xr`` explicitly. + + 0.3.9 (2026-04-29) ~~~~~~~~~~~~~~~~~~ From 9e4e62c900c29565cb6f804d7bca7cfd64df99ed Mon Sep 17 00:00:00 2001 From: hujc Date: Thu, 7 May 2026 18:26:56 -0700 Subject: [PATCH 11/51] [Newton] Bump Newton pin to v1.2.0rc2 (#5523) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit ## Summary Bumps the Newton pin to [`v1.2.0rc2`](https://pypi.org/project/newton/1.2.0rc2/), which pulls in IsaacLab-relevant fixes plus the upstream tendon-scoping fix. ## What's new in Newton v1.2.0rc2 vs IsaacLab's current pin (`a27277e`) The current IsaacLab Newton pin is from late April; v1.2.0rc2 is the latest release-candidate cut. Notable fixes pulled in: - **[newton-physics/newton#2659](https://github.com/newton-physics/newton/pull/2659)** \"Scope USD custom-frequency parsing\" — `parse_usd` now scopes the custom-frequency walk to `root_path` natively. - **[newton-physics/newton#2678](https://github.com/newton-physics/newton/pull/2678)** Regression fix. - **[newton-physics/newton#2720](https://github.com/newton-physics/newton/pull/2720)** `SolverKamino` reset under `world_mask`. - **[newton-physics/newton#2710](https://github.com/newton-physics/newton/pull/2710)** VRAM leak fix on example reset. - Plus 16 other smaller fixes between rc1 and rc2. ## Required dep bumps Newton 1.2.0rc2's \`pyproject.toml\` requires: - \`warp-lang==1.13.0\` - \`mujoco==3.8.0\` (was 3.6.0) - \`mujoco-warp==3.8.0.1\` (was 3.6.0) Pins updated in: | File | Change | |---|---| | \`source/isaaclab/setup.py\` | \`warp-lang==1.12.0\` → \`==1.13.0\`; \`mujoco==3.6.0\` → \`==3.8.0\`; \`mujoco-warp==3.6.0\` → \`==3.8.0.1\` | | \`source/isaaclab_newton/setup.py\` | mujoco / mujoco-warp bumps; Newton pin → \`v1.2.0rc2\` | | \`source/isaaclab_visualizers/setup.py\` | 3× Newton pin → \`v1.2.0rc2\` | | \`tools/wheel_builder/res/python_packages.toml\` | All four pins mirrored | ## Code adapts \`warp-lang\` 1.13 removed the \`wp.math\` namespace. Two IsaacLab call sites use it: - \`source/isaaclab_newton/isaaclab_newton/physics/newton_manager.py:72\` - \`source/isaaclab_ov/isaaclab_ov/renderers/ovrtx_renderer_kernels.py:330\` Both rewritten as \`wp.math.transform_to_matrix(...)\` → \`wp.transform_to_matrix(...)\`. That's the only IsaacLab-side adapt needed. ## Test plan - [x] \`./isaaclab.sh -i newton\` clean install against the bumped pins. - [x] \`pip list\` confirms \`newton 1.2.0rc2\`, \`warp-lang 1.13.0\`, \`mujoco 3.8.0\`, \`mujoco-warp 3.8.0.1\`. - [x] Sanity smoke: Shadow-Hand-Over MAPPO (4 envs, 1 iter) runs clean — simulation init through CUDA graph capture through one training step + checkpoint save, no errors. - [x] Pre-commit clean. ## Caveat Smoke covered Shadow-Hand-Over MAPPO. Other envs with different sensors / renderers / collision setups could surface warp 1.13 or mujoco 3.8 differences the smoke didn't exercise; full PR CI catches them. --------- Co-authored-by: Kelly Guo --- .../jichuanh-newton-rc2-bump.minor.rst | 23 +++++++++ source/isaaclab/setup.py | 6 +-- .../changelog.d/jichuanh-newton-rc2-bump.rst | 15 ++++++ .../isaaclab_mimic/isaaclab_mimic/__init__.py | 49 +++++++++++++++++++ .../jichuanh-newton-rc2-bump.minor.rst | 33 +++++++++++++ .../isaaclab_newton/physics/newton_manager.py | 2 +- .../renderers/newton_warp_renderer.py | 15 +++++- source/isaaclab_newton/setup.py | 6 +-- .../changelog.d/jichuanh-newton-rc2-bump.rst | 23 +++++++++ .../renderers/ovrtx_renderer_kernels.py | 2 +- .../changelog.d/jichuanh-newton-rc2-bump.rst | 8 +++ source/isaaclab_physx/setup.py | 2 +- source/isaaclab_visualizers/setup.py | 6 +-- tools/wheel_builder/res/python_packages.toml | 10 ++-- 14 files changed, 182 insertions(+), 18 deletions(-) create mode 100644 source/isaaclab/changelog.d/jichuanh-newton-rc2-bump.minor.rst create mode 100644 source/isaaclab_mimic/changelog.d/jichuanh-newton-rc2-bump.rst create mode 100644 source/isaaclab_newton/changelog.d/jichuanh-newton-rc2-bump.minor.rst create mode 100644 source/isaaclab_ov/changelog.d/jichuanh-newton-rc2-bump.rst create mode 100644 source/isaaclab_physx/changelog.d/jichuanh-newton-rc2-bump.rst diff --git a/source/isaaclab/changelog.d/jichuanh-newton-rc2-bump.minor.rst b/source/isaaclab/changelog.d/jichuanh-newton-rc2-bump.minor.rst new file mode 100644 index 000000000000..3609cf6cd787 --- /dev/null +++ b/source/isaaclab/changelog.d/jichuanh-newton-rc2-bump.minor.rst @@ -0,0 +1,23 @@ +Changed +^^^^^^^ + +* Bumped Newton pin to ``v1.2.0rc2``. Pulls in IsaacLab-relevant fixes from + `newton-physics/newton#2678 `_ + and `newton-physics/newton#2720 + `_ (``SolverKamino`` + reset under ``world_mask``), the upstream tendon-scoping fix from + `newton-physics/newton#2659 + `_ ("Scope USD + custom-frequency parsing"), and a VRAM-leak fix on example reset + (`newton-physics/newton#2710 + `_). +* Newton ``v1.2.0rc2`` requires ``warp-lang==1.13.0``, ``mujoco==3.8.0``, + and ``mujoco-warp==3.8.0.1``. ``warp-lang``/``mujoco``/``mujoco-warp`` + pins live in :mod:`isaaclab` and ``tools/wheel_builder/res/python_packages.toml``; + the Newton pin is mirrored across :mod:`isaaclab_newton`, + :mod:`isaaclab_visualizers` (3×), :mod:`isaaclab_physx` (``[newton]`` + extra), and the wheel-builder TOML. +* Updated ``wp.math.transform_to_matrix`` to ``wp.transform_to_matrix`` in + :mod:`~isaaclab_newton.physics.newton_manager` and + :mod:`~isaaclab_ov.renderers.ovrtx_renderer_kernels` to match the + ``warp-lang`` 1.13 API (the ``wp.math`` namespace was removed). diff --git a/source/isaaclab/setup.py b/source/isaaclab/setup.py index 67c18c4c62d1..4f54032f6d14 100644 --- a/source/isaaclab/setup.py +++ b/source/isaaclab/setup.py @@ -30,12 +30,12 @@ # procedural-generation "trimesh", "pyglet>=2.1.6,<3", - "mujoco==3.6.0", - "mujoco-warp==3.6.0", + "mujoco==3.8.0", + "mujoco-warp==3.8.0.1", # image processing "transformers==4.57.6", "einops", # needed for transformers, doesn't always auto-install - "warp-lang==1.12.0", + "warp-lang==1.13.0", "matplotlib>=3.10.3", # minimum version for Python 3.12 support # make sure this is consistent with isaac sim version "pillow==12.1.1", diff --git a/source/isaaclab_mimic/changelog.d/jichuanh-newton-rc2-bump.rst b/source/isaaclab_mimic/changelog.d/jichuanh-newton-rc2-bump.rst new file mode 100644 index 000000000000..051f04fae9f2 --- /dev/null +++ b/source/isaaclab_mimic/changelog.d/jichuanh-newton-rc2-bump.rst @@ -0,0 +1,15 @@ +Added +^^^^^ + +* Added a temporary ``warp.torch`` compatibility shim at + :mod:`isaaclab_mimic` import time so that cuRobo (NVlabs/curobo) keeps + working with ``warp-lang>=1.13``, which dropped the ``warp.torch`` + submodule in favour of top-level ``warp.*`` (e.g. + ``wp.torch.device_from_torch`` → ``wp.device_from_torch``). cuRobo's + pinned commit and ``main`` still call ``wp.torch.*`` and raise + ``AttributeError: module 'warp' has no attribute 'torch'`` at + :meth:`MotionGenConfig.load_from_robot_config` time. The shim + reconstructs ``warp.torch`` as a thin forwarding module and is a + no-op once warp re-introduces the namespace or cuRobo migrates. + Remove this shim once the cuRobo pin in ``docker/Dockerfile.curobo`` + is bumped to a commit that uses the top-level ``wp.*`` API directly. diff --git a/source/isaaclab_mimic/isaaclab_mimic/__init__.py b/source/isaaclab_mimic/isaaclab_mimic/__init__.py index 17f1264a6b59..56b86cc6034d 100644 --- a/source/isaaclab_mimic/isaaclab_mimic/__init__.py +++ b/source/isaaclab_mimic/isaaclab_mimic/__init__.py @@ -5,4 +5,53 @@ """Package containing implementation of Isaac Lab Mimic data generation.""" +# --------------------------------------------------------------------------- +# Compatibility shim: re-expose ``warp.torch`` after warp-lang 1.13 dropped it +# +# Newton ``v1.2.0rc2`` requires ``warp-lang>=1.13``. Warp 1.13 collapsed the +# ``warp.torch`` submodule into the top-level ``warp`` namespace, so e.g. +# ``wp.torch.device_from_torch`` is now ``wp.device_from_torch``. cuRobo +# (NVlabs/curobo) still uses the old ``wp.torch.*`` form (verified at +# ``ebb71702f`` and on ``main`` as of 2026-05-07) and raises +# ``AttributeError: module 'warp' has no attribute 'torch'`` at +# ``MotionGenConfig.load_from_robot_config(...)`` time. +# +# This shim runs at ``isaaclab_mimic`` import — which Python evaluates before +# any submodule, including +# :mod:`isaaclab_mimic.motion_planners.curobo.curobo_planner` — so curobo +# sees a ``warp.torch`` namespace whose members forward to the relocated +# top-level ``warp.*`` callables. Idempotent: a no-op once warp ships +# ``wp.torch`` again or curobo migrates. +# +# TODO: remove this shim once the cuRobo pin in ``docker/Dockerfile.curobo`` +# bumps to a commit that uses ``wp.from_torch``/``wp.device_from_torch``/ +# etc. directly. Tracking upstream at https://github.com/NVlabs/curobo — +# follow up on the open issue / PR there to confirm the migration landed +# before deleting this block. +import sys as _sys +import types as _types + +import warp as _wp + +if not hasattr(_wp, "torch"): + _wp_torch_shim = _types.ModuleType("warp.torch") + for _name in ( + "from_torch", + "to_torch", + "device_from_torch", + "device_to_torch", + "dtype_from_torch", + "dtype_to_torch", + "stream_from_torch", + "stream_to_torch", + ): + if hasattr(_wp, _name): + setattr(_wp_torch_shim, _name, getattr(_wp, _name)) + _wp.torch = _wp_torch_shim + _sys.modules["warp.torch"] = _wp_torch_shim + del _wp_torch_shim, _name + +del _sys, _types, _wp + + __version__ = "1.0.0" diff --git a/source/isaaclab_newton/changelog.d/jichuanh-newton-rc2-bump.minor.rst b/source/isaaclab_newton/changelog.d/jichuanh-newton-rc2-bump.minor.rst new file mode 100644 index 000000000000..25985f94b4b2 --- /dev/null +++ b/source/isaaclab_newton/changelog.d/jichuanh-newton-rc2-bump.minor.rst @@ -0,0 +1,33 @@ +Changed +^^^^^^^ + +* Bumped Newton pin to ``v1.2.0rc2``. Pulls in IsaacLab-relevant fixes from + `newton-physics/newton#2678 `_ + and `newton-physics/newton#2720 + `_ (``SolverKamino`` + reset under ``world_mask``), the upstream tendon-scoping fix from + `newton-physics/newton#2659 + `_ ("Scope USD + custom-frequency parsing"), and a VRAM-leak fix on example reset + (`newton-physics/newton#2710 + `_). +* Newton ``v1.2.0rc2`` requires ``warp-lang==1.13.0``, ``mujoco==3.8.0``, + and ``mujoco-warp==3.8.0.1``. ``warp-lang``/``mujoco``/``mujoco-warp`` + pins live in :mod:`isaaclab` and ``tools/wheel_builder/res/python_packages.toml``; + the Newton pin is mirrored across :mod:`isaaclab_newton`, + :mod:`isaaclab_visualizers` (3×), :mod:`isaaclab_physx` (``[newton]`` + extra), and the wheel-builder TOML. +* Updated ``wp.math.transform_to_matrix`` to ``wp.transform_to_matrix`` in + :mod:`~isaaclab_newton.physics.newton_manager` and + :mod:`~isaaclab_ov.renderers.ovrtx_renderer_kernels` to match the + ``warp-lang`` 1.13 API (the ``wp.math`` namespace was removed). +* Adapted :class:`~isaaclab_newton.renderers.NewtonWarpRenderer` to + Newton ``v1.2.0rc2``'s explicit shape-BVH lifecycle. + :meth:`~newton.sensors.SensorTiledCamera.update` no longer auto-builds + the BVH when a non-``None`` state is passed and the underlying + ``RenderContext.render`` now raises ``RuntimeError("build_bvh_shape() + must be called before rendering shapes.")`` if it was never built. The + renderer now calls ``newton.geometry.build_bvh_shape`` once after + sensor construction and ``newton.geometry.refit_bvh_shape`` each frame + before :meth:`~newton.sensors.SensorTiledCamera.update`, since env + body poses move every step. diff --git a/source/isaaclab_newton/isaaclab_newton/physics/newton_manager.py b/source/isaaclab_newton/isaaclab_newton/physics/newton_manager.py index 2bb2f1f37397..dbc85e97c270 100644 --- a/source/isaaclab_newton/isaaclab_newton/physics/newton_manager.py +++ b/source/isaaclab_newton/isaaclab_newton/physics/newton_manager.py @@ -69,7 +69,7 @@ def _set_fabric_transforms( i = int(wp.tid()) idx = int(newton_indices[i]) transform = newton_body_q[idx] - fabric_transforms[i] = wp.transpose(wp.mat44d(wp.math.transform_to_matrix(transform))) + fabric_transforms[i] = wp.transpose(wp.mat44d(wp.transform_to_matrix(transform))) @wp.kernel(enable_backward=False) diff --git a/source/isaaclab_newton/isaaclab_newton/renderers/newton_warp_renderer.py b/source/isaaclab_newton/isaaclab_newton/renderers/newton_warp_renderer.py index a02d820f2951..78285636b6ef 100644 --- a/source/isaaclab_newton/isaaclab_newton/renderers/newton_warp_renderer.py +++ b/source/isaaclab_newton/isaaclab_newton/renderers/newton_warp_renderer.py @@ -172,6 +172,14 @@ def __init__(self, cfg: NewtonWarpRendererCfg): ), ) + # Newton ``v1.2.0rc2`` made shape-BVH construction explicit; ``SensorTiledCamera.update`` + # no longer auto-builds when a non-``None`` state is passed, and the underlying + # ``RenderContext.render`` raises if ``build_bvh_shape`` was never called for the model. + # Build it once per model — idempotent across multiple sensors that share ``newton_model`` + # because subsequent calls overwrite the same model-level BVH attributes. + if newton_model.shape_count > 0 and newton_model.bvh_shapes is None: + newton.geometry.build_bvh_shape(newton_model, newton_model.state()) + if cfg.create_default_light: self.newton_sensor.utils.create_default_light(enable_shadows=cfg.enable_shadows) @@ -220,8 +228,13 @@ def update_camera( def render(self, render_data: RenderData): """Render and write to output buffers. See :meth:`~isaaclab.renderers.base_renderer.BaseRenderer.render`.""" + newton_state = self.get_scene_data_provider().get_newton_state() + # Refit the shape BVH against the current state since env body poses move every frame. + # ``build_bvh_shape`` ran once in ``__init__``; ``refit_bvh_shape`` reuses that topology. + if self.newton_sensor.model.shape_count > 0: + newton.geometry.refit_bvh_shape(self.newton_sensor.model, newton_state) self.newton_sensor.update( - self.get_scene_data_provider().get_newton_state(), + newton_state, render_data.camera_transforms, render_data.camera_rays, color_image=render_data.outputs.color_image, diff --git a/source/isaaclab_newton/setup.py b/source/isaaclab_newton/setup.py index 2e0b87f17543..4621e77f879b 100644 --- a/source/isaaclab_newton/setup.py +++ b/source/isaaclab_newton/setup.py @@ -38,10 +38,10 @@ def run(self): EXTRAS_REQUIRE = { "all": [ "prettytable==3.3.0", - "mujoco==3.6.0", - "mujoco-warp==3.6.0", + "mujoco==3.8.0", + "mujoco-warp==3.8.0.1", "PyOpenGL-accelerate==3.1.10", - "newton @ git+https://github.com/newton-physics/newton.git@a27277ed49d6f307b8a1e4c394be7e1d14965a62", + "newton @ git+https://github.com/newton-physics/newton.git@v1.2.0rc2", ], } diff --git a/source/isaaclab_ov/changelog.d/jichuanh-newton-rc2-bump.rst b/source/isaaclab_ov/changelog.d/jichuanh-newton-rc2-bump.rst new file mode 100644 index 000000000000..3609cf6cd787 --- /dev/null +++ b/source/isaaclab_ov/changelog.d/jichuanh-newton-rc2-bump.rst @@ -0,0 +1,23 @@ +Changed +^^^^^^^ + +* Bumped Newton pin to ``v1.2.0rc2``. Pulls in IsaacLab-relevant fixes from + `newton-physics/newton#2678 `_ + and `newton-physics/newton#2720 + `_ (``SolverKamino`` + reset under ``world_mask``), the upstream tendon-scoping fix from + `newton-physics/newton#2659 + `_ ("Scope USD + custom-frequency parsing"), and a VRAM-leak fix on example reset + (`newton-physics/newton#2710 + `_). +* Newton ``v1.2.0rc2`` requires ``warp-lang==1.13.0``, ``mujoco==3.8.0``, + and ``mujoco-warp==3.8.0.1``. ``warp-lang``/``mujoco``/``mujoco-warp`` + pins live in :mod:`isaaclab` and ``tools/wheel_builder/res/python_packages.toml``; + the Newton pin is mirrored across :mod:`isaaclab_newton`, + :mod:`isaaclab_visualizers` (3×), :mod:`isaaclab_physx` (``[newton]`` + extra), and the wheel-builder TOML. +* Updated ``wp.math.transform_to_matrix`` to ``wp.transform_to_matrix`` in + :mod:`~isaaclab_newton.physics.newton_manager` and + :mod:`~isaaclab_ov.renderers.ovrtx_renderer_kernels` to match the + ``warp-lang`` 1.13 API (the ``wp.math`` namespace was removed). diff --git a/source/isaaclab_ov/isaaclab_ov/renderers/ovrtx_renderer_kernels.py b/source/isaaclab_ov/isaaclab_ov/renderers/ovrtx_renderer_kernels.py index c287f1257632..0c1626916414 100644 --- a/source/isaaclab_ov/isaaclab_ov/renderers/ovrtx_renderer_kernels.py +++ b/source/isaaclab_ov/isaaclab_ov/renderers/ovrtx_renderer_kernels.py @@ -327,4 +327,4 @@ def sync_newton_transforms_kernel( i = wp.tid() body_idx = newton_body_indices[i] transform = newton_body_q[body_idx] - ovrtx_transforms[i] = wp.transpose(wp.mat44d(wp.math.transform_to_matrix(transform))) + ovrtx_transforms[i] = wp.transpose(wp.mat44d(wp.transform_to_matrix(transform))) diff --git a/source/isaaclab_physx/changelog.d/jichuanh-newton-rc2-bump.rst b/source/isaaclab_physx/changelog.d/jichuanh-newton-rc2-bump.rst new file mode 100644 index 000000000000..74bca94ff983 --- /dev/null +++ b/source/isaaclab_physx/changelog.d/jichuanh-newton-rc2-bump.rst @@ -0,0 +1,8 @@ +Changed +^^^^^^^ + +* Bumped the optional ``[newton]`` extra to ``v1.2.0rc2`` so the Newton + scene representation built by + :class:`~isaaclab_physx.scene_data_providers.PhysxSceneDataProvider` + for the OV/Rerun/Viser visualizers stays in sync with the version + pinned in :mod:`isaaclab_newton` and :mod:`isaaclab_visualizers`. diff --git a/source/isaaclab_physx/setup.py b/source/isaaclab_physx/setup.py index 1e917e938c2b..9cc172addf50 100644 --- a/source/isaaclab_physx/setup.py +++ b/source/isaaclab_physx/setup.py @@ -20,7 +20,7 @@ EXTRAS_REQUIRE = { "newton": [ - "newton @ git+https://github.com/newton-physics/newton.git@2684d75bfa4bb8b058a93b81c458a74b7701c997", + "newton @ git+https://github.com/newton-physics/newton.git@v1.2.0rc2", ], } diff --git a/source/isaaclab_visualizers/setup.py b/source/isaaclab_visualizers/setup.py index fc120619787b..9ad52a712360 100644 --- a/source/isaaclab_visualizers/setup.py +++ b/source/isaaclab_visualizers/setup.py @@ -17,16 +17,16 @@ "kit": [], "newton": [ "warp-lang", - "newton @ git+https://github.com/newton-physics/newton.git@a27277ed49d6f307b8a1e4c394be7e1d14965a62", + "newton @ git+https://github.com/newton-physics/newton.git@v1.2.0rc2", "PyOpenGL-accelerate", "imgui-bundle>=1.92.5", ], "rerun": [ - "newton @ git+https://github.com/newton-physics/newton.git@a27277ed49d6f307b8a1e4c394be7e1d14965a62", + "newton @ git+https://github.com/newton-physics/newton.git@v1.2.0rc2", "rerun-sdk>=0.29.0", ], "viser": [ - "newton @ git+https://github.com/newton-physics/newton.git@a27277ed49d6f307b8a1e4c394be7e1d14965a62", + "newton @ git+https://github.com/newton-physics/newton.git@v1.2.0rc2", "viser>=1.0.16", ], } diff --git a/tools/wheel_builder/res/python_packages.toml b/tools/wheel_builder/res/python_packages.toml index 1676fdc8f905..285d1cddbc66 100644 --- a/tools/wheel_builder/res/python_packages.toml +++ b/tools/wheel_builder/res/python_packages.toml @@ -22,7 +22,7 @@ pyproject.dependencies.all = [ # image processing "transformers==4.57.6", "einops", # needed for transformers, doesn't always auto-install - "warp-lang==1.12.0", + "warp-lang==1.13.0", "matplotlib>=3.10.3", # make sure this is consistent with isaac sim version "pillow==12.1.1", @@ -82,10 +82,10 @@ pyproject.optional-dependencies.all = [ # https://github.com/isaac-sim/IsaacLab/blob/main/source/isaaclab_newton/setup.py # ================================================================================ { "newton" = [ - "warp-lang==1.12.0", - "mujoco==3.6.0", - "mujoco-warp==3.6.0", - "newton @ git+https://github.com/newton-physics/newton.git@a27277ed49d6f307b8a1e4c394be7e1d14965a62", + "warp-lang==1.13.0", + "mujoco==3.8.0", + "mujoco-warp==3.8.0.1", + "newton @ git+https://github.com/newton-physics/newton.git@v1.2.0rc2", "PyOpenGL-accelerate==3.1.10" ] }, # ================================================================================ From 99b0359aa290a0ad246ba0e2cbc7481d63bbd159 Mon Sep 17 00:00:00 2001 From: "isaaclab-bot[bot]" <282401363+isaaclab-bot[bot]@users.noreply.github.com> Date: Fri, 8 May 2026 05:44:17 +0000 Subject: [PATCH 12/51] [CI][Auto Version Bump] Compile changelog fragments (schedule) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Bumped packages: - isaaclab: 4.7.0 → 4.8.0 - isaaclab_mimic: 1.2.5 → 1.2.6 - isaaclab_newton: 0.6.0 → 0.7.0 - isaaclab_ov: 0.1.4 → 0.1.5 - isaaclab_physx: 0.6.0 → 0.6.1 --- .../jichuanh-newton-rc2-bump.minor.rst | 23 ----------- source/isaaclab/config/extension.toml | 2 +- source/isaaclab/docs/CHANGELOG.rst | 28 ++++++++++++++ .../changelog.d/jichuanh-newton-rc2-bump.rst | 15 -------- source/isaaclab_mimic/config/extension.toml | 2 +- source/isaaclab_mimic/docs/CHANGELOG.rst | 20 ++++++++++ .../jichuanh-newton-rc2-bump.minor.rst | 33 ---------------- source/isaaclab_newton/config/extension.toml | 2 +- source/isaaclab_newton/docs/CHANGELOG.rst | 38 +++++++++++++++++++ .../changelog.d/jichuanh-newton-rc2-bump.rst | 23 ----------- source/isaaclab_ov/config/extension.toml | 2 +- source/isaaclab_ov/docs/CHANGELOG.rst | 28 ++++++++++++++ .../changelog.d/jichuanh-newton-rc2-bump.rst | 8 ---- source/isaaclab_physx/config/extension.toml | 2 +- source/isaaclab_physx/docs/CHANGELOG.rst | 13 +++++++ 15 files changed, 132 insertions(+), 107 deletions(-) delete mode 100644 source/isaaclab/changelog.d/jichuanh-newton-rc2-bump.minor.rst delete mode 100644 source/isaaclab_mimic/changelog.d/jichuanh-newton-rc2-bump.rst delete mode 100644 source/isaaclab_newton/changelog.d/jichuanh-newton-rc2-bump.minor.rst delete mode 100644 source/isaaclab_ov/changelog.d/jichuanh-newton-rc2-bump.rst delete mode 100644 source/isaaclab_physx/changelog.d/jichuanh-newton-rc2-bump.rst diff --git a/source/isaaclab/changelog.d/jichuanh-newton-rc2-bump.minor.rst b/source/isaaclab/changelog.d/jichuanh-newton-rc2-bump.minor.rst deleted file mode 100644 index 3609cf6cd787..000000000000 --- a/source/isaaclab/changelog.d/jichuanh-newton-rc2-bump.minor.rst +++ /dev/null @@ -1,23 +0,0 @@ -Changed -^^^^^^^ - -* Bumped Newton pin to ``v1.2.0rc2``. Pulls in IsaacLab-relevant fixes from - `newton-physics/newton#2678 `_ - and `newton-physics/newton#2720 - `_ (``SolverKamino`` - reset under ``world_mask``), the upstream tendon-scoping fix from - `newton-physics/newton#2659 - `_ ("Scope USD - custom-frequency parsing"), and a VRAM-leak fix on example reset - (`newton-physics/newton#2710 - `_). -* Newton ``v1.2.0rc2`` requires ``warp-lang==1.13.0``, ``mujoco==3.8.0``, - and ``mujoco-warp==3.8.0.1``. ``warp-lang``/``mujoco``/``mujoco-warp`` - pins live in :mod:`isaaclab` and ``tools/wheel_builder/res/python_packages.toml``; - the Newton pin is mirrored across :mod:`isaaclab_newton`, - :mod:`isaaclab_visualizers` (3×), :mod:`isaaclab_physx` (``[newton]`` - extra), and the wheel-builder TOML. -* Updated ``wp.math.transform_to_matrix`` to ``wp.transform_to_matrix`` in - :mod:`~isaaclab_newton.physics.newton_manager` and - :mod:`~isaaclab_ov.renderers.ovrtx_renderer_kernels` to match the - ``warp-lang`` 1.13 API (the ``wp.math`` namespace was removed). diff --git a/source/isaaclab/config/extension.toml b/source/isaaclab/config/extension.toml index e1620d629745..ce77d89f4c45 100644 --- a/source/isaaclab/config/extension.toml +++ b/source/isaaclab/config/extension.toml @@ -1,7 +1,7 @@ [package] # Note: Semantic Versioning is used: https://semver.org/ -version = "4.7.0" +version = "4.8.0" # Description title = "Isaac Lab framework for Robot Learning" diff --git a/source/isaaclab/docs/CHANGELOG.rst b/source/isaaclab/docs/CHANGELOG.rst index 1bb6a29060fa..152979d60df4 100644 --- a/source/isaaclab/docs/CHANGELOG.rst +++ b/source/isaaclab/docs/CHANGELOG.rst @@ -1,6 +1,34 @@ Changelog --------- +4.8.0 (2026-05-08) +~~~~~~~~~~~~~~~~~~ + +Changed +^^^^^^^ + +* Bumped Newton pin to ``v1.2.0rc2``. Pulls in IsaacLab-relevant fixes from + `newton-physics/newton#2678 `_ + and `newton-physics/newton#2720 + `_ (``SolverKamino`` + reset under ``world_mask``), the upstream tendon-scoping fix from + `newton-physics/newton#2659 + `_ ("Scope USD + custom-frequency parsing"), and a VRAM-leak fix on example reset + (`newton-physics/newton#2710 + `_). +* Newton ``v1.2.0rc2`` requires ``warp-lang==1.13.0``, ``mujoco==3.8.0``, + and ``mujoco-warp==3.8.0.1``. ``warp-lang``/``mujoco``/``mujoco-warp`` + pins live in :mod:`isaaclab` and ``tools/wheel_builder/res/python_packages.toml``; + the Newton pin is mirrored across :mod:`isaaclab_newton`, + :mod:`isaaclab_visualizers` (3×), :mod:`isaaclab_physx` (``[newton]`` + extra), and the wheel-builder TOML. +* Updated ``wp.math.transform_to_matrix`` to ``wp.transform_to_matrix`` in + :mod:`~isaaclab_newton.physics.newton_manager` and + :mod:`~isaaclab_ov.renderers.ovrtx_renderer_kernels` to match the + ``warp-lang`` 1.13 API (the ``wp.math`` namespace was removed). + + 4.7.0 (2026-05-08) ~~~~~~~~~~~~~~~~~~ diff --git a/source/isaaclab_mimic/changelog.d/jichuanh-newton-rc2-bump.rst b/source/isaaclab_mimic/changelog.d/jichuanh-newton-rc2-bump.rst deleted file mode 100644 index 051f04fae9f2..000000000000 --- a/source/isaaclab_mimic/changelog.d/jichuanh-newton-rc2-bump.rst +++ /dev/null @@ -1,15 +0,0 @@ -Added -^^^^^ - -* Added a temporary ``warp.torch`` compatibility shim at - :mod:`isaaclab_mimic` import time so that cuRobo (NVlabs/curobo) keeps - working with ``warp-lang>=1.13``, which dropped the ``warp.torch`` - submodule in favour of top-level ``warp.*`` (e.g. - ``wp.torch.device_from_torch`` → ``wp.device_from_torch``). cuRobo's - pinned commit and ``main`` still call ``wp.torch.*`` and raise - ``AttributeError: module 'warp' has no attribute 'torch'`` at - :meth:`MotionGenConfig.load_from_robot_config` time. The shim - reconstructs ``warp.torch`` as a thin forwarding module and is a - no-op once warp re-introduces the namespace or cuRobo migrates. - Remove this shim once the cuRobo pin in ``docker/Dockerfile.curobo`` - is bumped to a commit that uses the top-level ``wp.*`` API directly. diff --git a/source/isaaclab_mimic/config/extension.toml b/source/isaaclab_mimic/config/extension.toml index f53461c3fc6f..6646522f5f1e 100644 --- a/source/isaaclab_mimic/config/extension.toml +++ b/source/isaaclab_mimic/config/extension.toml @@ -1,7 +1,7 @@ [package] # Semantic Versioning is used: https://semver.org/ -version = "1.2.5" +version = "1.2.6" # Description category = "isaaclab" diff --git a/source/isaaclab_mimic/docs/CHANGELOG.rst b/source/isaaclab_mimic/docs/CHANGELOG.rst index 782cf6f7d220..08da411a579c 100644 --- a/source/isaaclab_mimic/docs/CHANGELOG.rst +++ b/source/isaaclab_mimic/docs/CHANGELOG.rst @@ -1,6 +1,26 @@ Changelog --------- +1.2.6 (2026-05-08) +~~~~~~~~~~~~~~~~~~ + +Added +^^^^^ + +* Added a temporary ``warp.torch`` compatibility shim at + :mod:`isaaclab_mimic` import time so that cuRobo (NVlabs/curobo) keeps + working with ``warp-lang>=1.13``, which dropped the ``warp.torch`` + submodule in favour of top-level ``warp.*`` (e.g. + ``wp.torch.device_from_torch`` → ``wp.device_from_torch``). cuRobo's + pinned commit and ``main`` still call ``wp.torch.*`` and raise + ``AttributeError: module 'warp' has no attribute 'torch'`` at + :meth:`MotionGenConfig.load_from_robot_config` time. The shim + reconstructs ``warp.torch`` as a thin forwarding module and is a + no-op once warp re-introduces the namespace or cuRobo migrates. + Remove this shim once the cuRobo pin in ``docker/Dockerfile.curobo`` + is bumped to a commit that uses the top-level ``wp.*`` API directly. + + 1.2.5 (2026-04-14) ~~~~~~~~~~~~~~~~~~~ diff --git a/source/isaaclab_newton/changelog.d/jichuanh-newton-rc2-bump.minor.rst b/source/isaaclab_newton/changelog.d/jichuanh-newton-rc2-bump.minor.rst deleted file mode 100644 index 25985f94b4b2..000000000000 --- a/source/isaaclab_newton/changelog.d/jichuanh-newton-rc2-bump.minor.rst +++ /dev/null @@ -1,33 +0,0 @@ -Changed -^^^^^^^ - -* Bumped Newton pin to ``v1.2.0rc2``. Pulls in IsaacLab-relevant fixes from - `newton-physics/newton#2678 `_ - and `newton-physics/newton#2720 - `_ (``SolverKamino`` - reset under ``world_mask``), the upstream tendon-scoping fix from - `newton-physics/newton#2659 - `_ ("Scope USD - custom-frequency parsing"), and a VRAM-leak fix on example reset - (`newton-physics/newton#2710 - `_). -* Newton ``v1.2.0rc2`` requires ``warp-lang==1.13.0``, ``mujoco==3.8.0``, - and ``mujoco-warp==3.8.0.1``. ``warp-lang``/``mujoco``/``mujoco-warp`` - pins live in :mod:`isaaclab` and ``tools/wheel_builder/res/python_packages.toml``; - the Newton pin is mirrored across :mod:`isaaclab_newton`, - :mod:`isaaclab_visualizers` (3×), :mod:`isaaclab_physx` (``[newton]`` - extra), and the wheel-builder TOML. -* Updated ``wp.math.transform_to_matrix`` to ``wp.transform_to_matrix`` in - :mod:`~isaaclab_newton.physics.newton_manager` and - :mod:`~isaaclab_ov.renderers.ovrtx_renderer_kernels` to match the - ``warp-lang`` 1.13 API (the ``wp.math`` namespace was removed). -* Adapted :class:`~isaaclab_newton.renderers.NewtonWarpRenderer` to - Newton ``v1.2.0rc2``'s explicit shape-BVH lifecycle. - :meth:`~newton.sensors.SensorTiledCamera.update` no longer auto-builds - the BVH when a non-``None`` state is passed and the underlying - ``RenderContext.render`` now raises ``RuntimeError("build_bvh_shape() - must be called before rendering shapes.")`` if it was never built. The - renderer now calls ``newton.geometry.build_bvh_shape`` once after - sensor construction and ``newton.geometry.refit_bvh_shape`` each frame - before :meth:`~newton.sensors.SensorTiledCamera.update`, since env - body poses move every step. diff --git a/source/isaaclab_newton/config/extension.toml b/source/isaaclab_newton/config/extension.toml index 4837c3f7ae03..8ddb2526072e 100644 --- a/source/isaaclab_newton/config/extension.toml +++ b/source/isaaclab_newton/config/extension.toml @@ -1,7 +1,7 @@ [package] # Note: Semantic Versioning is used: https://semver.org/ -version = "0.6.0" +version = "0.7.0" # Description title = "Newton simulation interfaces for IsaacLab core package" diff --git a/source/isaaclab_newton/docs/CHANGELOG.rst b/source/isaaclab_newton/docs/CHANGELOG.rst index 0f81a9effc43..afde5c8d2ec5 100644 --- a/source/isaaclab_newton/docs/CHANGELOG.rst +++ b/source/isaaclab_newton/docs/CHANGELOG.rst @@ -1,6 +1,44 @@ Changelog --------- +0.7.0 (2026-05-08) +~~~~~~~~~~~~~~~~~~ + +Changed +^^^^^^^ + +* Bumped Newton pin to ``v1.2.0rc2``. Pulls in IsaacLab-relevant fixes from + `newton-physics/newton#2678 `_ + and `newton-physics/newton#2720 + `_ (``SolverKamino`` + reset under ``world_mask``), the upstream tendon-scoping fix from + `newton-physics/newton#2659 + `_ ("Scope USD + custom-frequency parsing"), and a VRAM-leak fix on example reset + (`newton-physics/newton#2710 + `_). +* Newton ``v1.2.0rc2`` requires ``warp-lang==1.13.0``, ``mujoco==3.8.0``, + and ``mujoco-warp==3.8.0.1``. ``warp-lang``/``mujoco``/``mujoco-warp`` + pins live in :mod:`isaaclab` and ``tools/wheel_builder/res/python_packages.toml``; + the Newton pin is mirrored across :mod:`isaaclab_newton`, + :mod:`isaaclab_visualizers` (3×), :mod:`isaaclab_physx` (``[newton]`` + extra), and the wheel-builder TOML. +* Updated ``wp.math.transform_to_matrix`` to ``wp.transform_to_matrix`` in + :mod:`~isaaclab_newton.physics.newton_manager` and + :mod:`~isaaclab_ov.renderers.ovrtx_renderer_kernels` to match the + ``warp-lang`` 1.13 API (the ``wp.math`` namespace was removed). +* Adapted :class:`~isaaclab_newton.renderers.NewtonWarpRenderer` to + Newton ``v1.2.0rc2``'s explicit shape-BVH lifecycle. + :meth:`~newton.sensors.SensorTiledCamera.update` no longer auto-builds + the BVH when a non-``None`` state is passed and the underlying + ``RenderContext.render`` now raises ``RuntimeError("build_bvh_shape() + must be called before rendering shapes.")`` if it was never built. The + renderer now calls ``newton.geometry.build_bvh_shape`` once after + sensor construction and ``newton.geometry.refit_bvh_shape`` each frame + before :meth:`~newton.sensors.SensorTiledCamera.update`, since env + body poses move every step. + + 0.6.0 (2026-05-08) ~~~~~~~~~~~~~~~~~~ diff --git a/source/isaaclab_ov/changelog.d/jichuanh-newton-rc2-bump.rst b/source/isaaclab_ov/changelog.d/jichuanh-newton-rc2-bump.rst deleted file mode 100644 index 3609cf6cd787..000000000000 --- a/source/isaaclab_ov/changelog.d/jichuanh-newton-rc2-bump.rst +++ /dev/null @@ -1,23 +0,0 @@ -Changed -^^^^^^^ - -* Bumped Newton pin to ``v1.2.0rc2``. Pulls in IsaacLab-relevant fixes from - `newton-physics/newton#2678 `_ - and `newton-physics/newton#2720 - `_ (``SolverKamino`` - reset under ``world_mask``), the upstream tendon-scoping fix from - `newton-physics/newton#2659 - `_ ("Scope USD - custom-frequency parsing"), and a VRAM-leak fix on example reset - (`newton-physics/newton#2710 - `_). -* Newton ``v1.2.0rc2`` requires ``warp-lang==1.13.0``, ``mujoco==3.8.0``, - and ``mujoco-warp==3.8.0.1``. ``warp-lang``/``mujoco``/``mujoco-warp`` - pins live in :mod:`isaaclab` and ``tools/wheel_builder/res/python_packages.toml``; - the Newton pin is mirrored across :mod:`isaaclab_newton`, - :mod:`isaaclab_visualizers` (3×), :mod:`isaaclab_physx` (``[newton]`` - extra), and the wheel-builder TOML. -* Updated ``wp.math.transform_to_matrix`` to ``wp.transform_to_matrix`` in - :mod:`~isaaclab_newton.physics.newton_manager` and - :mod:`~isaaclab_ov.renderers.ovrtx_renderer_kernels` to match the - ``warp-lang`` 1.13 API (the ``wp.math`` namespace was removed). diff --git a/source/isaaclab_ov/config/extension.toml b/source/isaaclab_ov/config/extension.toml index 88756787ecc1..63cda50eb5c0 100644 --- a/source/isaaclab_ov/config/extension.toml +++ b/source/isaaclab_ov/config/extension.toml @@ -1,5 +1,5 @@ [package] -version = "0.1.4" +version = "0.1.5" title = "Omniverse renderers for IsaacLab" description = "Extension providing Omniverse renderers (OVRTX, ovphysx, etc.) for tiled camera rendering." readme = "docs/README.md" diff --git a/source/isaaclab_ov/docs/CHANGELOG.rst b/source/isaaclab_ov/docs/CHANGELOG.rst index 9d558d295876..d1af152a61e5 100644 --- a/source/isaaclab_ov/docs/CHANGELOG.rst +++ b/source/isaaclab_ov/docs/CHANGELOG.rst @@ -1,6 +1,34 @@ Changelog --------- +0.1.5 (2026-05-08) +~~~~~~~~~~~~~~~~~~ + +Changed +^^^^^^^ + +* Bumped Newton pin to ``v1.2.0rc2``. Pulls in IsaacLab-relevant fixes from + `newton-physics/newton#2678 `_ + and `newton-physics/newton#2720 + `_ (``SolverKamino`` + reset under ``world_mask``), the upstream tendon-scoping fix from + `newton-physics/newton#2659 + `_ ("Scope USD + custom-frequency parsing"), and a VRAM-leak fix on example reset + (`newton-physics/newton#2710 + `_). +* Newton ``v1.2.0rc2`` requires ``warp-lang==1.13.0``, ``mujoco==3.8.0``, + and ``mujoco-warp==3.8.0.1``. ``warp-lang``/``mujoco``/``mujoco-warp`` + pins live in :mod:`isaaclab` and ``tools/wheel_builder/res/python_packages.toml``; + the Newton pin is mirrored across :mod:`isaaclab_newton`, + :mod:`isaaclab_visualizers` (3×), :mod:`isaaclab_physx` (``[newton]`` + extra), and the wheel-builder TOML. +* Updated ``wp.math.transform_to_matrix`` to ``wp.transform_to_matrix`` in + :mod:`~isaaclab_newton.physics.newton_manager` and + :mod:`~isaaclab_ov.renderers.ovrtx_renderer_kernels` to match the + ``warp-lang`` 1.13 API (the ``wp.math`` namespace was removed). + + 0.1.4 (2026-05-08) ~~~~~~~~~~~~~~~~~~ diff --git a/source/isaaclab_physx/changelog.d/jichuanh-newton-rc2-bump.rst b/source/isaaclab_physx/changelog.d/jichuanh-newton-rc2-bump.rst deleted file mode 100644 index 74bca94ff983..000000000000 --- a/source/isaaclab_physx/changelog.d/jichuanh-newton-rc2-bump.rst +++ /dev/null @@ -1,8 +0,0 @@ -Changed -^^^^^^^ - -* Bumped the optional ``[newton]`` extra to ``v1.2.0rc2`` so the Newton - scene representation built by - :class:`~isaaclab_physx.scene_data_providers.PhysxSceneDataProvider` - for the OV/Rerun/Viser visualizers stays in sync with the version - pinned in :mod:`isaaclab_newton` and :mod:`isaaclab_visualizers`. diff --git a/source/isaaclab_physx/config/extension.toml b/source/isaaclab_physx/config/extension.toml index 2e6fbc7360fc..00264e1238ff 100644 --- a/source/isaaclab_physx/config/extension.toml +++ b/source/isaaclab_physx/config/extension.toml @@ -1,7 +1,7 @@ [package] # Note: Semantic Versioning is used: https://semver.org/ -version = "0.6.0" +version = "0.6.1" # Description title = "PhysX simulation interfaces for IsaacLab core package" diff --git a/source/isaaclab_physx/docs/CHANGELOG.rst b/source/isaaclab_physx/docs/CHANGELOG.rst index f99368bd5be5..bc487f3190ab 100644 --- a/source/isaaclab_physx/docs/CHANGELOG.rst +++ b/source/isaaclab_physx/docs/CHANGELOG.rst @@ -1,6 +1,19 @@ Changelog --------- +0.6.1 (2026-05-08) +~~~~~~~~~~~~~~~~~~ + +Changed +^^^^^^^ + +* Bumped the optional ``[newton]`` extra to ``v1.2.0rc2`` so the Newton + scene representation built by + :class:`~isaaclab_physx.scene_data_providers.PhysxSceneDataProvider` + for the OV/Rerun/Viser visualizers stays in sync with the version + pinned in :mod:`isaaclab_newton` and :mod:`isaaclab_visualizers`. + + 0.6.0 (2026-05-08) ~~~~~~~~~~~~~~~~~~ From af9c98fa1c17015b111f1f6264819a3c0499194a Mon Sep 17 00:00:00 2001 From: Antoine RICHARD Date: Fri, 8 May 2026 09:25:03 +0200 Subject: [PATCH 13/51] Fixes joint friction API docs (#5533) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit # Description Clarifies the articulation joint friction API docs across the base, PhysX, and Newton implementations. The base API now warns that joint friction semantics are backend-specific. The PhysX docs distinguish legacy unitless coefficients from PhysX 5 static/dynamic friction efforts and viscous coefficients. The Newton docs now identify joint friction as an absolute force/torque value and include an MJWarp example mapping the value to MuJoCo Warp's `dof_frictionloss`. Fixes isaac-sim/IsaacLab-Internal#875 ## Type of change - Documentation update ## Screenshots Not applicable. ## Checklist - [ ] I have read and understood the [contribution guidelines](https://isaac-sim.github.io/IsaacLab/main/source/refs/contributing.html) - [x] I have run the [`pre-commit` checks](https://pre-commit.com/) with `./isaaclab.sh --format` - [x] I have made corresponding changes to the documentation - [x] My changes generate no new warnings - [ ] I have added tests that prove my fix is effective or that my feature works (not applicable: docs-only change) - [x] I have added a changelog fragment under `source//changelog.d/` for every touched package (do **not** edit `CHANGELOG.rst` or bump `extension.toml` — CI handles that) - [x] I have added my name to the `CONTRIBUTORS.md` or my name already exists there --- .../antoiner-docs-joint-friction.rst | 4 + .../assets/articulation/base_articulation.py | 22 ++--- .../articulation/base_articulation_data.py | 7 +- .../antoiner-docs-joint-friction.rst | 5 ++ .../assets/articulation/articulation.py | 32 ++++++- .../assets/articulation/articulation_data.py | 9 +- .../antoiner-docs-joint-friction.rst | 5 ++ .../assets/articulation/articulation.py | 90 ++++++++++++------- .../assets/articulation/articulation_data.py | 11 ++- 9 files changed, 135 insertions(+), 50 deletions(-) create mode 100644 source/isaaclab/changelog.d/antoiner-docs-joint-friction.rst create mode 100644 source/isaaclab_newton/changelog.d/antoiner-docs-joint-friction.rst create mode 100644 source/isaaclab_physx/changelog.d/antoiner-docs-joint-friction.rst diff --git a/source/isaaclab/changelog.d/antoiner-docs-joint-friction.rst b/source/isaaclab/changelog.d/antoiner-docs-joint-friction.rst new file mode 100644 index 000000000000..4b7e63eeb995 --- /dev/null +++ b/source/isaaclab/changelog.d/antoiner-docs-joint-friction.rst @@ -0,0 +1,4 @@ +Fixed +^^^^^ + +* Fixed :class:`~isaaclab.assets.Articulation` joint friction API docs to clarify backend-specific semantics. diff --git a/source/isaaclab/isaaclab/assets/articulation/base_articulation.py b/source/isaaclab/isaaclab/assets/articulation/base_articulation.py index 3cd9e33376db..dc9ddc6cb7ad 100644 --- a/source/isaaclab/isaaclab/assets/articulation/base_articulation.py +++ b/source/isaaclab/isaaclab/assets/articulation/base_articulation.py @@ -1067,11 +1067,12 @@ def write_joint_friction_coefficient_to_sim_index( joint_ids: Sequence[int] | torch.Tensor | wp.array | None = None, env_ids: Sequence[int] | torch.Tensor | wp.array | None = None, ) -> None: - r"""Write joint static friction coefficients into the simulation. + r"""Write backend-specific joint friction values into the simulation. - The joint static friction is a unitless quantity. It relates the magnitude of the spatial force transmitted - from the parent body to the child body to the maximal static friction force that may be applied by the solver - to resist the joint motion. + .. warning:: + The physical meaning and units of joint friction depend on the concrete backend and solver. Do not assume + values are comparable across backends; check the backend-specific implementation before interpreting or + reusing them. .. note:: This method expects partial data. @@ -1081,7 +1082,7 @@ def write_joint_friction_coefficient_to_sim_index( Some backends may provide optimized implementations for masks / indices. Args: - joint_friction_coeff: Joint static friction coefficient. Shape is (len(env_ids), len(joint_ids)). + joint_friction_coeff: Backend-specific joint friction values. Shape is (len(env_ids), len(joint_ids)). joint_ids: The joint indices to set the joint torque limits for. Defaults to None (all joints). env_ids: The environment indices to set the joint torque limits for. Defaults to None (all instances). """ @@ -1095,11 +1096,12 @@ def write_joint_friction_coefficient_to_sim_mask( joint_mask: wp.array | None = None, env_mask: wp.array | None = None, ) -> None: - r"""Write joint static friction coefficients into the simulation. + r"""Write backend-specific joint friction values into the simulation. - The joint static friction is a unitless quantity. It relates the magnitude of the spatial force transmitted - from the parent body to the child body to the maximal static friction force that may be applied by the solver - to resist the joint motion. + .. warning:: + The physical meaning and units of joint friction depend on the concrete backend and solver. Do not assume + values are comparable across backends; check the backend-specific implementation before interpreting or + reusing them. .. note:: This method expects full data. @@ -1109,7 +1111,7 @@ def write_joint_friction_coefficient_to_sim_mask( Some backends may provide optimized implementations for masks / indices. Args: - joint_friction_coeff: Joint static friction coefficient. Shape is (num_instances, num_joints). + joint_friction_coeff: Backend-specific joint friction values. Shape is (num_instances, num_joints). joint_mask: Joint mask. If None, then all the joints are updated. Shape is (num_joints,). env_mask: Environment mask. If None, then all the instances are updated. Shape is (num_instances,). """ diff --git a/source/isaaclab/isaaclab/assets/articulation/base_articulation_data.py b/source/isaaclab/isaaclab/assets/articulation/base_articulation_data.py index 1a2dc5f1b278..b902db7d29bb 100644 --- a/source/isaaclab/isaaclab/assets/articulation/base_articulation_data.py +++ b/source/isaaclab/isaaclab/assets/articulation/base_articulation_data.py @@ -248,9 +248,14 @@ def joint_armature(self) -> ProxyArray: @abstractmethod @leapp_tensor_semantics(const=True) def joint_friction_coeff(self) -> ProxyArray: - """Joint static friction coefficient provided to the simulation. + """Backend-specific joint friction values provided to the simulation. Shape is (num_instances, num_joints), dtype = wp.float32. In torch this resolves to (num_instances, num_joints). + + .. warning:: + The physical meaning and units of this value depend on the concrete backend and solver. Do not assume + values are comparable across backends; check the backend-specific :class:`ArticulationData` + implementation before interpreting or reusing them. """ raise NotImplementedError diff --git a/source/isaaclab_newton/changelog.d/antoiner-docs-joint-friction.rst b/source/isaaclab_newton/changelog.d/antoiner-docs-joint-friction.rst new file mode 100644 index 000000000000..e84764b739c9 --- /dev/null +++ b/source/isaaclab_newton/changelog.d/antoiner-docs-joint-friction.rst @@ -0,0 +1,5 @@ +Fixed +^^^^^ + +* Fixed :class:`~isaaclab_newton.assets.Articulation` joint friction docs to identify Newton friction as a force or + torque value instead of a unitless coefficient. diff --git a/source/isaaclab_newton/isaaclab_newton/assets/articulation/articulation.py b/source/isaaclab_newton/isaaclab_newton/assets/articulation/articulation.py index c3c6eca044f7..ff04b96c63ca 100644 --- a/source/isaaclab_newton/isaaclab_newton/assets/articulation/articulation.py +++ b/source/isaaclab_newton/isaaclab_newton/assets/articulation/articulation.py @@ -1964,7 +1964,19 @@ def write_joint_friction_coefficient_to_sim_index( joint_ids: Sequence[int] | torch.Tensor | wp.array | None = None, env_ids: Sequence[int] | torch.Tensor | wp.array | None = None, ): - r"""Write joint friction coefficients over selected environment indices into the simulation. + r"""Write Newton joint friction force/torque values over selected environment indices into the simulation. + + This writes to Newton's ``Model.joint_friction`` field. Despite the ``coeff`` suffix in the Isaac Lab API + name, Newton treats this value as an absolute friction force/torque [N or N·m, depending on joint type], not + as a unitless coefficient. + + For example, the MJWarp solver copies this value into MuJoCo Warp's ``dof_frictionloss``. Setting + ``joint_friction_coeff`` to 0.2 configures a dry-friction loss limit of 0.2 N·m on a revolute joint DOF, + or 0.2 N on a prismatic joint DOF. + + .. note:: + Solver support is defined by the active Newton solver. Unsupported solvers may ignore + ``Model.joint_friction``. .. note:: This method expects partial data. @@ -1974,7 +1986,7 @@ def write_joint_friction_coefficient_to_sim_index( However, to allow graphed pipelines, the mask method must be used. Args: - joint_friction_coeff: Static friction coefficient :math:`\mu_s`. + joint_friction_coeff: Joint friction force/torque [N or N·m, depending on joint type]. Shape is (len(env_ids), len(joint_ids)). joint_ids: Joint indices. If None, then all joints are used. env_ids: Environment indices. If None, then all indices are used. @@ -2024,7 +2036,19 @@ def write_joint_friction_coefficient_to_sim_mask( joint_mask: wp.array | None = None, env_mask: wp.array | None = None, ): - r"""Write joint friction coefficients over selected environment mask into the simulation. + r"""Write Newton joint friction force/torque values over selected environment mask into the simulation. + + This writes to Newton's ``Model.joint_friction`` field. Despite the ``coeff`` suffix in the Isaac Lab API + name, Newton treats this value as an absolute friction force/torque [N or N·m, depending on joint type], not + as a unitless coefficient. + + For example, the MJWarp solver copies this value into MuJoCo Warp's ``dof_frictionloss``. Setting + ``joint_friction_coeff`` to 0.2 configures a dry-friction loss limit of 0.2 N·m on a revolute joint DOF, + or 0.2 N on a prismatic joint DOF. + + .. note:: + Solver support is defined by the active Newton solver. Unsupported solvers may ignore + ``Model.joint_friction``. .. note:: This method expects full data. @@ -2034,7 +2058,7 @@ def write_joint_friction_coefficient_to_sim_mask( However, to allow graphed pipelines, the mask method must be used. Args: - joint_friction_coeff: Static friction coefficient :math:`\mu_s`. + joint_friction_coeff: Joint friction force/torque [N or N·m, depending on joint type]. Shape is (num_instances, num_joints). joint_mask: Joint mask. If None, then all joints are used. Shape is (num_joints,). env_mask: Environment mask. If None, then all the instances are updated. Shape is (num_instances,). diff --git a/source/isaaclab_newton/isaaclab_newton/assets/articulation/articulation_data.py b/source/isaaclab_newton/isaaclab_newton/assets/articulation/articulation_data.py index a22ba73e1725..2da95b49b21d 100644 --- a/source/isaaclab_newton/isaaclab_newton/assets/articulation/articulation_data.py +++ b/source/isaaclab_newton/isaaclab_newton/assets/articulation/articulation_data.py @@ -342,7 +342,14 @@ def joint_armature(self) -> ProxyArray: @property def joint_friction_coeff(self) -> ProxyArray: - """Joint static friction coefficient provided to the simulation. + """Newton joint friction force/torque provided to the simulation. + + Despite the ``coeff`` suffix in the Isaac Lab API name, Newton stores this as an absolute joint friction + force/torque [N or N·m, depending on joint type]. + + For example, the MJWarp solver copies this value into MuJoCo Warp's ``dof_frictionloss``. Setting + ``joint_friction_coeff`` to 0.2 configures a dry-friction loss limit of 0.2 N·m on a revolute joint DOF, + or 0.2 N on a prismatic joint DOF. Shape is (num_instances, num_joints), dtype = wp.float32. In torch this resolves to (num_instances, num_joints). """ diff --git a/source/isaaclab_physx/changelog.d/antoiner-docs-joint-friction.rst b/source/isaaclab_physx/changelog.d/antoiner-docs-joint-friction.rst new file mode 100644 index 000000000000..652271d896b1 --- /dev/null +++ b/source/isaaclab_physx/changelog.d/antoiner-docs-joint-friction.rst @@ -0,0 +1,5 @@ +Fixed +^^^^^ + +* Fixed :class:`~isaaclab_physx.assets.Articulation` joint friction docs to distinguish legacy coefficients from + PhysX 5 static and dynamic friction efforts. diff --git a/source/isaaclab_physx/isaaclab_physx/assets/articulation/articulation.py b/source/isaaclab_physx/isaaclab_physx/assets/articulation/articulation.py index 913914e29f30..6258b5c5b8e4 100644 --- a/source/isaaclab_physx/isaaclab_physx/assets/articulation/articulation.py +++ b/source/isaaclab_physx/isaaclab_physx/assets/articulation/articulation.py @@ -1684,16 +1684,23 @@ def write_joint_friction_coefficient_to_sim_index( ): r"""Write joint friction coefficients over selected environment indices into the simulation. - For Isaac Sim versions below 5.0, only the static friction coefficient is set. - This limits the resisting force or torque up to a maximum proportional to the transmitted - spatial force: :math:`\|F_{resist}\| \leq \mu_s \, \|F_{spatial}\|`. + For Isaac Sim versions below 5.0, only the legacy unitless joint friction coefficient is set. + This limits the resisting force or torque up to a maximum proportional to the transmitted spatial force: + :math:`\|F_{resist}\| \leq \mu_s \, \|F_{spatial}\|`. - For Isaac Sim versions 5.0 and above, the static, dynamic, and viscous friction coefficients - are set. The model combines Coulomb (static & dynamic) friction with a viscous term: + For Isaac Sim versions 5.0 and above, the PhysX joint friction parameter model is used. It combines + Coulomb (static and dynamic) friction with a viscous term: - - Static friction :math:`\mu_s` defines the maximum effort that prevents motion at rest. - - Dynamic friction :math:`\mu_d` applies once motion begins and remains constant during motion. - - Viscous friction :math:`c_v` is a velocity-proportional resistive term. + - Static friction effort defines the maximum effort that prevents motion at rest [N or N·m, depending on + joint type]. + - Dynamic friction effort applies once motion begins and remains constant during motion [N or N·m, + depending on joint type]. + - Viscous friction coefficient is a velocity-proportional resistive term [N·s/m or N·m·s/rad, depending + on joint type]. + + .. warning:: + For Isaac Sim versions 5.0 and above, the static friction effort must be greater than or equal to the + dynamic friction effort. .. note:: This method expects partial data or full data. @@ -1703,11 +1710,12 @@ def write_joint_friction_coefficient_to_sim_index( is only supporting indexing, hence masks need to be converted to indices. Args: - joint_friction_coeff: Static friction coefficient :math:`\mu_s`. - Shape is (len(env_ids), len(joint_ids)) or (num_instances, num_joints). - joint_dynamic_friction_coeff: Dynamic (Coulomb) friction coefficient :math:`\mu_d`. + joint_friction_coeff: Legacy unitless coefficient for Isaac Sim versions below 5.0, or static friction + effort [N or N·m, depending on joint type] for Isaac Sim versions 5.0 and above. Shape is + (len(env_ids), len(joint_ids)) or (num_instances, num_joints). + joint_dynamic_friction_coeff: Dynamic friction effort [N or N·m, depending on joint type]. Same shape as above. If None, the dynamic coefficient is not updated. - joint_viscous_friction_coeff: Viscous friction coefficient :math:`c_v`. + joint_viscous_friction_coeff: Viscous friction coefficient [N·s/m or N·m·s/rad, depending on joint type]. Same shape as above. If None, the viscous coefficient is not updated. joint_ids: Joint indices. If None, then all joints are used. env_ids: Environment indices. If None, then all indices are used. @@ -1793,16 +1801,23 @@ def write_joint_friction_coefficient_to_sim_mask( ): r"""Write joint friction coefficients over selected environment mask into the simulation. - For Isaac Sim versions below 5.0, only the static friction coefficient is set. - This limits the resisting force or torque up to a maximum proportional to the transmitted - spatial force: :math:`\|F_{resist}\| \leq \mu_s \, \|F_{spatial}\|`. + For Isaac Sim versions below 5.0, only the legacy unitless joint friction coefficient is set. + This limits the resisting force or torque up to a maximum proportional to the transmitted spatial force: + :math:`\|F_{resist}\| \leq \mu_s \, \|F_{spatial}\|`. + + For Isaac Sim versions 5.0 and above, the PhysX joint friction parameter model is used. It combines + Coulomb (static and dynamic) friction with a viscous term: - For Isaac Sim versions 5.0 and above, the static, dynamic, and viscous friction coefficients - are set. The model combines Coulomb (static & dynamic) friction with a viscous term: + - Static friction effort defines the maximum effort that prevents motion at rest [N or N·m, depending on + joint type]. + - Dynamic friction effort applies once motion begins and remains constant during motion [N or N·m, + depending on joint type]. + - Viscous friction coefficient is a velocity-proportional resistive term [N·s/m or N·m·s/rad, depending + on joint type]. - - Static friction :math:`\mu_s` defines the maximum effort that prevents motion at rest. - - Dynamic friction :math:`\mu_d` applies once motion begins and remains constant during motion. - - Viscous friction :math:`c_v` is a velocity-proportional resistive term. + .. warning:: + For Isaac Sim versions 5.0 and above, the static friction effort must be greater than or equal to the + dynamic friction effort. .. note:: This method expects full data. @@ -1812,11 +1827,12 @@ def write_joint_friction_coefficient_to_sim_mask( is only supporting indexing, hence masks need to be converted to indices. Args: - joint_friction_coeff: Static friction coefficient :math:`\mu_s`. - Shape is (num_instances, num_joints). - joint_dynamic_friction_coeff: Dynamic (Coulomb) friction coefficient :math:`\mu_d`. + joint_friction_coeff: Legacy unitless coefficient for Isaac Sim versions below 5.0, or static friction + effort [N or N·m, depending on joint type] for Isaac Sim versions 5.0 and above. Shape is + (num_instances, num_joints). + joint_dynamic_friction_coeff: Dynamic friction effort [N or N·m, depending on joint type]. Same shape as above. If None, the dynamic coefficient is not updated. - joint_viscous_friction_coeff: Viscous friction coefficient :math:`c_v`. + joint_viscous_friction_coeff: Viscous friction coefficient [N·s/m or N·m·s/rad, depending on joint type]. Same shape as above. If None, the viscous coefficient is not updated. joint_mask: Joint mask. If None, then all joints are used. env_mask: Environment mask. If None, then all the instances are updated. Shape is (num_instances,). @@ -1842,7 +1858,9 @@ def write_joint_dynamic_friction_coefficient_to_sim_index( env_ids: Sequence[int] | torch.Tensor | wp.array | None = None, full_data: bool = False, ) -> None: - """Write joint dynamic friction coefficient over selected environment indices into the simulation. + """Write joint dynamic friction effort over selected environment indices into the simulation. + + The dynamic friction effort is [N or N·m, depending on joint type]. .. note:: This method expects partial data or full data. @@ -1852,8 +1870,8 @@ def write_joint_dynamic_friction_coefficient_to_sim_index( is only supporting indexing, hence masks need to be converted to indices. Args: - joint_dynamic_friction_coeff: Joint dynamic friction coefficient. Shape is (len(env_ids), len(joint_ids)) - or (num_instances, num_joints) if full_data. + joint_dynamic_friction_coeff: Dynamic friction effort [N or N·m, depending on joint type]. Shape is + (len(env_ids), len(joint_ids)) or (num_instances, num_joints) if full_data. joint_ids: Joint indices. If None, then all joints are used. env_ids: Environment indices. If None, then all indices are used. full_data: Whether to expect full data. Defaults to False. @@ -1907,7 +1925,9 @@ def write_joint_dynamic_friction_coefficient_to_sim_mask( joint_mask: wp.array | None = None, env_mask: wp.array | None = None, ) -> None: - """Write joint dynamic friction coefficient over selected environment mask into the simulation. + """Write joint dynamic friction effort over selected environment mask into the simulation. + + The dynamic friction effort is [N or N·m, depending on joint type]. .. note:: This method expects full data. @@ -1917,7 +1937,8 @@ def write_joint_dynamic_friction_coefficient_to_sim_mask( is only supporting indexing, hence masks need to be converted to indices. Args: - joint_dynamic_friction_coeff: Joint dynamic friction coefficient. Shape is (num_instances, num_joints). + joint_dynamic_friction_coeff: Dynamic friction effort [N or N·m, depending on joint type]. Shape is + (num_instances, num_joints). joint_mask: Joint mask. If None, then all joints are used. env_mask: Environment mask. If None, then all the instances are updated. Shape is (num_instances,). """ @@ -1942,6 +1963,8 @@ def write_joint_viscous_friction_coefficient_to_sim_index( ) -> None: """Write joint viscous friction coefficient over selected environment indices into the simulation. + The coefficient is [N·s/m or N·m·s/rad, depending on joint type]. + .. note:: This method expects partial data or full data. @@ -1950,8 +1973,8 @@ def write_joint_viscous_friction_coefficient_to_sim_index( is only supporting indexing, hence masks need to be converted to indices. Args: - joint_viscous_friction_coeff: Joint viscous friction coefficient. Shape is (len(env_ids), len(joint_ids)) - or (num_instances, num_joints) if full_data. + joint_viscous_friction_coeff: Viscous friction coefficient [N·s/m or N·m·s/rad, depending on joint type]. + Shape is (len(env_ids), len(joint_ids)) or (num_instances, num_joints) if full_data. joint_ids: Joint indices. If None, then all joints are used. env_ids: Environment indices. If None, then all indices are used. full_data: Whether to expect full data. Defaults to False. @@ -2010,6 +2033,8 @@ def write_joint_viscous_friction_coefficient_to_sim_mask( ) -> None: """Write joint viscous friction coefficient over selected environment mask into the simulation. + The coefficient is [N·s/m or N·m·s/rad, depending on joint type]. + .. note:: This method expects full data. @@ -2018,7 +2043,8 @@ def write_joint_viscous_friction_coefficient_to_sim_mask( is only supporting indexing, hence masks need to be converted to indices. Args: - joint_viscous_friction_coeff: Joint viscous friction coefficient. Shape is (num_instances, num_joints). + joint_viscous_friction_coeff: Viscous friction coefficient [N·s/m or N·m·s/rad, depending on joint type]. + Shape is (num_instances, num_joints). joint_mask: Joint mask. If None, then all joints are used. env_mask: Environment mask. If None, then all the instances are updated. Shape is (num_instances,). """ diff --git a/source/isaaclab_physx/isaaclab_physx/assets/articulation/articulation_data.py b/source/isaaclab_physx/isaaclab_physx/assets/articulation/articulation_data.py index 8c2056d9cbfa..3d7e6e9cb483 100644 --- a/source/isaaclab_physx/isaaclab_physx/assets/articulation/articulation_data.py +++ b/source/isaaclab_physx/isaaclab_physx/assets/articulation/articulation_data.py @@ -369,7 +369,10 @@ def joint_armature(self) -> ProxyArray: @property def joint_friction_coeff(self) -> ProxyArray: - """Joint static friction coefficient provided to the simulation. + """PhysX joint static friction value provided to the simulation. + + For Isaac Sim 5.0 and later, this is the static friction effort [N or N·m, depending on joint type]. + For earlier Isaac Sim versions, this is the legacy unitless joint friction coefficient. Shape is (num_instances, num_joints), dtype = wp.float32. In torch this resolves to (num_instances, num_joints). """ @@ -379,7 +382,9 @@ def joint_friction_coeff(self) -> ProxyArray: @property def joint_dynamic_friction_coeff(self) -> ProxyArray: - """Joint dynamic friction coefficient provided to the simulation. + """PhysX joint dynamic friction effort provided to the simulation. + + The effort is [N or N·m, depending on joint type]. Shape is (num_instances, num_joints), dtype = wp.float32. In torch this resolves to (num_instances, num_joints). """ @@ -391,6 +396,8 @@ def joint_dynamic_friction_coeff(self) -> ProxyArray: def joint_viscous_friction_coeff(self) -> ProxyArray: """Joint viscous friction coefficient provided to the simulation. + The coefficient is [N·s/m or N·m·s/rad, depending on joint type]. + Shape is (num_instances, num_joints), dtype = wp.float32. In torch this resolves to (num_instances, num_joints). """ if self._joint_viscous_friction_coeff_ta is None: From 8c5e2ad030d80b58cecbcf94995d6b1e4d468d6a Mon Sep 17 00:00:00 2001 From: Antoine RICHARD Date: Fri, 8 May 2026 09:26:17 +0200 Subject: [PATCH 14/51] Deprecates state properties calls (#5423) # Description Reduce higher-level dependency on packed state tensors in targeted IsaacLab call sites without changing existing task observation keys. This PR: - changes Pink IK to read `body_link_pose_w` directly instead of slicing `body_link_state_w`; - changes Dexsuite orientation rewards to use `root_link_quat_w` directly instead of slicing `root_state_w`; - adds explicit pick-place helpers for robot link pose and velocity; - keeps `get_all_robot_link_state()` available for compatibility, but marks it deprecated for removal in IsaacLab 4.0; - keeps existing `robot_links_state` task config entries unchanged. Fixes # (issue) ## Type of change - Bug fix (non-breaking change which fixes an issue) - Documentation update ## Screenshots N/A ## Test Plan - `./isaaclab.sh -p -m py_compile source/isaaclab/isaaclab/envs/mdp/__init__.pyi source/isaaclab/isaaclab/envs/mdp/actions/pink_task_space_actions.py source/isaaclab/isaaclab/envs/mdp/observations.py source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/pick_place/mdp/__init__.pyi source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/pick_place/mdp/observations.py source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/dexsuite/mdp/rewards.py` - `./isaaclab.sh -f` - `git diff --check origin/develop..HEAD` - `rg -n "body_link_state_w|root_state_w" source/isaaclab/isaaclab/envs/mdp/actions/pink_task_space_actions.py source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/pick_place/mdp/observations.py source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/dexsuite/mdp/rewards.py` (no matches) - Existing/new MDP pytest not run locally. Per review, new MDP tests were removed and should be added in a separate PR. Local pytest collection is also blocked in this worktree because `./isaaclab.sh -p` selects `/usr/bin/python3.12` without `torch`. ## Checklist - [x] I have read and understood the [contribution guidelines](https://isaac-sim.github.io/IsaacLab/main/source/refs/contributing.html) - [x] I have run the [`pre-commit` checks](https://pre-commit.com/) with `./isaaclab.sh --format` - [x] I have made corresponding changes to the documentation - [ ] My changes generate no new warnings - [ ] 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 Notes: - The unchecked warning item is intentional: this PR adds a `DeprecationWarning` to `get_all_robot_link_state()` so users can migrate before IsaacLab 4.0. - The unchecked test item follows review feedback: MDP tests should be added in a separate PR. --- .../pr-5423-state-observation-mdp.rst | 6 ++++ .../mdp/actions/pink_task_space_actions.py | 2 +- .../pr-5423-state-observation-mdp.rst | 21 ++++++++++++ .../manipulation/dexsuite/mdp/rewards.py | 3 +- .../manipulation/pick_place/mdp/__init__.pyi | 4 +++ .../pick_place/mdp/observations.py | 33 ++++++++++++++++--- 6 files changed, 62 insertions(+), 7 deletions(-) create mode 100644 source/isaaclab/changelog.d/pr-5423-state-observation-mdp.rst create mode 100644 source/isaaclab_tasks/changelog.d/pr-5423-state-observation-mdp.rst diff --git a/source/isaaclab/changelog.d/pr-5423-state-observation-mdp.rst b/source/isaaclab/changelog.d/pr-5423-state-observation-mdp.rst new file mode 100644 index 000000000000..62193bc0796f --- /dev/null +++ b/source/isaaclab/changelog.d/pr-5423-state-observation-mdp.rst @@ -0,0 +1,6 @@ +Changed +^^^^^^^ + +* Changed the Pink IK task-space action base link frame lookup to read direct + body link pose data instead of slicing packed body link state. No user + migration is required. diff --git a/source/isaaclab/isaaclab/envs/mdp/actions/pink_task_space_actions.py b/source/isaaclab/isaaclab/envs/mdp/actions/pink_task_space_actions.py index 3cb4450805b2..f826c80d51eb 100644 --- a/source/isaaclab/isaaclab/envs/mdp/actions/pink_task_space_actions.py +++ b/source/isaaclab/isaaclab/envs/mdp/actions/pink_task_space_actions.py @@ -218,7 +218,7 @@ def _get_base_link_frame_transform(self) -> torch.Tensor: """ # Get base link frame pose in world origin using cached index articulation_data = self._env.scene[self.cfg.controller.articulation_name].data - base_link_frame_in_world_origin = articulation_data.body_link_state_w.torch[:, self._base_link_idx, :7] + base_link_frame_in_world_origin = articulation_data.body_link_pose_w.torch[:, self._base_link_idx] # Transform to environment origin frame (reuse buffer to avoid allocation) torch.sub( diff --git a/source/isaaclab_tasks/changelog.d/pr-5423-state-observation-mdp.rst b/source/isaaclab_tasks/changelog.d/pr-5423-state-observation-mdp.rst new file mode 100644 index 000000000000..655f379a939a --- /dev/null +++ b/source/isaaclab_tasks/changelog.d/pr-5423-state-observation-mdp.rst @@ -0,0 +1,21 @@ +Added +^^^^^ + +* Added explicit GR1T2 and Unitree G1 pick-place robot link pose and velocity + MDP helpers as replacements for packed robot link state observations. + +Changed +^^^^^^^ + +* Changed Dexsuite orientation tracking rewards to read root link orientation + directly instead of slicing packed root state tensors. + +Deprecated +^^^^^^^^^^ + +* Deprecated + :func:`~isaaclab_tasks.manager_based.manipulation.pick_place.mdp.observations.get_all_robot_link_state` + in favor of + :func:`~isaaclab_tasks.manager_based.manipulation.pick_place.mdp.observations.get_all_robot_link_pose` + and + :func:`~isaaclab_tasks.manager_based.manipulation.pick_place.mdp.observations.get_all_robot_link_velocity`. diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/dexsuite/mdp/rewards.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/dexsuite/mdp/rewards.py index 8a5a013ea846..9e8b084afbae 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/dexsuite/mdp/rewards.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/dexsuite/mdp/rewards.py @@ -219,8 +219,7 @@ def orientation_command_error_tanh( obj: RigidObject = env.scene[align_asset_cfg.name] command = env.command_manager.get_command(command_name) des_quat_b = command[:, 3:7] - root_state = asset.data.root_state_w.torch - des_quat_w = math_utils.quat_mul(root_state[:, 3:7], des_quat_b) + des_quat_w = math_utils.quat_mul(asset.data.root_link_quat_w.torch, des_quat_b) quat_distance = math_utils.quat_error_magnitude(obj.data.root_quat_w.torch, des_quat_w) return (1 - torch.tanh(quat_distance / std)) * contacts(env, contact_threshold, thumb_name, finger_names).float() diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/pick_place/mdp/__init__.pyi b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/pick_place/mdp/__init__.pyi index 1421a52bc546..de6c777b49c1 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/pick_place/mdp/__init__.pyi +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/pick_place/mdp/__init__.pyi @@ -4,7 +4,9 @@ # SPDX-License-Identifier: BSD-3-Clause __all__ = [ + "get_all_robot_link_pose", "get_all_robot_link_state", + "get_all_robot_link_velocity", "get_eef_pos", "get_eef_quat", "get_robot_joint_state", @@ -16,7 +18,9 @@ __all__ = [ ] from .observations import ( + get_all_robot_link_pose, get_all_robot_link_state, + get_all_robot_link_velocity, get_eef_pos, get_eef_quat, get_robot_joint_state, diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/pick_place/mdp/observations.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/pick_place/mdp/observations.py index c3e030b33ec0..cedc6507d78c 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/pick_place/mdp/observations.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/pick_place/mdp/observations.py @@ -5,6 +5,7 @@ from __future__ import annotations +import warnings from typing import TYPE_CHECKING import torch @@ -77,10 +78,34 @@ def get_robot_joint_state( return robot_joint_states +def get_all_robot_link_pose(env: ManagerBasedRLEnv) -> torch.Tensor: + """Robot link poses in the world frame. + + Returns: + Link poses with shape ``[num_envs, num_bodies, 7]`` and layout + ``[x, y, z, qx, qy, qz, qw]`` where position is in ``[m]``. + """ + return env.scene["robot"].data.body_link_pose_w.torch + + +def get_all_robot_link_velocity(env: ManagerBasedRLEnv) -> torch.Tensor: + """Robot link velocities in the world frame. + + Returns: + Link velocities with shape ``[num_envs, num_bodies, 6]`` and layout + ``[linear_velocity(3), angular_velocity(3)]`` in ``[m/s, rad/s]``. + """ + return env.scene["robot"].data.body_link_vel_w.torch + + def get_all_robot_link_state( env: ManagerBasedRLEnv, ) -> torch.Tensor: - body_pos_w = env.scene["robot"].data.body_link_state_w.torch[:, :, :] - all_robot_link_pos = body_pos_w - - return all_robot_link_pos + # TODO: Remove this compatibility helper in IsaacLab 4.0. + warnings.warn( + "`get_all_robot_link_state` is deprecated and will be removed in IsaacLab 4.0. " + "Use `get_all_robot_link_pose` and `get_all_robot_link_velocity` instead.", + DeprecationWarning, + stacklevel=2, + ) + return torch.cat((get_all_robot_link_pose(env), get_all_robot_link_velocity(env)), dim=-1) From 311ec73098084b7b6e20327a7ba7ce70e73c49af Mon Sep 17 00:00:00 2001 From: Antoine RICHARD Date: Fri, 8 May 2026 09:31:32 +0200 Subject: [PATCH 15/51] Fixes backend deprecation warning call sites (#5418) ## Summary - Updated PhysX and Newton backend tests to use the current root-state, joint-state, contact-sensor, and wrench-composer API names. - Updated the Newton contact sensor adapter to use the current SensorContact constructor and force/metadata fields. - Bumped matching PhysX and Newton extension changelog/version files. ## Test Plan - [x] ./isaaclab.sh -p -m py_compile source/isaaclab_physx/test/sensors/test_frame_transformer.py source/isaaclab_newton/test/sensors/test_frame_transformer.py source/isaaclab_physx/test/sensors/test_contact_sensor.py source/isaaclab_newton/isaaclab_newton/physics/newton_manager.py source/isaaclab_newton/isaaclab_newton/sensors/contact_sensor/contact_sensor.py source/isaaclab_newton/isaaclab_newton/sensors/contact_sensor/contact_sensor_kernels.py - [x] ./isaaclab.sh -f - [x] Focused deprecation scan: 118 matches on origin/develop, 0 matches on this branch - [ ] Targeted GPU pytest on NvidiaWorkstation-WiFi: attempted in isaac-lab-base-pr5304:latest, but the PhysX container timed out after 3600s during pytest collection before tests ran --- ...er-backend-deprecation-warning-cleanup.rst | 6 + .../isaaclab_newton/physics/newton_manager.py | 2 +- .../sensors/contact_sensor/contact_sensor.py | 58 ++++++--- .../contact_sensor/contact_sensor_kernels.py | 11 +- .../test/assets/test_articulation.py | 20 +-- .../test/assets/test_rigid_object.py | 12 +- .../assets/test_rigid_object_collection.py | 12 +- .../test/sensors/test_frame_transformer.py | 120 +++++++++++++----- ...er-backend-deprecation-warning-cleanup.rst | 5 + .../test/assets/test_articulation.py | 20 +-- .../test/assets/test_rigid_object.py | 16 +-- .../assets/test_rigid_object_collection.py | 12 +- .../test/sensors/test_contact_sensor.py | 22 ++-- .../test/sensors/test_frame_transformer.py | 120 +++++++++++++----- 14 files changed, 288 insertions(+), 148 deletions(-) create mode 100644 source/isaaclab_newton/changelog.d/antoiner-backend-deprecation-warning-cleanup.rst create mode 100644 source/isaaclab_physx/changelog.d/antoiner-backend-deprecation-warning-cleanup.rst diff --git a/source/isaaclab_newton/changelog.d/antoiner-backend-deprecation-warning-cleanup.rst b/source/isaaclab_newton/changelog.d/antoiner-backend-deprecation-warning-cleanup.rst new file mode 100644 index 000000000000..2fd8df763f82 --- /dev/null +++ b/source/isaaclab_newton/changelog.d/antoiner-backend-deprecation-warning-cleanup.rst @@ -0,0 +1,6 @@ +Fixed +^^^^^ + +* Fixed :class:`~isaaclab_newton.sensors.contact_sensor.ContactSensor` to use + current Newton contact sensor API names, removing deprecation warnings from + Newton contact sensor test runs. diff --git a/source/isaaclab_newton/isaaclab_newton/physics/newton_manager.py b/source/isaaclab_newton/isaaclab_newton/physics/newton_manager.py index dbc85e97c270..97535fb8a328 100644 --- a/source/isaaclab_newton/isaaclab_newton/physics/newton_manager.py +++ b/source/isaaclab_newton/isaaclab_newton/physics/newton_manager.py @@ -1351,7 +1351,7 @@ def _normalize_for_labels(expr: str | list[str] | None, labels: list[str]) -> st sensing_obj_shapes=_normalize_for_labels(_to_fnmatch(shape_names_expr), shape_labels), counterpart_bodies=_normalize_for_labels(_to_fnmatch(contact_partners_body_expr), body_labels), counterpart_shapes=_normalize_for_labels(_to_fnmatch(contact_partners_shape_expr), shape_labels), - include_total=True, + measure_total=True, verbose=verbose, ) diff --git a/source/isaaclab_newton/isaaclab_newton/sensors/contact_sensor/contact_sensor.py b/source/isaaclab_newton/isaaclab_newton/sensors/contact_sensor/contact_sensor.py index 02850e9cc903..43e878fecbfb 100644 --- a/source/isaaclab_newton/isaaclab_newton/sensors/contact_sensor/contact_sensor.py +++ b/source/isaaclab_newton/isaaclab_newton/sensors/contact_sensor/contact_sensor.py @@ -322,17 +322,17 @@ def _initialize_impl(self): raise RuntimeError(self._init_error) from err def _create_buffers(self): - # Get Newton sensor shape: (n_sensors * n_envs, n_counterparts) - newton_shape = self.contact_view.shape + # Get Newton sensor count from total force: (n_sensors * n_envs) + total_sensor_count = self.contact_view.total_force.shape[0] # resolve the true count of sensors - self._num_sensors = newton_shape[0] // self._num_envs + self._num_sensors = total_sensor_count // self._num_envs # Check that number of sensors is an integer - if newton_shape[0] % self._num_envs != 0: + if total_sensor_count % self._num_envs != 0: raise RuntimeError( "Number of sensors is not an integer multiple of the number of environments. Received:" - f" {newton_shape[0]} sensors across {self._num_envs} environments." + f" {total_sensor_count} sensors across {self._num_envs} environments." ) if self._num_sensors == 0: raise RuntimeError( @@ -350,25 +350,49 @@ def get_name(idx, kind): kind_name = getattr(kind, "name", None) kind_value = getattr(kind, "value", kind) if kind_name == "BODY" or kind_value == 2: - return body_labels[idx].split("/")[-1] + return body_labels[int(idx)].split("/")[-1] if kind_name == "SHAPE" or kind_value == 1: - return shape_labels[idx].split("/")[-1] + return shape_labels[int(idx)].split("/")[-1] return "MATCH_ANY" - flat_sensing = [obj for world_objs in self.contact_view.sensing_objs for obj in world_objs] + def flatten_metadata(values): + if isinstance(values, wp.array): + values = values.numpy() + flat_values = np.asarray(values, dtype=object).reshape(-1).tolist() + if flat_values and isinstance(flat_values[0], list | tuple | np.ndarray): + return [ + value + for nested_values in flat_values + for value in np.asarray(nested_values, dtype=object).reshape(-1).tolist() + ] + return flat_values + + flat_sensing = list( + zip( + flatten_metadata(self.contact_view.sensing_obj_idx), + flatten_metadata(self.contact_view.sensing_obj_type), + ) + ) self._sensor_names = [get_name(idx, kind) for idx, kind in flat_sensing] # Assumes the environments are processed in order. self._sensor_names = self._sensor_names[: self._num_sensors] - flat_counterparts = [obj for world_objs in self.contact_view.counterparts for obj in world_objs] + flat_counterparts = list( + zip( + flatten_metadata(self.contact_view.counterpart_indices), + flatten_metadata(self.contact_view.counterpart_type), + ) + ) self._filter_object_names = [get_name(idx, kind) for idx, kind in flat_counterparts] - # Number of filter objects (counterparts minus the total column) - self._num_filter_objects = max(newton_shape[1] - 1, 0) + force_matrix = self.contact_view.force_matrix + force_matrix_shape = force_matrix.shape if force_matrix is not None else (total_sensor_count, 0) + # Number of filter objects. + self._num_filter_objects = force_matrix_shape[1] if len(force_matrix_shape) > 1 else 0 - # Store reshaped Newton net_force view for copying data - # Newton net_force shape: (n_sensors * n_envs, n_counterparts) - # Reshaped to: (n_envs, n_sensors, n_counterparts) - self._newton_forces_view = self.contact_view.net_force.reshape((self._num_envs, self._num_sensors, -1)) + # Store flat Newton force views for copying data. These may be non-contiguous + # views, so the copy kernel indexes them without reshaping. + self._newton_total_force_view = self.contact_view.total_force + self._newton_force_matrix_view = force_matrix if self._num_filter_objects > 0 else None # prepare data buffers logger.info( @@ -413,7 +437,9 @@ def _update_buffers_impl(self, env_mask: wp.array): dim=(self._num_envs, self._num_sensors, max(self._num_filter_objects, 1)), inputs=[ env_mask, - self._newton_forces_view, + self._num_sensors, + self._newton_total_force_view, + self._newton_force_matrix_view, ], outputs=[ self._data._net_forces_w, diff --git a/source/isaaclab_newton/isaaclab_newton/sensors/contact_sensor/contact_sensor_kernels.py b/source/isaaclab_newton/isaaclab_newton/sensors/contact_sensor/contact_sensor_kernels.py index 324f0106682f..81fef0bcab63 100644 --- a/source/isaaclab_newton/isaaclab_newton/sensors/contact_sensor/contact_sensor_kernels.py +++ b/source/isaaclab_newton/isaaclab_newton/sensors/contact_sensor/contact_sensor_kernels.py @@ -13,7 +13,9 @@ def copy_from_newton_kernel( # in env_mask: wp.array(dtype=wp.bool), - newton_forces: wp.array3d(dtype=wp.vec3f), # (n_envs, n_sensors, n_counterparts) + num_sensors: int, + newton_total_force: wp.array(dtype=wp.vec3f), # (n_envs * n_sensors) + newton_force_matrix: wp.array2d(dtype=wp.vec3f), # (n_envs * n_sensors, n_filter_objects) or None # outputs net_force_total: wp.array2d(dtype=wp.vec3f), # (n_envs, n_sensors) force_matrix: wp.array3d(dtype=wp.vec3f), # (n_envs, n_sensors, n_filter_objects) or None @@ -30,13 +32,14 @@ def copy_from_newton_kernel( return # Copy total force (column 0) - only thread with f_idx == 0 does this + src_idx = env * num_sensors + sensor if f_idx == 0: - net_force_total[env, sensor] = newton_forces[env, sensor, 0] + net_force_total[env, sensor] = newton_total_force[src_idx] - # Copy per-filter-object forces (columns 1+) + # Copy per-filter-object forces. # Guard with `if force_matrix:` to handle None case (no filter objects) if force_matrix: - force_matrix[env, sensor, f_idx] = newton_forces[env, sensor, f_idx + 1] + force_matrix[env, sensor, f_idx] = newton_force_matrix[src_idx, f_idx] @wp.kernel diff --git a/source/isaaclab_newton/test/assets/test_articulation.py b/source/isaaclab_newton/test/assets/test_articulation.py index a392e7773468..fdb335291fa5 100644 --- a/source/isaaclab_newton/test/assets/test_articulation.py +++ b/source/isaaclab_newton/test/assets/test_articulation.py @@ -983,8 +983,8 @@ def test_external_force_buffer(sim, num_articulations, device, articulation_type # check if the articulation's force and torque buffers are correctly updated for i in range(num_articulations): - assert articulation.permanent_wrench_composer.composed_force.torch[i, 0, 0].item() == force - assert articulation.permanent_wrench_composer.composed_torque.torch[i, 0, 0].item() == force + assert articulation.permanent_wrench_composer.out_force_b.torch[i, 0, 0].item() == force + assert articulation.permanent_wrench_composer.out_torque_b.torch[i, 0, 0].item() == force # Check if the instantaneous wrench is correctly added to the permanent wrench articulation.instantaneous_wrench_composer.add_forces_and_torques_index( @@ -1724,10 +1724,10 @@ def test_reset(sim, num_articulations, device, articulation_type): # Reset should zero external forces and torques assert not articulation._instantaneous_wrench_composer.active assert not articulation._permanent_wrench_composer.active - assert torch.count_nonzero(articulation._instantaneous_wrench_composer.composed_force.torch) == 0 - assert torch.count_nonzero(articulation._instantaneous_wrench_composer.composed_torque.torch) == 0 - assert torch.count_nonzero(articulation._permanent_wrench_composer.composed_force.torch) == 0 - assert torch.count_nonzero(articulation._permanent_wrench_composer.composed_torque.torch) == 0 + assert torch.count_nonzero(articulation._instantaneous_wrench_composer.out_force_b.torch) == 0 + assert torch.count_nonzero(articulation._instantaneous_wrench_composer.out_torque_b.torch) == 0 + assert torch.count_nonzero(articulation._permanent_wrench_composer.out_force_b.torch) == 0 + assert torch.count_nonzero(articulation._permanent_wrench_composer.out_torque_b.torch) == 0 if num_articulations > 1: num_bodies = articulation.num_bodies @@ -1742,10 +1742,10 @@ def test_reset(sim, num_articulations, device, articulation_type): articulation.reset(env_ids=torch.tensor([0], device=device)) assert articulation._instantaneous_wrench_composer.active assert articulation._permanent_wrench_composer.active - assert torch.count_nonzero(articulation._instantaneous_wrench_composer.composed_force.torch) == num_bodies * 3 - assert torch.count_nonzero(articulation._instantaneous_wrench_composer.composed_torque.torch) == num_bodies * 3 - assert torch.count_nonzero(articulation._permanent_wrench_composer.composed_force.torch) == num_bodies * 3 - assert torch.count_nonzero(articulation._permanent_wrench_composer.composed_torque.torch) == num_bodies * 3 + assert torch.count_nonzero(articulation._instantaneous_wrench_composer.out_force_b.torch) == num_bodies * 3 + assert torch.count_nonzero(articulation._instantaneous_wrench_composer.out_torque_b.torch) == num_bodies * 3 + assert torch.count_nonzero(articulation._permanent_wrench_composer.out_force_b.torch) == num_bodies * 3 + assert torch.count_nonzero(articulation._permanent_wrench_composer.out_torque_b.torch) == num_bodies * 3 @pytest.mark.isaacsim_ci diff --git a/source/isaaclab_newton/test/assets/test_rigid_object.py b/source/isaaclab_newton/test/assets/test_rigid_object.py index 3b8e3aa9bf85..67796416dce6 100644 --- a/source/isaaclab_newton/test/assets/test_rigid_object.py +++ b/source/isaaclab_newton/test/assets/test_rigid_object.py @@ -276,8 +276,8 @@ def test_external_force_buffer(device): # check if the cube's force and torque buffers are correctly updated for i in range(cube_object.num_instances): - assert cube_object._permanent_wrench_composer.composed_force.torch[i, 0, 0].item() == force - assert cube_object._permanent_wrench_composer.composed_torque.torch[i, 0, 0].item() == force + assert cube_object._permanent_wrench_composer.out_force_b.torch[i, 0, 0].item() == force + assert cube_object._permanent_wrench_composer.out_torque_b.torch[i, 0, 0].item() == force # Check if the instantaneous wrench is correctly added to the permanent wrench cube_object.permanent_wrench_composer.add_forces_and_torques_index( @@ -565,10 +565,10 @@ def test_reset_rigid_object(num_cubes, device): # Reset should zero external forces and torques assert not cube_object._instantaneous_wrench_composer.active assert not cube_object._permanent_wrench_composer.active - assert torch.count_nonzero(cube_object._instantaneous_wrench_composer.composed_force.torch) == 0 - assert torch.count_nonzero(cube_object._instantaneous_wrench_composer.composed_torque.torch) == 0 - assert torch.count_nonzero(cube_object._permanent_wrench_composer.composed_force.torch) == 0 - assert torch.count_nonzero(cube_object._permanent_wrench_composer.composed_torque.torch) == 0 + assert torch.count_nonzero(cube_object._instantaneous_wrench_composer.out_force_b.torch) == 0 + assert torch.count_nonzero(cube_object._instantaneous_wrench_composer.out_torque_b.torch) == 0 + assert torch.count_nonzero(cube_object._permanent_wrench_composer.out_force_b.torch) == 0 + assert torch.count_nonzero(cube_object._permanent_wrench_composer.out_torque_b.torch) == 0 @pytest.mark.isaacsim_ci diff --git a/source/isaaclab_newton/test/assets/test_rigid_object_collection.py b/source/isaaclab_newton/test/assets/test_rigid_object_collection.py index 0873da8ecf22..cec62a98bcd3 100644 --- a/source/isaaclab_newton/test/assets/test_rigid_object_collection.py +++ b/source/isaaclab_newton/test/assets/test_rigid_object_collection.py @@ -241,8 +241,8 @@ def test_external_force_buffer(device): # check if the object collection's force and torque buffers are correctly updated for i in range(num_envs): - assert object_collection._permanent_wrench_composer.composed_force.torch[i, 0, 0].item() == force - assert object_collection._permanent_wrench_composer.composed_torque.torch[i, 0, 0].item() == force + assert object_collection._permanent_wrench_composer.out_force_b.torch[i, 0, 0].item() == force + assert object_collection._permanent_wrench_composer.out_torque_b.torch[i, 0, 0].item() == force object_collection.instantaneous_wrench_composer.add_forces_and_torques_index( body_ids=object_ids, @@ -502,10 +502,10 @@ def test_reset_object_collection(num_envs, num_cubes, device): # Reset should zero external forces and torques assert not object_collection._instantaneous_wrench_composer.active assert not object_collection._permanent_wrench_composer.active - assert torch.count_nonzero(object_collection._instantaneous_wrench_composer.composed_force.torch) == 0 - assert torch.count_nonzero(object_collection._instantaneous_wrench_composer.composed_torque.torch) == 0 - assert torch.count_nonzero(object_collection._permanent_wrench_composer.composed_force.torch) == 0 - assert torch.count_nonzero(object_collection._permanent_wrench_composer.composed_torque.torch) == 0 + assert torch.count_nonzero(object_collection._instantaneous_wrench_composer.out_force_b.torch) == 0 + assert torch.count_nonzero(object_collection._instantaneous_wrench_composer.out_torque_b.torch) == 0 + assert torch.count_nonzero(object_collection._permanent_wrench_composer.out_force_b.torch) == 0 + assert torch.count_nonzero(object_collection._permanent_wrench_composer.out_torque_b.torch) == 0 @pytest.mark.parametrize("num_envs", [1, 3]) diff --git a/source/isaaclab_newton/test/sensors/test_frame_transformer.py b/source/isaaclab_newton/test/sensors/test_frame_transformer.py index 513ba9dda918..236fb53f25d9 100644 --- a/source/isaaclab_newton/test/sensors/test_frame_transformer.py +++ b/source/isaaclab_newton/test/sensors/test_frame_transformer.py @@ -168,21 +168,28 @@ def test_frame_transformer_feet_wrt_base(sim): # # reset if count % 25 == 0: # reset root state - root_state = scene.articulations["robot"].data.default_root_state.torch.clone() + root_state = torch.cat( + ( + scene.articulations["robot"].data.default_root_pose.torch, + scene.articulations["robot"].data.default_root_vel.torch, + ), + dim=-1, + ).clone() root_state[:, :3] += scene.env_origins joint_pos = scene.articulations["robot"].data.default_joint_pos.torch joint_vel = scene.articulations["robot"].data.default_joint_vel.torch # -- set root state # -- robot - scene.articulations["robot"].write_root_pose_to_sim(root_state[:, :7]) - scene.articulations["robot"].write_root_velocity_to_sim(root_state[:, 7:]) - scene.articulations["robot"].write_joint_state_to_sim(joint_pos, joint_vel) + scene.articulations["robot"].write_root_pose_to_sim_index(root_pose=root_state[:, :7]) + scene.articulations["robot"].write_root_velocity_to_sim_index(root_velocity=root_state[:, 7:]) + scene.articulations["robot"].write_joint_position_to_sim_index(position=joint_pos) + scene.articulations["robot"].write_joint_velocity_to_sim_index(velocity=joint_vel) # reset buffers scene.reset() # set joint targets robot_actions = default_actions + 0.5 * torch.randn_like(default_actions) - scene.articulations["robot"].set_joint_position_target(robot_actions) + scene.articulations["robot"].set_joint_position_target_index(target=robot_actions) # write data to sim scene.write_data_to_sim() # perform step @@ -266,21 +273,28 @@ def test_frame_transformer_feet_wrt_thigh(sim): # # reset if count % 25 == 0: # reset root state - root_state = scene.articulations["robot"].data.default_root_state.torch.clone() + root_state = torch.cat( + ( + scene.articulations["robot"].data.default_root_pose.torch, + scene.articulations["robot"].data.default_root_vel.torch, + ), + dim=-1, + ).clone() root_state[:, :3] += scene.env_origins joint_pos = scene.articulations["robot"].data.default_joint_pos.torch joint_vel = scene.articulations["robot"].data.default_joint_vel.torch # -- set root state # -- robot - scene.articulations["robot"].write_root_pose_to_sim(root_state[:, :7]) - scene.articulations["robot"].write_root_velocity_to_sim(root_state[:, 7:]) - scene.articulations["robot"].write_joint_state_to_sim(joint_pos, joint_vel) + scene.articulations["robot"].write_root_pose_to_sim_index(root_pose=root_state[:, :7]) + scene.articulations["robot"].write_root_velocity_to_sim_index(root_velocity=root_state[:, 7:]) + scene.articulations["robot"].write_joint_position_to_sim_index(position=joint_pos) + scene.articulations["robot"].write_joint_velocity_to_sim_index(velocity=joint_vel) # reset buffers scene.reset() # set joint targets robot_actions = default_actions + 0.5 * torch.randn_like(default_actions) - scene.articulations["robot"].set_joint_position_target(robot_actions) + scene.articulations["robot"].set_joint_position_target_index(target=robot_actions) # write data to sim scene.write_data_to_sim() # perform step @@ -344,21 +358,28 @@ def test_frame_transformer_robot_body_to_external_cube(sim): # # reset if count % 25 == 0: # reset root state - root_state = scene.articulations["robot"].data.default_root_state.torch.clone() + root_state = torch.cat( + ( + scene.articulations["robot"].data.default_root_pose.torch, + scene.articulations["robot"].data.default_root_vel.torch, + ), + dim=-1, + ).clone() root_state[:, :3] += scene.env_origins joint_pos = scene.articulations["robot"].data.default_joint_pos.torch joint_vel = scene.articulations["robot"].data.default_joint_vel.torch # -- set root state # -- robot - scene.articulations["robot"].write_root_pose_to_sim(root_state[:, :7]) - scene.articulations["robot"].write_root_velocity_to_sim(root_state[:, 7:]) - scene.articulations["robot"].write_joint_state_to_sim(joint_pos, joint_vel) + scene.articulations["robot"].write_root_pose_to_sim_index(root_pose=root_state[:, :7]) + scene.articulations["robot"].write_root_velocity_to_sim_index(root_velocity=root_state[:, 7:]) + scene.articulations["robot"].write_joint_position_to_sim_index(position=joint_pos) + scene.articulations["robot"].write_joint_velocity_to_sim_index(velocity=joint_vel) # reset buffers scene.reset() # set joint targets robot_actions = default_actions + 0.5 * torch.randn_like(default_actions) - scene.articulations["robot"].set_joint_position_target(robot_actions) + scene.articulations["robot"].set_joint_position_target_index(target=robot_actions) # write data to sim scene.write_data_to_sim() # perform step @@ -440,12 +461,18 @@ def test_frame_transformer_offset_frames(sim): # # reset if count % 25 == 0: # reset root state - root_state = scene["cube"].data.default_root_state.torch.clone() + root_state = torch.cat( + ( + scene["cube"].data.default_root_pose.torch, + scene["cube"].data.default_root_vel.torch, + ), + dim=-1, + ).clone() root_state[:, :3] += scene.env_origins # -- set root state # -- cube - scene["cube"].write_root_pose_to_sim(root_state[:, :7]) - scene["cube"].write_root_velocity_to_sim(root_state[:, 7:]) + scene["cube"].write_root_pose_to_sim_index(root_pose=root_state[:, :7]) + scene["cube"].write_root_velocity_to_sim_index(root_velocity=root_state[:, 7:]) # reset buffers scene.reset() @@ -532,21 +559,28 @@ def test_frame_transformer_all_bodies(sim): # # reset if count % 25 == 0: # reset root state - root_state = scene.articulations["robot"].data.default_root_state.torch.clone() + root_state = torch.cat( + ( + scene.articulations["robot"].data.default_root_pose.torch, + scene.articulations["robot"].data.default_root_vel.torch, + ), + dim=-1, + ).clone() root_state[:, :3] += scene.env_origins joint_pos = scene.articulations["robot"].data.default_joint_pos.torch joint_vel = scene.articulations["robot"].data.default_joint_vel.torch # -- set root state # -- robot - scene.articulations["robot"].write_root_pose_to_sim(root_state[:, :7]) - scene.articulations["robot"].write_root_velocity_to_sim(root_state[:, 7:]) - scene.articulations["robot"].write_joint_state_to_sim(joint_pos, joint_vel) + scene.articulations["robot"].write_root_pose_to_sim_index(root_pose=root_state[:, :7]) + scene.articulations["robot"].write_root_velocity_to_sim_index(root_velocity=root_state[:, 7:]) + scene.articulations["robot"].write_joint_position_to_sim_index(position=joint_pos) + scene.articulations["robot"].write_joint_velocity_to_sim_index(velocity=joint_vel) # reset buffers scene.reset() # set joint targets robot_actions = default_actions + 0.5 * torch.randn_like(default_actions) - scene.articulations["robot"].set_joint_position_target(robot_actions) + scene.articulations["robot"].set_joint_position_target_index(target=robot_actions) # write data to sim scene.write_data_to_sim() # perform step @@ -727,22 +761,38 @@ class MultiRobotSceneCfg(InteractiveSceneCfg): # Reset periodically if count % 10 == 0: # Reset robot - root_state = scene.articulations["robot"].data.default_root_state.torch.clone() + root_state = torch.cat( + ( + scene.articulations["robot"].data.default_root_pose.torch, + scene.articulations["robot"].data.default_root_vel.torch, + ), + dim=-1, + ).clone() root_state[:, :3] += scene.env_origins - scene.articulations["robot"].write_root_pose_to_sim(root_state[:, :7]) - scene.articulations["robot"].write_root_velocity_to_sim(root_state[:, 7:]) - scene.articulations["robot"].write_joint_state_to_sim( - scene.articulations["robot"].data.default_joint_pos.torch, - scene.articulations["robot"].data.default_joint_vel.torch, + scene.articulations["robot"].write_root_pose_to_sim_index(root_pose=root_state[:, :7]) + scene.articulations["robot"].write_root_velocity_to_sim_index(root_velocity=root_state[:, 7:]) + scene.articulations["robot"].write_joint_position_to_sim_index( + position=scene.articulations["robot"].data.default_joint_pos.torch + ) + scene.articulations["robot"].write_joint_velocity_to_sim_index( + velocity=scene.articulations["robot"].data.default_joint_vel.torch ) # Reset robot_1 - root_state_1 = scene.articulations["robot_1"].data.default_root_state.torch.clone() + root_state_1 = torch.cat( + ( + scene.articulations["robot_1"].data.default_root_pose.torch, + scene.articulations["robot_1"].data.default_root_vel.torch, + ), + dim=-1, + ).clone() root_state_1[:, :3] += scene.env_origins - scene.articulations["robot_1"].write_root_pose_to_sim(root_state_1[:, :7]) - scene.articulations["robot_1"].write_root_velocity_to_sim(root_state_1[:, 7:]) - scene.articulations["robot_1"].write_joint_state_to_sim( - scene.articulations["robot_1"].data.default_joint_pos.torch, - scene.articulations["robot_1"].data.default_joint_vel.torch, + scene.articulations["robot_1"].write_root_pose_to_sim_index(root_pose=root_state_1[:, :7]) + scene.articulations["robot_1"].write_root_velocity_to_sim_index(root_velocity=root_state_1[:, 7:]) + scene.articulations["robot_1"].write_joint_position_to_sim_index( + position=scene.articulations["robot_1"].data.default_joint_pos.torch + ) + scene.articulations["robot_1"].write_joint_velocity_to_sim_index( + velocity=scene.articulations["robot_1"].data.default_joint_vel.torch ) scene.reset() diff --git a/source/isaaclab_physx/changelog.d/antoiner-backend-deprecation-warning-cleanup.rst b/source/isaaclab_physx/changelog.d/antoiner-backend-deprecation-warning-cleanup.rst new file mode 100644 index 000000000000..bdec42289b0d --- /dev/null +++ b/source/isaaclab_physx/changelog.d/antoiner-backend-deprecation-warning-cleanup.rst @@ -0,0 +1,5 @@ +Fixed +^^^^^ + +* Fixed PhysX backend tests to use current contact sensor and asset API names, + removing deprecation warnings from scoped test runs. diff --git a/source/isaaclab_physx/test/assets/test_articulation.py b/source/isaaclab_physx/test/assets/test_articulation.py index 508a10f27c27..bd015562c4df 100644 --- a/source/isaaclab_physx/test/assets/test_articulation.py +++ b/source/isaaclab_physx/test/assets/test_articulation.py @@ -844,8 +844,8 @@ def test_external_force_buffer(sim, num_articulations, device): # check if the articulation's force and torque buffers are correctly updated for i in range(num_articulations): - assert articulation.permanent_wrench_composer.composed_force.torch[i, 0, 0].item() == force - assert articulation.permanent_wrench_composer.composed_torque.torch[i, 0, 0].item() == force + assert articulation.permanent_wrench_composer.out_force_b.torch[i, 0, 0].item() == force + assert articulation.permanent_wrench_composer.out_torque_b.torch[i, 0, 0].item() == force # Check if the instantaneous wrench is correctly added to the permanent wrench articulation.instantaneous_wrench_composer.add_forces_and_torques_index( @@ -1559,10 +1559,10 @@ def test_reset(sim, num_articulations, device): # Reset should zero external forces and torques assert not articulation._instantaneous_wrench_composer.active assert not articulation._permanent_wrench_composer.active - assert torch.count_nonzero(articulation._instantaneous_wrench_composer.composed_force.torch) == 0 - assert torch.count_nonzero(articulation._instantaneous_wrench_composer.composed_torque.torch) == 0 - assert torch.count_nonzero(articulation._permanent_wrench_composer.composed_force.torch) == 0 - assert torch.count_nonzero(articulation._permanent_wrench_composer.composed_torque.torch) == 0 + assert torch.count_nonzero(articulation._instantaneous_wrench_composer.out_force_b.torch) == 0 + assert torch.count_nonzero(articulation._instantaneous_wrench_composer.out_torque_b.torch) == 0 + assert torch.count_nonzero(articulation._permanent_wrench_composer.out_force_b.torch) == 0 + assert torch.count_nonzero(articulation._permanent_wrench_composer.out_torque_b.torch) == 0 if num_articulations > 1: num_bodies = articulation.num_bodies @@ -1577,10 +1577,10 @@ def test_reset(sim, num_articulations, device): articulation.reset(env_ids=torch.tensor([0], device=device)) assert articulation._instantaneous_wrench_composer.active assert articulation._permanent_wrench_composer.active - assert torch.count_nonzero(articulation._instantaneous_wrench_composer.composed_force.torch) == num_bodies * 3 - assert torch.count_nonzero(articulation._instantaneous_wrench_composer.composed_torque.torch) == num_bodies * 3 - assert torch.count_nonzero(articulation._permanent_wrench_composer.composed_force.torch) == num_bodies * 3 - assert torch.count_nonzero(articulation._permanent_wrench_composer.composed_torque.torch) == num_bodies * 3 + assert torch.count_nonzero(articulation._instantaneous_wrench_composer.out_force_b.torch) == num_bodies * 3 + assert torch.count_nonzero(articulation._instantaneous_wrench_composer.out_torque_b.torch) == num_bodies * 3 + assert torch.count_nonzero(articulation._permanent_wrench_composer.out_force_b.torch) == num_bodies * 3 + assert torch.count_nonzero(articulation._permanent_wrench_composer.out_torque_b.torch) == num_bodies * 3 @pytest.mark.parametrize("num_articulations", [1, 2]) diff --git a/source/isaaclab_physx/test/assets/test_rigid_object.py b/source/isaaclab_physx/test/assets/test_rigid_object.py index 6a2211787e19..b7f422c4f2f0 100644 --- a/source/isaaclab_physx/test/assets/test_rigid_object.py +++ b/source/isaaclab_physx/test/assets/test_rigid_object.py @@ -253,8 +253,8 @@ def test_external_force_buffer(device): # check if the cube's force and torque buffers are correctly updated for i in range(cube_object.num_instances): - assert cube_object._permanent_wrench_composer.composed_force.torch[i, 0, 0].item() == force - assert cube_object._permanent_wrench_composer.composed_torque.torch[i, 0, 0].item() == force + assert cube_object._permanent_wrench_composer.out_force_b.torch[i, 0, 0].item() == force + assert cube_object._permanent_wrench_composer.out_torque_b.torch[i, 0, 0].item() == force # Check if the instantaneous wrench is correctly added to the permanent wrench cube_object.permanent_wrench_composer.add_forces_and_torques_index( @@ -426,13 +426,13 @@ def test_external_force_on_single_body_at_position(num_cubes, device): is_global=is_global, ) torch.testing.assert_close( - cube_object._permanent_wrench_composer.composed_force.torch[:, 0, :], + cube_object._permanent_wrench_composer.out_force_b.torch[:, 0, :], desired_force[:, 0, :], rtol=1e-6, atol=1e-7, ) torch.testing.assert_close( - cube_object._permanent_wrench_composer.composed_torque.torch[:, 0, :], + cube_object._permanent_wrench_composer.out_torque_b.torch[:, 0, :], desired_torque[:, 0, :], rtol=1e-6, atol=1e-7, @@ -557,10 +557,10 @@ def test_reset_rigid_object(num_cubes, device): # Reset should zero external forces and torques assert not cube_object._instantaneous_wrench_composer.active assert not cube_object._permanent_wrench_composer.active - assert torch.count_nonzero(cube_object._instantaneous_wrench_composer.composed_force.torch) == 0 - assert torch.count_nonzero(cube_object._instantaneous_wrench_composer.composed_torque.torch) == 0 - assert torch.count_nonzero(cube_object._permanent_wrench_composer.composed_force.torch) == 0 - assert torch.count_nonzero(cube_object._permanent_wrench_composer.composed_torque.torch) == 0 + assert torch.count_nonzero(cube_object._instantaneous_wrench_composer.out_force_b.torch) == 0 + assert torch.count_nonzero(cube_object._instantaneous_wrench_composer.out_torque_b.torch) == 0 + assert torch.count_nonzero(cube_object._permanent_wrench_composer.out_force_b.torch) == 0 + assert torch.count_nonzero(cube_object._permanent_wrench_composer.out_torque_b.torch) == 0 @pytest.mark.parametrize("num_cubes", [1, 2]) diff --git a/source/isaaclab_physx/test/assets/test_rigid_object_collection.py b/source/isaaclab_physx/test/assets/test_rigid_object_collection.py index 8401cc395a0c..f42f6dfcb085 100644 --- a/source/isaaclab_physx/test/assets/test_rigid_object_collection.py +++ b/source/isaaclab_physx/test/assets/test_rigid_object_collection.py @@ -259,8 +259,8 @@ def test_external_force_buffer(sim, device): # check if the object collection's force and torque buffers are correctly updated for i in range(num_envs): - assert object_collection._permanent_wrench_composer.composed_force.torch[i, 0, 0].item() == force - assert object_collection._permanent_wrench_composer.composed_torque.torch[i, 0, 0].item() == force + assert object_collection._permanent_wrench_composer.out_force_b.torch[i, 0, 0].item() == force + assert object_collection._permanent_wrench_composer.out_torque_b.torch[i, 0, 0].item() == force object_collection.instantaneous_wrench_composer.add_forces_and_torques_index( body_ids=object_ids, @@ -681,10 +681,10 @@ def test_reset_object_collection(sim, num_envs, num_cubes, device): # Reset should zero external forces and torques assert not object_collection._instantaneous_wrench_composer.active assert not object_collection._permanent_wrench_composer.active - assert torch.count_nonzero(object_collection._instantaneous_wrench_composer.composed_force.torch) == 0 - assert torch.count_nonzero(object_collection._instantaneous_wrench_composer.composed_torque.torch) == 0 - assert torch.count_nonzero(object_collection._permanent_wrench_composer.composed_force.torch) == 0 - assert torch.count_nonzero(object_collection._permanent_wrench_composer.composed_torque.torch) == 0 + assert torch.count_nonzero(object_collection._instantaneous_wrench_composer.out_force_b.torch) == 0 + assert torch.count_nonzero(object_collection._instantaneous_wrench_composer.out_torque_b.torch) == 0 + assert torch.count_nonzero(object_collection._permanent_wrench_composer.out_force_b.torch) == 0 + assert torch.count_nonzero(object_collection._permanent_wrench_composer.out_torque_b.torch) == 0 @pytest.mark.parametrize("num_envs", [1, 3]) diff --git a/source/isaaclab_physx/test/sensors/test_contact_sensor.py b/source/isaaclab_physx/test/sensors/test_contact_sensor.py index 00772e6cb0d3..685d9204b3ef 100644 --- a/source/isaaclab_physx/test/sensors/test_contact_sensor.py +++ b/source/isaaclab_physx/test/sensors/test_contact_sensor.py @@ -480,7 +480,7 @@ def test_friction_reporting(setup_simulation, grav_dir): sim.reset() scene["contact_sensor"].reset() - scene["shape"].write_root_pose_to_sim( + scene["shape"].write_root_pose_to_sim_index( root_pose=torch.tensor([0, 0.0, CUBE_CFG.spawn.size[2] / 2.0, 1, 0, 0, 0], device=device).unsqueeze(0) ) @@ -703,7 +703,7 @@ def _test_sensor_contact( duration = durations[idx] while current_test_time < duration: # set object states to contact the ground plane - shape.write_root_pose_to_sim(root_pose=torch.tensor(test_pose, device=shape.device).unsqueeze(0)) + shape.write_root_pose_to_sim_index(root_pose=torch.tensor(test_pose, device=shape.device).unsqueeze(0)) # perform simulation step _perform_sim_step(sim, scene, sim_dt) # increment contact time @@ -735,7 +735,7 @@ def _test_sensor_contact( _test_friction_forces(shape, sensor, mode) # switch the contact mode for 1 dt step before the next contact test begins. - shape.write_root_pose_to_sim(root_pose=torch.tensor(reset_pose, device=shape.device).unsqueeze(0)) + shape.write_root_pose_to_sim_index(root_pose=torch.tensor(reset_pose, device=shape.device).unsqueeze(0)) # perform simulation step _perform_sim_step(sim, scene, sim_dt) # set the last air time to 2 sim_dt steps, because last_air_time and last_contact_time @@ -750,9 +750,9 @@ def _test_friction_forces(shape: RigidObject, sensor: ContactSensor, mode: Conta return # check shape of the friction_forces_w tensor (wp.to_torch expands vec3f -> float32 trailing dim) - num_bodies = sensor.num_bodies + num_sensors = sensor.num_sensors friction_torch = sensor._data.friction_forces_w.torch - assert friction_torch.shape == (sensor.num_instances // num_bodies, num_bodies, 1, 3) + assert friction_torch.shape == (sensor.num_instances // num_sensors, num_sensors, 1, 3) # compare friction forces if mode == ContactTestMode.IN_CONTACT: assert torch.any(torch.abs(friction_torch) > 1e-5).item() @@ -762,14 +762,14 @@ def _test_friction_forces(shape: RigidObject, sensor: ContactSensor, mode: Conta friction_forces_t = wp.to_torch(friction_forces) buffer_count_t = wp.to_torch(buffer_count).to(torch.int32) buffer_start_t = wp.to_torch(buffer_start_indices).to(torch.int32) - for i in range(sensor.num_instances * num_bodies): + for i in range(sensor.num_instances * num_sensors): for j in range(sensor.contact_view.filter_count): start_index_ij = buffer_start_t[i, j] count_ij = buffer_count_t[i, j] force = torch.sum(friction_forces_t[start_index_ij : (start_index_ij + count_ij), :], dim=0) - env_idx = i // num_bodies - body_idx = i % num_bodies - assert torch.allclose(force, friction_torch[env_idx, body_idx, j, :], atol=1e-5) + env_idx = i // num_sensors + sensor_idx = i % num_sensors + assert torch.allclose(force, friction_torch[env_idx, sensor_idx, j, :], atol=1e-5) elif mode == ContactTestMode.NON_CONTACT: assert torch.all(friction_torch == 0.0).item() @@ -788,9 +788,9 @@ def _test_contact_position(shape: RigidObject, sensor: ContactSensor, mode: Cont return # check shape of the contact_pos_w tensor (wp.to_torch expands vec3f -> float32 trailing dim) - num_bodies = sensor.num_bodies + num_sensors = sensor.num_sensors contact_pos_torch = sensor._data.contact_pos_w.torch - assert contact_pos_torch.shape == (sensor.num_instances // num_bodies, num_bodies, 1, 3) + assert contact_pos_torch.shape == (sensor.num_instances // num_sensors, num_sensors, 1, 3) # check contact positions if mode == ContactTestMode.IN_CONTACT: pos_w_torch = sensor._data.pos_w.torch diff --git a/source/isaaclab_physx/test/sensors/test_frame_transformer.py b/source/isaaclab_physx/test/sensors/test_frame_transformer.py index 631e9ba118dd..28559f9b6da5 100644 --- a/source/isaaclab_physx/test/sensors/test_frame_transformer.py +++ b/source/isaaclab_physx/test/sensors/test_frame_transformer.py @@ -153,21 +153,28 @@ def test_frame_transformer_feet_wrt_base(sim): # # reset if count % 25 == 0: # reset root state - root_state = scene.articulations["robot"].data.default_root_state.torch.clone() + root_state = torch.cat( + ( + scene.articulations["robot"].data.default_root_pose.torch, + scene.articulations["robot"].data.default_root_vel.torch, + ), + dim=-1, + ).clone() root_state[:, :3] += scene.env_origins joint_pos = scene.articulations["robot"].data.default_joint_pos.torch joint_vel = scene.articulations["robot"].data.default_joint_vel.torch # -- set root state # -- robot - scene.articulations["robot"].write_root_pose_to_sim(root_state[:, :7]) - scene.articulations["robot"].write_root_velocity_to_sim(root_state[:, 7:]) - scene.articulations["robot"].write_joint_state_to_sim(joint_pos, joint_vel) + scene.articulations["robot"].write_root_pose_to_sim_index(root_pose=root_state[:, :7]) + scene.articulations["robot"].write_root_velocity_to_sim_index(root_velocity=root_state[:, 7:]) + scene.articulations["robot"].write_joint_position_to_sim_index(position=joint_pos) + scene.articulations["robot"].write_joint_velocity_to_sim_index(velocity=joint_vel) # reset buffers scene.reset() # set joint targets robot_actions = default_actions + 0.5 * torch.randn_like(default_actions) - scene.articulations["robot"].set_joint_position_target(robot_actions) + scene.articulations["robot"].set_joint_position_target_index(target=robot_actions) # write data to sim scene.write_data_to_sim() # perform step @@ -251,21 +258,28 @@ def test_frame_transformer_feet_wrt_thigh(sim): # # reset if count % 25 == 0: # reset root state - root_state = scene.articulations["robot"].data.default_root_state.torch.clone() + root_state = torch.cat( + ( + scene.articulations["robot"].data.default_root_pose.torch, + scene.articulations["robot"].data.default_root_vel.torch, + ), + dim=-1, + ).clone() root_state[:, :3] += scene.env_origins joint_pos = scene.articulations["robot"].data.default_joint_pos.torch joint_vel = scene.articulations["robot"].data.default_joint_vel.torch # -- set root state # -- robot - scene.articulations["robot"].write_root_pose_to_sim(root_state[:, :7]) - scene.articulations["robot"].write_root_velocity_to_sim(root_state[:, 7:]) - scene.articulations["robot"].write_joint_state_to_sim(joint_pos, joint_vel) + scene.articulations["robot"].write_root_pose_to_sim_index(root_pose=root_state[:, :7]) + scene.articulations["robot"].write_root_velocity_to_sim_index(root_velocity=root_state[:, 7:]) + scene.articulations["robot"].write_joint_position_to_sim_index(position=joint_pos) + scene.articulations["robot"].write_joint_velocity_to_sim_index(velocity=joint_vel) # reset buffers scene.reset() # set joint targets robot_actions = default_actions + 0.5 * torch.randn_like(default_actions) - scene.articulations["robot"].set_joint_position_target(robot_actions) + scene.articulations["robot"].set_joint_position_target_index(target=robot_actions) # write data to sim scene.write_data_to_sim() # perform step @@ -329,21 +343,28 @@ def test_frame_transformer_robot_body_to_external_cube(sim): # # reset if count % 25 == 0: # reset root state - root_state = scene.articulations["robot"].data.default_root_state.torch.clone() + root_state = torch.cat( + ( + scene.articulations["robot"].data.default_root_pose.torch, + scene.articulations["robot"].data.default_root_vel.torch, + ), + dim=-1, + ).clone() root_state[:, :3] += scene.env_origins joint_pos = scene.articulations["robot"].data.default_joint_pos.torch joint_vel = scene.articulations["robot"].data.default_joint_vel.torch # -- set root state # -- robot - scene.articulations["robot"].write_root_pose_to_sim(root_state[:, :7]) - scene.articulations["robot"].write_root_velocity_to_sim(root_state[:, 7:]) - scene.articulations["robot"].write_joint_state_to_sim(joint_pos, joint_vel) + scene.articulations["robot"].write_root_pose_to_sim_index(root_pose=root_state[:, :7]) + scene.articulations["robot"].write_root_velocity_to_sim_index(root_velocity=root_state[:, 7:]) + scene.articulations["robot"].write_joint_position_to_sim_index(position=joint_pos) + scene.articulations["robot"].write_joint_velocity_to_sim_index(velocity=joint_vel) # reset buffers scene.reset() # set joint targets robot_actions = default_actions + 0.5 * torch.randn_like(default_actions) - scene.articulations["robot"].set_joint_position_target(robot_actions) + scene.articulations["robot"].set_joint_position_target_index(target=robot_actions) # write data to sim scene.write_data_to_sim() # perform step @@ -425,12 +446,18 @@ def test_frame_transformer_offset_frames(sim): # # reset if count % 25 == 0: # reset root state - root_state = scene["cube"].data.default_root_state.torch.clone() + root_state = torch.cat( + ( + scene["cube"].data.default_root_pose.torch, + scene["cube"].data.default_root_vel.torch, + ), + dim=-1, + ).clone() root_state[:, :3] += scene.env_origins # -- set root state # -- cube - scene["cube"].write_root_pose_to_sim(root_state[:, :7]) - scene["cube"].write_root_velocity_to_sim(root_state[:, 7:]) + scene["cube"].write_root_pose_to_sim_index(root_pose=root_state[:, :7]) + scene["cube"].write_root_velocity_to_sim_index(root_velocity=root_state[:, 7:]) # reset buffers scene.reset() @@ -513,21 +540,28 @@ def test_frame_transformer_all_bodies(sim): # # reset if count % 25 == 0: # reset root state - root_state = scene.articulations["robot"].data.default_root_state.torch.clone() + root_state = torch.cat( + ( + scene.articulations["robot"].data.default_root_pose.torch, + scene.articulations["robot"].data.default_root_vel.torch, + ), + dim=-1, + ).clone() root_state[:, :3] += scene.env_origins joint_pos = scene.articulations["robot"].data.default_joint_pos.torch joint_vel = scene.articulations["robot"].data.default_joint_vel.torch # -- set root state # -- robot - scene.articulations["robot"].write_root_pose_to_sim(root_state[:, :7]) - scene.articulations["robot"].write_root_velocity_to_sim(root_state[:, 7:]) - scene.articulations["robot"].write_joint_state_to_sim(joint_pos, joint_vel) + scene.articulations["robot"].write_root_pose_to_sim_index(root_pose=root_state[:, :7]) + scene.articulations["robot"].write_root_velocity_to_sim_index(root_velocity=root_state[:, 7:]) + scene.articulations["robot"].write_joint_position_to_sim_index(position=joint_pos) + scene.articulations["robot"].write_joint_velocity_to_sim_index(velocity=joint_vel) # reset buffers scene.reset() # set joint targets robot_actions = default_actions + 0.5 * torch.randn_like(default_actions) - scene.articulations["robot"].set_joint_position_target(robot_actions) + scene.articulations["robot"].set_joint_position_target_index(target=robot_actions) # write data to sim scene.write_data_to_sim() # perform step @@ -708,22 +742,38 @@ class MultiRobotSceneCfg(InteractiveSceneCfg): # Reset periodically if count % 10 == 0: # Reset robot - root_state = scene.articulations["robot"].data.default_root_state.torch.clone() + root_state = torch.cat( + ( + scene.articulations["robot"].data.default_root_pose.torch, + scene.articulations["robot"].data.default_root_vel.torch, + ), + dim=-1, + ).clone() root_state[:, :3] += scene.env_origins - scene.articulations["robot"].write_root_pose_to_sim(root_state[:, :7]) - scene.articulations["robot"].write_root_velocity_to_sim(root_state[:, 7:]) - scene.articulations["robot"].write_joint_state_to_sim( - scene.articulations["robot"].data.default_joint_pos.torch, - scene.articulations["robot"].data.default_joint_vel.torch, + scene.articulations["robot"].write_root_pose_to_sim_index(root_pose=root_state[:, :7]) + scene.articulations["robot"].write_root_velocity_to_sim_index(root_velocity=root_state[:, 7:]) + scene.articulations["robot"].write_joint_position_to_sim_index( + position=scene.articulations["robot"].data.default_joint_pos.torch + ) + scene.articulations["robot"].write_joint_velocity_to_sim_index( + velocity=scene.articulations["robot"].data.default_joint_vel.torch ) # Reset robot_1 - root_state_1 = scene.articulations["robot_1"].data.default_root_state.torch.clone() + root_state_1 = torch.cat( + ( + scene.articulations["robot_1"].data.default_root_pose.torch, + scene.articulations["robot_1"].data.default_root_vel.torch, + ), + dim=-1, + ).clone() root_state_1[:, :3] += scene.env_origins - scene.articulations["robot_1"].write_root_pose_to_sim(root_state_1[:, :7]) - scene.articulations["robot_1"].write_root_velocity_to_sim(root_state_1[:, 7:]) - scene.articulations["robot_1"].write_joint_state_to_sim( - scene.articulations["robot_1"].data.default_joint_pos.torch, - scene.articulations["robot_1"].data.default_joint_vel.torch, + scene.articulations["robot_1"].write_root_pose_to_sim_index(root_pose=root_state_1[:, :7]) + scene.articulations["robot_1"].write_root_velocity_to_sim_index(root_velocity=root_state_1[:, 7:]) + scene.articulations["robot_1"].write_joint_position_to_sim_index( + position=scene.articulations["robot_1"].data.default_joint_pos.torch + ) + scene.articulations["robot_1"].write_joint_velocity_to_sim_index( + velocity=scene.articulations["robot_1"].data.default_joint_vel.torch ) scene.reset() From 3d93e84d7d00c616c14da893644dd135958f95a9 Mon Sep 17 00:00:00 2001 From: Antoine RICHARD Date: Fri, 8 May 2026 09:41:36 +0200 Subject: [PATCH 16/51] Updates core deprecation call sites (#5409) ## Summary - Migrates core test and MDP callers off deprecated state/read/write helper APIs. - Updates the test_pose_inv tensor-to-NumPy conversion for NumPy 2.0. - Bumps the isaaclab changelog/version because core MDP source changed. ## Verification - ./isaaclab.sh -f - Scoped deprecated-call-site search: assigned core matches removed. Rebased onto develop after PR #5304 merged. --- ...oiner-core-deprecation-warning-cleanup.rst | 5 + .../controllers/test_operational_space.py | 7 +- .../test/envs/test_scale_randomization.py | 2 +- .../test/scene/test_interactive_scene.py | 32 +-- .../utils/test_wrench_composer_integration.py | 206 ++++++++++-------- .../utils/test_wrench_composer_vs_physx.py | 34 ++- 6 files changed, 164 insertions(+), 122 deletions(-) create mode 100644 source/isaaclab/changelog.d/antoiner-core-deprecation-warning-cleanup.rst diff --git a/source/isaaclab/changelog.d/antoiner-core-deprecation-warning-cleanup.rst b/source/isaaclab/changelog.d/antoiner-core-deprecation-warning-cleanup.rst new file mode 100644 index 000000000000..a3a3e51f8b3a --- /dev/null +++ b/source/isaaclab/changelog.d/antoiner-core-deprecation-warning-cleanup.rst @@ -0,0 +1,5 @@ +Fixed +^^^^^ + +* Fixed :class:`~isaaclab.envs.mdp.actions.PinkInverseKinematicsAction` + base link pose reads to avoid deprecated body link state access. diff --git a/source/isaaclab/test/controllers/test_operational_space.py b/source/isaaclab/test/controllers/test_operational_space.py index 63c1633c5f7c..badf51543e17 100644 --- a/source/isaaclab/test/controllers/test_operational_space.py +++ b/source/isaaclab/test/controllers/test_operational_space.py @@ -1498,8 +1498,9 @@ def _run_op_space_controller( # reset joint state to default default_joint_pos = robot.data.default_joint_pos.torch.clone() default_joint_vel = robot.data.default_joint_vel.torch.clone() - robot.write_joint_state_to_sim(default_joint_pos, default_joint_vel) - robot.set_joint_effort_target(zero_joint_efforts) # Set zero torques in the initial step + robot.write_joint_position_to_sim_index(position=default_joint_pos) + robot.write_joint_velocity_to_sim_index(velocity=default_joint_vel) + robot.set_joint_effort_target_index(target=zero_joint_efforts) # Set zero torques in the initial step robot.write_data_to_sim() robot.reset() # reset contact sensor @@ -1545,7 +1546,7 @@ def _run_op_space_controller( current_joint_vel=joint_vel, nullspace_joint_pos_target=joint_centers, ) - robot.set_joint_effort_target(joint_efforts, joint_ids=arm_joint_ids) + robot.set_joint_effort_target_index(target=joint_efforts, joint_ids=arm_joint_ids) robot.write_data_to_sim() # update marker positions diff --git a/source/isaaclab/test/envs/test_scale_randomization.py b/source/isaaclab/test/envs/test_scale_randomization.py index af5dc220e63f..ec4c6cd42a96 100644 --- a/source/isaaclab/test/envs/test_scale_randomization.py +++ b/source/isaaclab/test/envs/test_scale_randomization.py @@ -105,7 +105,7 @@ def apply_actions(self): vel_error = -self._asset.data.root_lin_vel_w.torch # set velocity targets self._vel_command[:, :3] = self.p_gain * pos_error + self.d_gain * vel_error - self._asset.write_root_velocity_to_sim(self._vel_command) + self._asset.write_root_velocity_to_sim_index(root_velocity=self._vel_command) @configclass diff --git a/source/isaaclab/test/scene/test_interactive_scene.py b/source/isaaclab/test/scene/test_interactive_scene.py index 31b577db634f..390129b9e4f2 100644 --- a/source/isaaclab/test/scene/test_interactive_scene.py +++ b/source/isaaclab/test/scene/test_interactive_scene.py @@ -84,10 +84,10 @@ def test_relative_flag(device, setup_scene): # test is relative == False prev_state = scene.get_state(is_relative=False) - scene["robot"].write_joint_state_to_sim( - position=torch.rand_like(scene["robot"].data.joint_pos.torch), - velocity=torch.rand_like(scene["robot"].data.joint_pos.torch), - ) + joint_pos = torch.rand_like(scene["robot"].data.joint_pos.torch) + joint_vel = torch.rand_like(scene["robot"].data.joint_pos.torch) + scene["robot"].write_joint_position_to_sim_index(position=joint_pos) + scene["robot"].write_joint_velocity_to_sim_index(velocity=joint_vel) next_state = scene.get_state(is_relative=False) assert_state_different(prev_state, next_state) scene.reset_to(prev_state, is_relative=False) @@ -95,10 +95,10 @@ def test_relative_flag(device, setup_scene): # test is relative == True prev_state = scene.get_state(is_relative=True) - scene["robot"].write_joint_state_to_sim( - position=torch.rand_like(scene["robot"].data.joint_pos.torch), - velocity=torch.rand_like(scene["robot"].data.joint_pos.torch), - ) + joint_pos = torch.rand_like(scene["robot"].data.joint_pos.torch) + joint_vel = torch.rand_like(scene["robot"].data.joint_pos.torch) + scene["robot"].write_joint_position_to_sim_index(position=joint_pos) + scene["robot"].write_joint_velocity_to_sim_index(velocity=joint_vel) next_state = scene.get_state(is_relative=True) assert_state_different(prev_state, next_state) scene.reset_to(prev_state, is_relative=True) @@ -114,18 +114,18 @@ def test_reset_to_env_ids_input_types(device, setup_scene): # test env_ids = None prev_state = scene.get_state() - scene["robot"].write_joint_state_to_sim( - position=torch.rand_like(scene["robot"].data.joint_pos.torch), - velocity=torch.rand_like(scene["robot"].data.joint_pos.torch), - ) + joint_pos = torch.rand_like(scene["robot"].data.joint_pos.torch) + joint_vel = torch.rand_like(scene["robot"].data.joint_pos.torch) + scene["robot"].write_joint_position_to_sim_index(position=joint_pos) + scene["robot"].write_joint_velocity_to_sim_index(velocity=joint_vel) scene.reset_to(prev_state, env_ids=None) assert_state_equal(prev_state, scene.get_state()) # test env_ids = torch tensor - scene["robot"].write_joint_state_to_sim( - position=torch.rand_like(scene["robot"].data.joint_pos.torch), - velocity=torch.rand_like(scene["robot"].data.joint_pos.torch), - ) + joint_pos = torch.rand_like(scene["robot"].data.joint_pos.torch) + joint_vel = torch.rand_like(scene["robot"].data.joint_pos.torch) + scene["robot"].write_joint_position_to_sim_index(position=joint_pos) + scene["robot"].write_joint_velocity_to_sim_index(velocity=joint_vel) scene.reset_to(prev_state, env_ids=torch.arange(scene.num_envs, device=scene.device, dtype=torch.int32)) assert_state_equal(prev_state, scene.get_state()) diff --git a/source/isaaclab/test/utils/test_wrench_composer_integration.py b/source/isaaclab/test/utils/test_wrench_composer_integration.py index bb195e856030..acb1682bde02 100644 --- a/source/isaaclab/test/utils/test_wrench_composer_integration.py +++ b/source/isaaclab/test/utils/test_wrench_composer_integration.py @@ -79,7 +79,7 @@ def test_global_force_invariant_under_rotation(device): forces[..., 0] = FORCE_MAGNITUDE torques = torch.zeros(1, len(body_ids), 3, device=device) - cube_object.permanent_wrench_composer.set_forces_and_torques( + cube_object.permanent_wrench_composer.set_forces_and_torques_index( forces=forces, torques=torques, positions=com, @@ -96,9 +96,9 @@ def test_global_force_invariant_under_rotation(device): vel_after_phase1 = cube_object.data.root_lin_vel_w.torch[0].clone() # Rotate body 180deg about Z (quat wxyz = [0, 0, 0, 1]) while keeping velocity - root_pose = cube_object.data.root_state_w.torch[0, :7].clone().unsqueeze(0) + root_pose = cube_object.data.root_pose_w.torch[0].clone().unsqueeze(0) root_pose[0, 3:7] = torch.tensor([0.0, 0.0, 1.0, 0.0], device=device) # 180deg about Z (xyzw) - cube_object.write_root_pose_to_sim(root_pose) + cube_object.write_root_pose_to_sim_index(root_pose=root_pose) # Phase 2: run N_STEPS more for _ in range(N_STEPS): @@ -152,7 +152,7 @@ def test_local_force_follows_rotation(device): forces[..., 0] = FORCE_MAGNITUDE torques = torch.zeros(1, len(body_ids), 3, device=device) - cube_object.permanent_wrench_composer.set_forces_and_torques( + cube_object.permanent_wrench_composer.set_forces_and_torques_index( forces=forces, torques=torques, body_ids=body_ids, @@ -169,9 +169,9 @@ def test_local_force_follows_rotation(device): assert vel_after_phase1[0].item() > 1.0, "Object should be moving in +X" # Rotate body 180deg about Z while keeping velocity - root_pose = cube_object.data.root_state_w.torch[0, :7].clone().unsqueeze(0) + root_pose = cube_object.data.root_pose_w.torch[0].clone().unsqueeze(0) root_pose[0, 3:7] = torch.tensor([0.0, 0.0, 1.0, 0.0], device=device) # 180deg about Z (xyzw) - cube_object.write_root_pose_to_sim(root_pose) + cube_object.write_root_pose_to_sim_index(root_pose=root_pose) # Phase 2: run N_STEPS — local +X is now world -X, so force decelerates for _ in range(N_STEPS): @@ -217,7 +217,7 @@ def test_global_force_at_offset_generates_torque(device): positions = com_pos.clone() positions[..., 1] += 1.0 # +1m Y offset - cube_object.permanent_wrench_composer.set_forces_and_torques( + cube_object.permanent_wrench_composer.set_forces_and_torques_index( forces=forces, torques=torques, positions=positions, @@ -262,7 +262,7 @@ def test_global_torque_invariant_under_rotation(device): torques = torch.zeros(1, len(body_ids), 3, device=device) torques[..., 2] = TORQUE_MAGNITUDE - cube_object.permanent_wrench_composer.set_forces_and_torques( + cube_object.permanent_wrench_composer.set_forces_and_torques_index( forces=forces, torques=torques, body_ids=body_ids, @@ -279,10 +279,13 @@ def test_global_torque_invariant_under_rotation(device): # Rotate body 90deg about X and zero out velocities so phase 2 starts from rest # (avoids gyroscopic cross-coupling at high omega) - root_pose = cube_object.data.root_state_w.torch[0, :7].clone().unsqueeze(0) + root_pose = cube_object.data.root_pose_w.torch[0].clone().unsqueeze(0) root_pose[0, 3:7] = torch.tensor([0.7071, 0.0, 0.0, 0.7071], device=device) # 90deg about X (xyzw) - cube_object.write_root_pose_to_sim(root_pose) - cube_object.write_root_velocity_to_sim(torch.zeros(1, 6, device=device)) + cube_object.write_root_pose_to_sim_index(root_pose=root_pose) + + root_vel = cube_object.data.root_vel_w.torch.clone() + root_vel[0, :] = 0.0 + cube_object.write_root_velocity_to_sim_index(root_velocity=root_vel) # Phase 2: run N_STEPS from rest with different body orientation for _ in range(N_STEPS): @@ -324,13 +327,16 @@ def test_global_force_torque_after_translation(device): body_ids, _ = cube_object.find_bodies(".*") # Phase 1 setup: Move cube to (1, 0, 1) and apply force at (1, 0, 1) - root_state = cube_object.data.root_state_w.torch.clone() - root_state[0, 0] = 1.0 # x = 1 - root_state[0, 1] = 0.0 # y = 0 - root_state[0, 2] = 1.0 # z = 1 - root_state[0, 3:7] = torch.tensor([0.0, 0.0, 0.0, 1.0], device=device) # identity quat (xyzw) - root_state[0, 7:] = 0.0 # zero velocity - cube_object.write_root_state_to_sim(root_state) + root_pose = cube_object.data.root_pose_w.torch.clone() + root_pose[0, 0] = 1.0 # x = 1 + root_pose[0, 1] = 0.0 # y = 0 + root_pose[0, 2] = 1.0 # z = 1 + root_pose[0, 3:7] = torch.tensor([0.0, 0.0, 0.0, 1.0], device=device) # identity quat (xyzw) + cube_object.write_root_pose_to_sim_index(root_pose=root_pose) + + root_vel = cube_object.data.root_vel_w.torch.clone() + root_vel[0, :] = 0.0 # zero velocity + cube_object.write_root_velocity_to_sim_index(root_velocity=root_vel) # Step once to let the state settle sim.step() @@ -343,7 +349,7 @@ def test_global_force_torque_after_translation(device): forces[..., 1] = FORCE_MAGNITUDE # +Y force torques = torch.zeros(1, len(body_ids), 3, device=device) - cube_object.permanent_wrench_composer.set_forces_and_torques( + cube_object.permanent_wrench_composer.set_forces_and_torques_index( forces=forces, torques=torques, positions=com_pos, @@ -369,13 +375,16 @@ def test_global_force_torque_after_translation(device): ) # Phase 2: Teleport cube to origin, zero velocity, don't re-apply force - root_state2 = cube_object.data.root_state_w.torch.clone() - root_state2[0, 0] = 0.0 # x = 0 - root_state2[0, 1] = 0.0 - root_state2[0, 2] = 1.0 # z = 1 - root_state2[0, 3:7] = torch.tensor([0.0, 0.0, 0.0, 1.0], device=device) # identity (xyzw) - root_state2[0, 7:] = 0.0 # zero velocity - cube_object.write_root_state_to_sim(root_state2) + root_pose2 = cube_object.data.root_pose_w.torch.clone() + root_pose2[0, 0] = 0.0 # x = 0 + root_pose2[0, 1] = 0.0 + root_pose2[0, 2] = 1.0 # z = 1 + root_pose2[0, 3:7] = torch.tensor([0.0, 0.0, 0.0, 1.0], device=device) # identity (xyzw) + cube_object.write_root_pose_to_sim_index(root_pose=root_pose2) + + root_vel2 = cube_object.data.root_vel_w.torch.clone() + root_vel2[0, :] = 0.0 # zero velocity + cube_object.write_root_velocity_to_sim_index(root_velocity=root_vel2) # Step once to let state settle sim.step() @@ -422,13 +431,16 @@ def test_global_force_torque_reverses_on_opposite_side(device): body_ids, _ = cube_object.find_bodies(".*") # Move cube to (-1, 0, 1) - root_state = cube_object.data.root_state_w.torch.clone() - root_state[0, 0] = -1.0 - root_state[0, 1] = 0.0 - root_state[0, 2] = 1.0 - root_state[0, 3:7] = torch.tensor([0.0, 0.0, 0.0, 1.0], device=device) # identity (xyzw) - root_state[0, 7:] = 0.0 - cube_object.write_root_state_to_sim(root_state) + root_pose = cube_object.data.root_pose_w.torch.clone() + root_pose[0, 0] = -1.0 + root_pose[0, 1] = 0.0 + root_pose[0, 2] = 1.0 + root_pose[0, 3:7] = torch.tensor([0.0, 0.0, 0.0, 1.0], device=device) # identity (xyzw) + cube_object.write_root_pose_to_sim_index(root_pose=root_pose) + + root_vel = cube_object.data.root_vel_w.torch.clone() + root_vel[0, :] = 0.0 + cube_object.write_root_velocity_to_sim_index(root_velocity=root_vel) sim.step() cube_object.update(sim.cfg.dt) @@ -439,7 +451,7 @@ def test_global_force_torque_reverses_on_opposite_side(device): positions = torch.zeros(1, len(body_ids), 3, device=device) positions[..., 2] = 1.0 # P = (0, 0, 1) - cube_object.permanent_wrench_composer.set_forces_and_torques( + cube_object.permanent_wrench_composer.set_forces_and_torques_index( forces=forces, torques=torques, positions=positions, @@ -457,13 +469,16 @@ def test_global_force_torque_reverses_on_opposite_side(device): assert omega_z_phase1 > 0.1, f"Phase 1: expected positive omega_z, got {omega_z_phase1}" # Phase 2: Teleport cube to (+1, 0, 1), zero velocity - root_state2 = cube_object.data.root_state_w.torch.clone() - root_state2[0, 0] = 1.0 - root_state2[0, 1] = 0.0 - root_state2[0, 2] = 1.0 - root_state2[0, 3:7] = torch.tensor([0.0, 0.0, 0.0, 1.0], device=device) # identity (xyzw) - root_state2[0, 7:] = 0.0 - cube_object.write_root_state_to_sim(root_state2) + root_pose2 = cube_object.data.root_pose_w.torch.clone() + root_pose2[0, 0] = 1.0 + root_pose2[0, 1] = 0.0 + root_pose2[0, 2] = 1.0 + root_pose2[0, 3:7] = torch.tensor([0.0, 0.0, 0.0, 1.0], device=device) # identity (xyzw) + cube_object.write_root_pose_to_sim_index(root_pose=root_pose2) + + root_vel2 = cube_object.data.root_vel_w.torch.clone() + root_vel2[0, :] = 0.0 + cube_object.write_root_velocity_to_sim_index(root_velocity=root_vel2) sim.step() cube_object.update(sim.cfg.dt) @@ -493,13 +508,16 @@ def test_global_force_no_position_no_torque(device): body_ids, _ = cube_object.find_bodies(".*") # Move cube to (2, 0, 1) - root_state = cube_object.data.root_state_w.torch.clone() - root_state[0, 0] = 2.0 - root_state[0, 1] = 0.0 - root_state[0, 2] = 1.0 - root_state[0, 3:7] = torch.tensor([0.0, 0.0, 0.0, 1.0], device=device) # identity (xyzw) - root_state[0, 7:] = 0.0 - cube_object.write_root_state_to_sim(root_state) + root_pose = cube_object.data.root_pose_w.torch.clone() + root_pose[0, 0] = 2.0 + root_pose[0, 1] = 0.0 + root_pose[0, 2] = 1.0 + root_pose[0, 3:7] = torch.tensor([0.0, 0.0, 0.0, 1.0], device=device) # identity (xyzw) + cube_object.write_root_pose_to_sim_index(root_pose=root_pose) + + root_vel = cube_object.data.root_vel_w.torch.clone() + root_vel[0, :] = 0.0 + cube_object.write_root_velocity_to_sim_index(root_velocity=root_vel) sim.step() cube_object.update(sim.cfg.dt) @@ -508,7 +526,7 @@ def test_global_force_no_position_no_torque(device): forces[..., 1] = FORCE_MAGNITUDE torques = torch.zeros(1, len(body_ids), 3, device=device) - cube_object.permanent_wrench_composer.set_forces_and_torques( + cube_object.permanent_wrench_composer.set_forces_and_torques_index( forces=forces, torques=torques, body_ids=body_ids, @@ -549,19 +567,21 @@ def test_multi_cube_different_torques_from_same_force(device): body_ids, _ = cube_object.find_bodies(".*") # Position cubes: Cube 0 at (-1, 0, 1), Cube 1 at (+1, 0, 1) - root_state = cube_object.data.root_state_w.torch.clone() - root_state[0, 0] = -1.0 - root_state[0, 1] = 0.0 - root_state[0, 2] = 1.0 - root_state[0, 3:7] = torch.tensor([0.0, 0.0, 0.0, 1.0], device=device) # identity (xyzw) - root_state[0, 7:] = 0.0 - - root_state[1, 0] = 1.0 - root_state[1, 1] = 0.0 - root_state[1, 2] = 1.0 - root_state[1, 3:7] = torch.tensor([0.0, 0.0, 0.0, 1.0], device=device) # identity (xyzw) - root_state[1, 7:] = 0.0 - cube_object.write_root_state_to_sim(root_state) + root_pose = cube_object.data.root_pose_w.torch.clone() + root_pose[0, 0] = -1.0 + root_pose[0, 1] = 0.0 + root_pose[0, 2] = 1.0 + root_pose[0, 3:7] = torch.tensor([0.0, 0.0, 0.0, 1.0], device=device) # identity (xyzw) + + root_pose[1, 0] = 1.0 + root_pose[1, 1] = 0.0 + root_pose[1, 2] = 1.0 + root_pose[1, 3:7] = torch.tensor([0.0, 0.0, 0.0, 1.0], device=device) # identity (xyzw) + cube_object.write_root_pose_to_sim_index(root_pose=root_pose) + + root_vel = cube_object.data.root_vel_w.torch.clone() + root_vel[:, :] = 0.0 + cube_object.write_root_velocity_to_sim_index(root_velocity=root_vel) sim.step() cube_object.update(sim.cfg.dt) @@ -572,7 +592,7 @@ def test_multi_cube_different_torques_from_same_force(device): positions = torch.zeros(2, len(body_ids), 3, device=device) positions[..., 2] = 1.0 # P = (0, 0, 1) - cube_object.permanent_wrench_composer.set_forces_and_torques( + cube_object.permanent_wrench_composer.set_forces_and_torques_index( forces=forces, torques=torques, positions=positions, @@ -628,20 +648,22 @@ def test_global_force_torque_far_from_origin(device): body_ids, _ = cube_object.find_bodies(".*") # Position cubes: Cube 0 near origin, Cube 1 far from origin - root_state = cube_object.data.root_state_w.torch.clone() + root_pose = cube_object.data.root_pose_w.torch.clone() # Cube 0 at (0, 0, 1) - root_state[0, 0] = 0.0 - root_state[0, 1] = 0.0 - root_state[0, 2] = 1.0 - root_state[0, 3:7] = torch.tensor([0.0, 0.0, 0.0, 1.0], device=device) # identity (xyzw) - root_state[0, 7:] = 0.0 + root_pose[0, 0] = 0.0 + root_pose[0, 1] = 0.0 + root_pose[0, 2] = 1.0 + root_pose[0, 3:7] = torch.tensor([0.0, 0.0, 0.0, 1.0], device=device) # identity (xyzw) # Cube 1 at (2000, 0, 1) - root_state[1, 0] = 2000.0 - root_state[1, 1] = 0.0 - root_state[1, 2] = 1.0 - root_state[1, 3:7] = torch.tensor([0.0, 0.0, 0.0, 1.0], device=device) # identity (xyzw) - root_state[1, 7:] = 0.0 - cube_object.write_root_state_to_sim(root_state) + root_pose[1, 0] = 2000.0 + root_pose[1, 1] = 0.0 + root_pose[1, 2] = 1.0 + root_pose[1, 3:7] = torch.tensor([0.0, 0.0, 0.0, 1.0], device=device) # identity (xyzw) + cube_object.write_root_pose_to_sim_index(root_pose=root_pose) + + root_vel = cube_object.data.root_vel_w.torch.clone() + root_vel[:, :] = 0.0 + cube_object.write_root_velocity_to_sim_index(root_velocity=root_vel) sim.step() cube_object.update(sim.cfg.dt) @@ -655,7 +677,7 @@ def test_global_force_torque_far_from_origin(device): positions = com_pos.clone() positions[..., 0] += 1.0 # +1m X offset from CoM - cube_object.permanent_wrench_composer.set_forces_and_torques( + cube_object.permanent_wrench_composer.set_forces_and_torques_index( forces=forces, torques=torques, positions=positions, @@ -723,19 +745,21 @@ def test_global_force_no_position_no_rotation_large_offset(device): body_ids, _ = cube_object.find_bodies(".*") # Place cube at large X offset - root_state = cube_object.data.default_root_state.torch.clone() - root_state[0, 0] = 2000.0 # large X position - root_state[0, 1] = 0.0 - root_state[0, 2] = 1.0 - cube_object.write_root_pose_to_sim(root_state[:, :7]) - cube_object.write_root_velocity_to_sim(root_state[:, 7:]) + root_pose = cube_object.data.default_root_pose.torch.clone() + root_pose[0, 0] = 2000.0 # large X position + root_pose[0, 1] = 0.0 + root_pose[0, 2] = 1.0 + cube_object.write_root_pose_to_sim_index(root_pose=root_pose) + + root_vel = cube_object.data.default_root_vel.torch.clone() + cube_object.write_root_velocity_to_sim_index(root_velocity=root_vel) cube_object.reset() # Apply global force without positions (should go to CoM, no torque) forces = torch.zeros(cube_object.num_instances, len(body_ids), 3, device=device) forces[0, :, 1] = 10.0 # F_y = 10 N - cube_object.permanent_wrench_composer.set_forces_and_torques( + cube_object.permanent_wrench_composer.set_forces_and_torques_index( forces=forces, body_ids=body_ids, is_global=True, @@ -778,12 +802,14 @@ def test_global_force_at_com_position_no_rotation_large_offset(device): body_ids, _ = cube_object.find_bodies(".*") # Place cube at large X offset - root_state = cube_object.data.default_root_state.torch.clone() - root_state[0, 0] = 2000.0 - root_state[0, 1] = 0.0 - root_state[0, 2] = 1.0 - cube_object.write_root_pose_to_sim(root_state[:, :7]) - cube_object.write_root_velocity_to_sim(root_state[:, 7:]) + root_pose = cube_object.data.default_root_pose.torch.clone() + root_pose[0, 0] = 2000.0 + root_pose[0, 1] = 0.0 + root_pose[0, 2] = 1.0 + cube_object.write_root_pose_to_sim_index(root_pose=root_pose) + + root_vel = cube_object.data.default_root_vel.torch.clone() + cube_object.write_root_velocity_to_sim_index(root_velocity=root_vel) cube_object.reset() # Apply global force AT the cube's position (torque should cancel) @@ -794,7 +820,7 @@ def test_global_force_at_com_position_no_rotation_large_offset(device): positions[0, :, 0] = 2000.0 positions[0, :, 2] = 1.0 - cube_object.permanent_wrench_composer.set_forces_and_torques( + cube_object.permanent_wrench_composer.set_forces_and_torques_index( forces=forces, positions=positions, body_ids=body_ids, diff --git a/source/isaaclab/test/utils/test_wrench_composer_vs_physx.py b/source/isaaclab/test/utils/test_wrench_composer_vs_physx.py index 8d47b003369c..ca8f22be437c 100644 --- a/source/isaaclab/test/utils/test_wrench_composer_vs_physx.py +++ b/source/isaaclab/test/utils/test_wrench_composer_vs_physx.py @@ -110,7 +110,7 @@ def test_composer_vs_physx_local_force(device): forces[..., 0] = FORCE_MAGNITUDE torques = torch.zeros(1, len(body_ids), 3, device=device) - cube_composer.permanent_wrench_composer.set_forces_and_torques( + cube_composer.permanent_wrench_composer.set_forces_and_torques_index( forces=forces, torques=torques, body_ids=body_ids, @@ -175,7 +175,7 @@ def test_composer_vs_physx_global_force(device): forces[..., 0] = FORCE_MAGNITUDE torques = torch.zeros(1, len(body_ids), 3, device=device) - cube_composer.permanent_wrench_composer.set_forces_and_torques( + cube_composer.permanent_wrench_composer.set_forces_and_torques_index( forces=forces, torques=torques, body_ids=body_ids, @@ -249,7 +249,7 @@ def test_composer_vs_physx_local_force_at_position(device): positions = torch.zeros(1, len(body_ids), 3, device=device) positions[..., 1] = 0.5 # +0.5m Y offset in local frame - cube_composer.permanent_wrench_composer.set_forces_and_torques( + cube_composer.permanent_wrench_composer.set_forces_and_torques_index( forces=forces, torques=torques, positions=positions, @@ -322,7 +322,7 @@ def test_composer_vs_physx_global_force_at_position(device): pos_composer = cube_composer.data.body_com_pos_w.torch[:, body_ids, :3].clone() + offset pos_raw = cube_raw.data.body_com_pos_w.torch[:, body_ids, :3].clone() + offset - cube_composer.permanent_wrench_composer.set_forces_and_torques( + cube_composer.permanent_wrench_composer.set_forces_and_torques_index( forces=forces, torques=torques, positions=pos_composer, @@ -387,7 +387,7 @@ def test_composer_vs_physx_local_torque(device): torques = torch.zeros(1, len(body_ids), 3, device=device) torques[..., 2] = TORQUE_MAGNITUDE - cube_composer.permanent_wrench_composer.set_forces_and_torques( + cube_composer.permanent_wrench_composer.set_forces_and_torques_index( forces=forces, torques=torques, body_ids=body_ids, @@ -452,7 +452,7 @@ def test_composer_vs_physx_global_torque(device): torques = torch.zeros(1, len(body_ids), 3, device=device) torques[..., 2] = TORQUE_MAGNITUDE - cube_composer.permanent_wrench_composer.set_forces_and_torques( + cube_composer.permanent_wrench_composer.set_forces_and_torques_index( forces=forces, torques=torques, body_ids=body_ids, @@ -513,7 +513,7 @@ def test_composer_vs_physx_global_force_multi_env(device): forces[..., 0] = FORCE_MAGNITUDE torques = torch.zeros(NUM_CUBES_MULTI, len(body_ids), 3, device=device) - cube_composer.permanent_wrench_composer.set_forces_and_torques( + cube_composer.permanent_wrench_composer.set_forces_and_torques_index( forces=forces, torques=torques, body_ids=body_ids, @@ -605,7 +605,7 @@ def apply_global_force(): forces = torch.zeros(NUM_CUBES_MULTI, len(body_ids), 3, device=device) forces[..., 0] = FORCE_MAGNITUDE torques = torch.zeros(NUM_CUBES_MULTI, len(body_ids), 3, device=device) - cube_composer.permanent_wrench_composer.set_forces_and_torques( + cube_composer.permanent_wrench_composer.set_forces_and_torques_index( forces=forces, torques=torques, body_ids=body_ids, @@ -641,8 +641,18 @@ def apply_global_force(): reset_ids_torch = torch.tensor(reset_ids, dtype=torch.long, device=device) # Reset root state using captured world-frame initial state (includes env origins) - cube_composer.write_root_state_to_sim(initial_state_composer[reset_ids_torch], env_ids=reset_ids_torch) - cube_raw.write_root_state_to_sim(initial_state_raw[reset_ids_torch], env_ids=reset_ids_torch) + cube_composer.write_root_link_pose_to_sim_index( + root_pose=initial_state_composer[reset_ids_torch, :7], env_ids=reset_ids_torch + ) + cube_composer.write_root_com_velocity_to_sim_index( + root_velocity=initial_state_composer[reset_ids_torch, 7:], env_ids=reset_ids_torch + ) + cube_raw.write_root_link_pose_to_sim_index( + root_pose=initial_state_raw[reset_ids_torch, :7], env_ids=reset_ids_torch + ) + cube_raw.write_root_com_velocity_to_sim_index( + root_velocity=initial_state_raw[reset_ids_torch, 7:], env_ids=reset_ids_torch + ) cube_composer.reset(reset_ids) cube_raw.reset(reset_ids) @@ -717,7 +727,7 @@ def test_composer_vs_physx_payload_scenario(device): forces[..., 2] = -payload_force torques = torch.zeros(1, len(body_ids), 3, device=device) - cube_composer.permanent_wrench_composer.set_forces_and_torques( + cube_composer.permanent_wrench_composer.set_forces_and_torques_index( forces=forces, torques=torques, body_ids=body_ids, @@ -790,7 +800,7 @@ def test_composer_vs_physx_permanent_global_force_at_position_long_run(device): pos_composer = cube_composer.data.body_com_pos_w.torch[:, body_ids, :3].clone() + offset pos_raw = cube_raw.data.body_com_pos_w.torch[:, body_ids, :3].clone() + offset - cube_composer.permanent_wrench_composer.set_forces_and_torques( + cube_composer.permanent_wrench_composer.set_forces_and_torques_index( forces=forces, torques=torques, positions=pos_composer, From a64fcf1cb986fa603ecb137ec6a62b68b45d262c Mon Sep 17 00:00:00 2001 From: Antoine RICHARD Date: Fri, 8 May 2026 09:41:52 +0200 Subject: [PATCH 17/51] Adds PVA and joint wrench sensor docs (#5532) # Description Adds the missing core-concepts sensor documentation for the ground-truth PVA sensor and joint wrench sensor. The sensor overview now links both pages, the public `isaaclab.sensors` API page includes `Pva`, `PvaData`, and `PvaCfg`, and the sensor module table documents the joint wrench sensor prim-path expectation. Fixes isaac-sim/IsaacLab-Internal#880 Validation: - `./isaaclab.sh -f` - `git diff --check` - Verified `origin/develop` did not list `pva` or `joint_wrench_sensor` from `docs/source/overview/core-concepts/sensors/index.rst`, and this branch does. - Parsed the two new RST pages with `docutils` using local stubs for Sphinx-only directives and roles. - `make -C docs current-docs` was attempted locally but could not run because `sphinx-build` is not installed in this environment. ## Type of change - Documentation update ## Screenshots N/A; documentation text update. ## Checklist - [x] I have read and understood the [contribution guidelines](https://isaac-sim.github.io/IsaacLab/main/source/refs/contributing.html) - [x] I have run the [`pre-commit` checks](https://pre-commit.com/) with `./isaaclab.sh --format` - [x] I have made corresponding changes to the documentation - [ ] 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 added a changelog fragment under `source//changelog.d/` for every touched package (do **not** edit `CHANGELOG.rst` or bump `extension.toml` -- CI handles that) - [x] I have added my name to the `CONTRIBUTORS.md` or my name already exists there --- docs/source/api/lab/isaaclab.sensors.rst | 22 ++++++++ .../migration/migrating_to_isaaclab_3-0.rst | 4 ++ .../overview/core-concepts/sensors/index.rst | 2 + .../sensors/joint_wrench_sensor.rst | 42 +++++++++++++++ .../overview/core-concepts/sensors/pva.rst | 53 +++++++++++++++++++ scripts/demos/sensors/pva_sensor.py | 4 +- .../antoiner-docs-sensor-updates.rst | 8 +++ source/isaaclab/isaaclab/sensors/__init__.py | 2 + 8 files changed, 135 insertions(+), 2 deletions(-) create mode 100644 docs/source/overview/core-concepts/sensors/joint_wrench_sensor.rst create mode 100644 docs/source/overview/core-concepts/sensors/pva.rst create mode 100644 source/isaaclab/changelog.d/antoiner-docs-sensor-updates.rst diff --git a/docs/source/api/lab/isaaclab.sensors.rst b/docs/source/api/lab/isaaclab.sensors.rst index 1beccd5481f1..537dc8dcaf43 100644 --- a/docs/source/api/lab/isaaclab.sensors.rst +++ b/docs/source/api/lab/isaaclab.sensors.rst @@ -36,6 +36,9 @@ MultiMeshRayCasterCameraCfg Imu ImuCfg + Pva + PvaData + PvaCfg JointWrenchSensor JointWrenchSensorData JointWrenchSensorCfg @@ -193,6 +196,25 @@ Inertia Measurement Unit :show-inheritance: :exclude-members: __init__, class_type +Pose Velocity Acceleration Sensor +--------------------------------- + +.. autoclass:: Pva + :members: + :inherited-members: + :show-inheritance: + +.. autoclass:: PvaData + :members: + :inherited-members: + :exclude-members: __init__ + +.. autoclass:: PvaCfg + :members: + :inherited-members: + :show-inheritance: + :exclude-members: __init__, class_type + Joint Wrench Sensor ------------------- diff --git a/docs/source/migration/migrating_to_isaaclab_3-0.rst b/docs/source/migration/migrating_to_isaaclab_3-0.rst index 4d29d5f4c8fe..be5703ab1261 100644 --- a/docs/source/migration/migrating_to_isaaclab_3-0.rst +++ b/docs/source/migration/migrating_to_isaaclab_3-0.rst @@ -251,6 +251,8 @@ If you were using the old ``Imu`` sensor, you need to decide which new sensor to - Use :class:`~isaaclab.sensors.Imu` / :class:`~isaaclab.sensors.ImuCfg` if you only need angular velocity and linear acceleration (as a real IMU provides). +For configuration and data access examples, see the :ref:`overview_sensors_pva`. + **Import changes:** .. code-block:: python @@ -346,6 +348,8 @@ implementations and returns separate force [N] and torque [N·m] buffers. The sensor reports wrenches in the child-side incoming joint frame, with torque referenced at the child-side joint anchor. +For configuration and data access examples, see the :ref:`overview_sensors_joint_wrench`. + **Before (Isaac Lab 2.x):** .. code-block:: python diff --git a/docs/source/overview/core-concepts/sensors/index.rst b/docs/source/overview/core-concepts/sensors/index.rst index d2c63f212b76..f32923ab9c30 100644 --- a/docs/source/overview/core-concepts/sensors/index.rst +++ b/docs/source/overview/core-concepts/sensors/index.rst @@ -18,5 +18,7 @@ The following pages describe the available sensors in more detail: contact_sensor frame_transformer imu + pva + joint_wrench_sensor ray_caster visuo_tactile_sensor diff --git a/docs/source/overview/core-concepts/sensors/joint_wrench_sensor.rst b/docs/source/overview/core-concepts/sensors/joint_wrench_sensor.rst new file mode 100644 index 000000000000..d1357645ddc1 --- /dev/null +++ b/docs/source/overview/core-concepts/sensors/joint_wrench_sensor.rst @@ -0,0 +1,42 @@ +.. _overview_sensors_joint_wrench: + +.. currentmodule:: isaaclab + +Joint Wrench Sensor +=================== + +The joint wrench sensor reports incoming joint reaction wrenches for selected +articulation bodies. It exposes force [N] and torque [N·m] buffers separately, +with entries ordered by the sensor's :attr:`~isaaclab.sensors.JointWrenchSensor.body_names`. +The default convention is ``incoming_joint_frame``, which expresses each wrench +in the child-side joint frame at the child-side joint anchor. + +The sensor is configured on an articulation prim and can then be used directly +or through manager terms such as :func:`~isaaclab.envs.mdp.body_incoming_wrench`. +For example, the Ant environment adds a joint wrench sensor to the scene: + +.. literalinclude:: ../../../../../source/isaaclab_tasks/isaaclab_tasks/manager_based/classic/ant/ant_env_cfg.py + :language: python + :lines: 91-95 + +The same environment uses :class:`~isaaclab.managers.SceneEntityCfg` to select +the reported foot bodies for an observation term: + +.. literalinclude:: ../../../../../source/isaaclab_tasks/isaaclab_tasks/manager_based/classic/ant/ant_env_cfg.py + :language: python + :lines: 133-142 + +Direct access to the sensor data follows the usual scene lookup pattern. + +.. code-block:: python + + joint_wrench = scene["joint_wrench"] + foot_ids, _ = joint_wrench.find_bodies([".*foot"]) + + force = joint_wrench.data.force.torch[:, foot_ids] + torque = joint_wrench.data.torque.torch[:, foot_ids] + wrench = torch.cat((force, torque), dim=-1) + +The resulting ``wrench`` tensor has shape ``(num_envs, num_selected_bodies, 6)`` +and stores the force components followed by the torque components for each +selected body. diff --git a/docs/source/overview/core-concepts/sensors/pva.rst b/docs/source/overview/core-concepts/sensors/pva.rst new file mode 100644 index 000000000000..aa522984bd51 --- /dev/null +++ b/docs/source/overview/core-concepts/sensors/pva.rst @@ -0,0 +1,53 @@ +.. _overview_sensors_pva: + +.. currentmodule:: isaaclab + +Pose Velocity Acceleration (PVA) Sensor +======================================= + +The Pose Velocity Acceleration (PVA) sensor is a ground-truth sensor for reading +the kinematic state of a frame in the simulation. It reports the sensor pose in +the world frame, projected gravity, linear and angular velocities in the sensor +frame, and coordinate accelerations in the sensor frame. Unlike +:class:`~isaaclab.sensors.Imu`, the PVA sensor does not model proper +acceleration from an accelerometer. Use the IMU sensor when the observation +should include accelerometer-like gravity bias behavior. + +The sensor can be attached to a rigid body or to a child prim under a rigid-body +ancestor. If the configured prim is not itself rigid, Isaac Lab queries the +closest rigid ancestor and composes the fixed transform to the requested prim +with the configured sensor offset. + +Consider a simple environment with an Anymal Quadruped equipped with PVA sensors +on its front feet. + +.. literalinclude:: ../../../../../scripts/demos/sensors/pva_sensor.py + :language: python + :lines: 43-59 + +Retrieving values from the sensor follows the same pattern as the other Isaac +Lab sensors. The data fields are exposed as :class:`~isaaclab.utils.warp.ProxyArray` +buffers and can be converted to Torch tensors with the ``torch`` property. + +.. code-block:: python + + pva_data = scene["pva_LF"].data + print("Pose in world frame: ", pva_data.pose_w.torch) + print("Linear velocity in PVA frame: ", pva_data.lin_vel_b.torch) + print("Angular velocity in PVA frame: ", pva_data.ang_vel_b.torch) + print("Linear acceleration in PVA frame: ", pva_data.lin_acc_b.torch) + print("Angular acceleration in PVA frame: ", pva_data.ang_acc_b.torch) + print("Projected gravity in PVA frame: ", pva_data.projected_gravity_b.torch) + +The complete demo can be run with: + +.. code-block:: bash + + ./isaaclab.sh -p scripts/demos/sensors/pva_sensor.py + +.. dropdown:: Code for pva_sensor.py + :icon: code + + .. literalinclude:: ../../../../../scripts/demos/sensors/pva_sensor.py + :language: python + :linenos: diff --git a/scripts/demos/sensors/pva_sensor.py b/scripts/demos/sensors/pva_sensor.py index a51ea7c17cc9..31066fb59164 100644 --- a/scripts/demos/sensors/pva_sensor.py +++ b/scripts/demos/sensors/pva_sensor.py @@ -54,9 +54,9 @@ class PvaSensorSceneCfg(InteractiveSceneCfg): # robot robot = ANYMAL_C_CFG.replace(prim_path="{ENV_REGEX_NS}/Robot") - pva_RF = PvaCfg(prim_path="{ENV_REGEX_NS}/Robot/LF_FOOT", debug_vis=True) + pva_LF = PvaCfg(prim_path="{ENV_REGEX_NS}/Robot/LF_FOOT", debug_vis=True) - pva_LF = PvaCfg(prim_path="{ENV_REGEX_NS}/Robot/RF_FOOT", debug_vis=True) + pva_RF = PvaCfg(prim_path="{ENV_REGEX_NS}/Robot/RF_FOOT", debug_vis=True) def run_simulator(sim: sim_utils.SimulationContext, scene: InteractiveScene): diff --git a/source/isaaclab/changelog.d/antoiner-docs-sensor-updates.rst b/source/isaaclab/changelog.d/antoiner-docs-sensor-updates.rst new file mode 100644 index 000000000000..fd8e62a260cb --- /dev/null +++ b/source/isaaclab/changelog.d/antoiner-docs-sensor-updates.rst @@ -0,0 +1,8 @@ +Fixed +^^^^^ + +* Fixed the sensor overview documentation to include + :class:`~isaaclab.sensors.Pva` and + :class:`~isaaclab.sensors.JointWrenchSensor`. +* Fixed the PVA sensor demo to align front-foot sensor names with their prim + paths. diff --git a/source/isaaclab/isaaclab/sensors/__init__.py b/source/isaaclab/isaaclab/sensors/__init__.py index 717fc4a7163c..fa578a2677d0 100644 --- a/source/isaaclab/isaaclab/sensors/__init__.py +++ b/source/isaaclab/isaaclab/sensors/__init__.py @@ -34,6 +34,8 @@ +---------------------+---------------------------+---------------------------------------------------------------+ | Pva | /World/robot/base | Leaf exists and is a physics body (Rigid Body) | +---------------------+---------------------------+---------------------------------------------------------------+ +| Joint Wrench Sensor | /World/robot | Leaf exists and is an articulation | ++---------------------+---------------------------+---------------------------------------------------------------+ """ From a784ed9d3faecded3055cb3f26a21a65a0d6db01 Mon Sep 17 00:00:00 2001 From: hujc Date: Fri, 8 May 2026 03:14:47 -0700 Subject: [PATCH 18/51] [CI unblock] Skip viewergl-fully-black test + fix warp intersphinx 404 (#5538) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit ## Summary Two unrelated CI breakages on develop, bundled here so develop turns green in one PR. ### 1. Skip the failing viewergl test `test_cartpole_newton_visualizer_viewergl_rgb_motion[physx,newton]` started returning all-black frames on develop after `nvcr.io/nvidian/isaac-sim:latest-develop` flipped to a Kit 110.1.1 + USD 25.11 base. The failure has been deterministic across multiple PRs (#5523, #5495, #5408, …). Investigation so far has ruled out: - PR https://github.com/isaac-sim/IsaacLab/pull/5521 (revert in https://github.com/isaac-sim/IsaacLab/pull/5539 still failed) - Newton 1.0 → 1.2.0rc2 viewer code regression (only 7-line addition; ViewerGL alone yields 1.08M nonzero pixels) - warp 1.12 → 1.13 RegisteredGLBuffer ABI (byte-identical) - Module-load side effects of `isaaclab_physx.renderers` - CUDA-GL interop (PR #5540 diagnostic confirms direct CPU FBO readback also returns zeros, with `GL_NO_ERROR`) - GL context-currency (PR #5541 H6 attempt: still fails) - GL/CUDA sync (PR #5542 H4 attempt: still fails) Diagnostic output (PR #5540 v2): ``` [VIZDIAG] fbo=c_uint(8) pbo=None size=600x600 [VIZDIAG] glGetError before: GL_NO_ERROR [VIZDIAG] CPU-readback: nonzero=0/1080000 max=0 err=GL_NO_ERROR [VIZDIAG] PBO-result: nonzero=0/1080000 max=0 ``` The FBO itself is empty — Newton's pyglet/EGL renderer is not depositing pixels under Kit 110.1.1, even though `tiled_camera_rgb_non_black` (Kit RTX path) on the same env passes. Underlying root cause still being chased; this PR ships the skip to unblock develop. ### 2. Fix warp intersphinx 404 in docs build `https://nvidia.github.io/warp/objects.inv` started returning 404 — Warp's `objects.inv` only lives at `/stable/` and `/latest/` now. With Sphinx's `warnings_treated_as_errors`, the broken intersphinx fetch fails the docs build on every PR. Pinning to `/stable/` (matches the existing PyTorch `/docs/2.11/` workaround pattern in the same file). Verified `https://nvidia.github.io/warp/stable/objects.inv` returns 200. ## Test plan - [x] CI `isaaclab_visualizers` on this branch — was passing earlier with the skip; will re-verify with the bundled docs fix - [ ] CI `Build Latest Docs` on this branch — must turn green (was failing on every recent PR before this fix) ## Re-enable plan Once the underlying viewergl bug is identified and fixed, drop the `@pytest.mark.skip` decorator and remove the `jichuanh-disable-viewergl-flaky.skip` fragment. --- docs/conf.py | 3 ++- .../jichuanh-fix-warp-intersphinx.rst | 5 +++++ .../jichuanh-disable-viewergl-flaky.skip | 0 .../test/test_visualizer_cartpole_integration.py | 16 ++++++++++++++++ 4 files changed, 23 insertions(+), 1 deletion(-) create mode 100644 source/isaaclab/changelog.d/jichuanh-fix-warp-intersphinx.rst create mode 100644 source/isaaclab_visualizers/changelog.d/jichuanh-disable-viewergl-flaky.skip diff --git a/docs/conf.py b/docs/conf.py index 792ee6eeecbc..65ad5468d34e 100644 --- a/docs/conf.py +++ b/docs/conf.py @@ -140,7 +140,8 @@ "torch": ("https://docs.pytorch.org/docs/2.11/", None), "isaacsim": ("https://docs.isaacsim.omniverse.nvidia.com/6.0.0/py/", None), "gymnasium": ("https://gymnasium.farama.org/", None), - "warp": ("https://nvidia.github.io/warp/", None), + # NOTE: pinned to /stable/ because /objects.inv at the root currently 404s + "warp": ("https://nvidia.github.io/warp/stable/", None), "omniverse": ("https://docs.omniverse.nvidia.com/dev-guide/latest", None), } diff --git a/source/isaaclab/changelog.d/jichuanh-fix-warp-intersphinx.rst b/source/isaaclab/changelog.d/jichuanh-fix-warp-intersphinx.rst new file mode 100644 index 000000000000..7aa72335f9e1 --- /dev/null +++ b/source/isaaclab/changelog.d/jichuanh-fix-warp-intersphinx.rst @@ -0,0 +1,5 @@ +Fixed +^^^^^ + +* Fixed Sphinx docs build failing due to ``https://nvidia.github.io/warp/objects.inv`` returning 404. + Pinned the ``warp`` intersphinx mapping to ``/stable/``, which is where the inventory now lives. diff --git a/source/isaaclab_visualizers/changelog.d/jichuanh-disable-viewergl-flaky.skip b/source/isaaclab_visualizers/changelog.d/jichuanh-disable-viewergl-flaky.skip new file mode 100644 index 000000000000..e69de29bb2d1 diff --git a/source/isaaclab_visualizers/test/test_visualizer_cartpole_integration.py b/source/isaaclab_visualizers/test/test_visualizer_cartpole_integration.py index 42d1368dcebf..60f9921415cc 100644 --- a/source/isaaclab_visualizers/test/test_visualizer_cartpole_integration.py +++ b/source/isaaclab_visualizers/test/test_visualizer_cartpole_integration.py @@ -522,6 +522,22 @@ def test_cartpole_newton_visualizer_tiled_camera_rgb_non_black( @pytest.mark.isaacsim_ci +@pytest.mark.skip( + reason=( + "ViewerGL.get_frame returns a fully-black 600x600x3 buffer in CI on the current " + "Isaac Sim image + Newton 1.2.0rc2 + warp-lang 1.13 cohort. Failure is " + "deterministic across two consecutive reruns of the same SHA and reproduces on " + "every PR that touches the rendering / camera / sensor / USD stack (5 PRs hit it " + "in the last 100 build.yaml runs); zero failures on PRs outside that scope. " + "Investigation ruled out: rc1->rc2 viewer code diff (7-line image_logger.clear " + "only), wp.RegisteredGLBuffer API (byte-identical 1.12 vs 1.13), pure flakiness " + "(deterministic), and the bump cohort alone (warp-1.12 branches both pass and " + "fail). Strongest remaining hypothesis: a CUDA-OpenGL interop init-order " + "fragility in the PBO + glReadPixels + RegisteredGLBuffer.map path that gets " + "tipped by any source change perturbing GL/CUDA bring-up. Re-enable once root " + "cause is identified." + ) +) @pytest.mark.parametrize("backend_kind", ["physx", "newton"]) def test_cartpole_newton_visualizer_viewergl_rgb_motion(backend_kind: str, caplog: pytest.LogCaptureFixture) -> None: """Newton GL (``ViewerGL.get_frame``): full motion steps, last frame non-black; early vs late differ; logs.""" From 21a7919c48fc1360a7acc32d1344c04d8e314553 Mon Sep 17 00:00:00 2001 From: Antoine RICHARD Date: Fri, 8 May 2026 13:44:21 +0200 Subject: [PATCH 19/51] Replicates fk invalidation on other assets (#5367) # Description Replicates fk invalidation on other assets in Newton. Fixes #5359 ## Type of change - Bug fix (non-breaking change which fixes an issue) ## Checklist - [ ] I have read and understood the [contribution guidelines](https://isaac-sim.github.io/IsaacLab/main/source/refs/contributing.html) - [ ] I have run the [`pre-commit` checks](https://pre-commit.com/) with `./isaaclab.sh --format` - [ ] I have made corresponding changes to the documentation - [ ] My changes generate no new warnings - [ ] I have added tests that prove my fix is effective or that my feature works - [ ] I have updated the changelog and the corresponding version in the extension's `config/extension.toml` file - [ ] I have added my name to the `CONTRIBUTORS.md` or my name already exists there --- .../antoiner-fix-fk-invalidation.rst | 6 ++ .../assets/rigid_object/rigid_object.py | 4 + .../assets/rigid_object/rigid_object_data.py | 7 ++ .../test/assets/test_rigid_object.py | 74 +++++++++++++++++++ .../assets/test_rigid_object_collection.py | 63 ++++++++++++++++ 5 files changed, 154 insertions(+) create mode 100644 source/isaaclab_newton/changelog.d/antoiner-fix-fk-invalidation.rst diff --git a/source/isaaclab_newton/changelog.d/antoiner-fix-fk-invalidation.rst b/source/isaaclab_newton/changelog.d/antoiner-fix-fk-invalidation.rst new file mode 100644 index 000000000000..e3f16a0a8893 --- /dev/null +++ b/source/isaaclab_newton/changelog.d/antoiner-fix-fk-invalidation.rst @@ -0,0 +1,6 @@ +Fixed +^^^^^ + +* Fixed stale Newton forward-kinematics state after explicit pose writes so + downstream collision queries and :attr:`~isaaclab_newton.assets.RigidObjectData.body_link_pose_w` + reads use updated transforms. diff --git a/source/isaaclab_newton/isaaclab_newton/assets/rigid_object/rigid_object.py b/source/isaaclab_newton/isaaclab_newton/assets/rigid_object/rigid_object.py index 7e31fa22b60f..b93c9075393d 100644 --- a/source/isaaclab_newton/isaaclab_newton/assets/rigid_object/rigid_object.py +++ b/source/isaaclab_newton/isaaclab_newton/assets/rigid_object/rigid_object.py @@ -334,6 +334,7 @@ def write_root_link_pose_to_sim_index( self.data._root_link_state_w.timestamp = -1.0 if self.data._root_state_w is not None: self.data._root_state_w.timestamp = -1.0 + self.data._fk_timestamp = -1.0 # Forces a kinematic update to get the latest body link poses. SimulationManager.invalidate_fk(env_ids=env_ids, articulation_ids=self._root_view.articulation_ids) def write_root_link_pose_to_sim_mask( @@ -382,6 +383,7 @@ def write_root_link_pose_to_sim_mask( self.data._root_link_state_w.timestamp = -1.0 if self.data._root_state_w is not None: self.data._root_state_w.timestamp = -1.0 + self.data._fk_timestamp = -1.0 # Forces a kinematic update to get the latest body link poses. SimulationManager.invalidate_fk(env_mask=env_mask, articulation_ids=self._root_view.articulation_ids) def write_root_com_pose_to_sim_index( @@ -437,6 +439,7 @@ def write_root_com_pose_to_sim_index( self.data._root_link_state_w.timestamp = -1.0 if self.data._root_state_w is not None: self.data._root_state_w.timestamp = -1.0 + self.data._fk_timestamp = -1.0 # Forces a kinematic update to get the latest body link poses. SimulationManager.invalidate_fk(env_ids=env_ids, articulation_ids=self._root_view.articulation_ids) def write_root_com_pose_to_sim_mask( @@ -489,6 +492,7 @@ def write_root_com_pose_to_sim_mask( self.data._root_link_state_w.timestamp = -1.0 if self.data._root_state_w is not None: self.data._root_state_w.timestamp = -1.0 + self.data._fk_timestamp = -1.0 # Forces a kinematic update to get the latest body link poses. SimulationManager.invalidate_fk(env_mask=env_mask, articulation_ids=self._root_view.articulation_ids) def write_root_com_velocity_to_sim_index( diff --git a/source/isaaclab_newton/isaaclab_newton/assets/rigid_object/rigid_object_data.py b/source/isaaclab_newton/isaaclab_newton/assets/rigid_object/rigid_object_data.py index 0e9ecc8a41d0..43e719d3a580 100644 --- a/source/isaaclab_newton/isaaclab_newton/assets/rigid_object/rigid_object_data.py +++ b/source/isaaclab_newton/isaaclab_newton/assets/rigid_object/rigid_object_data.py @@ -76,6 +76,7 @@ def __init__(self, root_view: ArticulationView, device: str): # Set initial time stamp self._sim_timestamp = 0.0 self._is_primed = False + self._fk_timestamp = 0.0 # Convert to direction vector gravity = wp.to_torch(SimulationManager.get_model().gravity)[0] @@ -121,6 +122,9 @@ def update(self, dt: float) -> None: """ # update the simulation timestamp self._sim_timestamp += dt + # FK is current after a sim step — keep fk_timestamp in sync unless it was explicitly invalidated + if self._fk_timestamp >= 0.0: + self._fk_timestamp = self._sim_timestamp # Trigger an update of the body com acceleration buffer at a higher frequency # since we do finite differencing. self.body_com_acc_w @@ -291,6 +295,9 @@ def body_link_pose_w(self) -> ProxyArray: This quantity is the pose of the actor frame of the rigid body relative to the world. The orientation is provided in (x, y, z, w) format. """ + if self._fk_timestamp < self._sim_timestamp: + SimulationManager.forward() + self._fk_timestamp = self._sim_timestamp return self._body_link_pose_w_ta @property diff --git a/source/isaaclab_newton/test/assets/test_rigid_object.py b/source/isaaclab_newton/test/assets/test_rigid_object.py index 67796416dce6..ba2c47e24f9b 100644 --- a/source/isaaclab_newton/test/assets/test_rigid_object.py +++ b/source/isaaclab_newton/test/assets/test_rigid_object.py @@ -1259,3 +1259,77 @@ def test_warmup_attach_stage_not_called_for_cpu(): f"This indicates the CPU MBP broadphase double-initialization regression is present: " f"attach_stage() + force_load_physics_from_usd() must not be combined for CPU." ) + + +@pytest.mark.parametrize("device", ["cuda:0", "cpu"]) +@pytest.mark.parametrize("writer", ["link_index", "link_mask", "com_index", "com_mask"]) +@pytest.mark.isaacsim_ci +def test_body_link_pose_w_fresh_after_root_pose_write(device, writer): + """Regression: ``body_link_pose_w`` must reflect a freshly written root pose without an intervening sim step. + + After ``write_root_{link,com}_pose_to_sim_{index,mask}``, the cached ``_sim_bind_body_link_pose_w`` + (Newton ``body_q``) is stale until forward kinematics is re-evaluated. The getter must call + :meth:`SimulationManager.forward` so the returned tensor matches the written pose. Without the fix, + the getter returns the pre-write value. The write must also dirty the simulator-side + ``_fk_reset_mask`` so collision queries (which read ``body_q`` directly, not via the property) + re-run FK before the next step. + """ + + def _fk_reset_mask_dirty() -> bool: + assert SimulationManager._fk_reset_mask is not None + return bool(wp.to_torch(SimulationManager._fk_reset_mask).any().item()) + + num_cubes = 2 + with _newton_sim_context(device, gravity_enabled=False, auto_add_lighting=True) as sim: + sim._app_control_on_stop_handle = None + cube_object, _ = generate_cubes_scene(num_cubes=num_cubes, height=0.5, device=device) + + sim.reset() + assert cube_object.is_initialized + + # Step once so that _sim_timestamp > 0 and caches are primed. + sim.step() + cube_object.update(sim.cfg.dt) + + # Prime the body_link_pose_w cache with the current pose. + pre_write_pose = wp.to_torch(cube_object.data.body_link_pose_w).clone().view(num_cubes, 7) + + # Clear the dirty flag so we can observe that the write sets it. + SimulationManager.forward() + assert not _fk_reset_mask_dirty() + + # Build a target pose clearly distinct from the current one in both translation and orientation. + # Quaternion in (x, y, z, w) for 90° about z: [0, 0, sin(pi/4), cos(pi/4)] = [0, 0, sqrt(0.5), sqrt(0.5)]. + target_pose = wp.to_torch(cube_object.data.root_link_pose_w).clone() + target_pose[..., 0] += 10.0 + target_pose[..., 1] += 5.0 + target_pose[..., 2] += 2.0 + sqrt_half = 0.7071067811865476 + target_pose[..., 3] = 0.0 + target_pose[..., 4] = 0.0 + target_pose[..., 5] = sqrt_half + target_pose[..., 6] = sqrt_half + + if writer == "link_index": + cube_object.write_root_link_pose_to_sim_index(root_pose=target_pose) + elif writer == "link_mask": + cube_object.write_root_link_pose_to_sim_mask(root_pose=target_pose) + elif writer == "com_index": + cube_object.write_root_com_pose_to_sim_index(root_pose=target_pose) + elif writer == "com_mask": + cube_object.write_root_com_pose_to_sim_mask(root_pose=target_pose) + + # The simulator-side dirty flag must be set before any property read clears it via forward(). + assert _fk_reset_mask_dirty(), "pose write must call SimulationManager.invalidate_fk()" + + # Read without stepping: getter must trigger forward kinematics and return the fresh pose. + body_link = wp.to_torch(cube_object.data.body_link_pose_w).view(num_cubes, 7) + # Defeat alias accidents: the property must not still return the pre-write value. + assert not torch.allclose(body_link[..., :3], pre_write_pose[..., :3], rtol=1e-4, atol=1e-4), ( + "body_link_pose_w returned the pre-write cached pose; forward() was not invoked" + ) + # Translation must match the write. + torch.testing.assert_close(body_link[..., :3], target_pose[..., :3], rtol=1e-4, atol=1e-4) + # Orientation: compare via |q1 · q2| ≈ 1 to account for the q ≡ -q double cover. + quat_dot = torch.abs((body_link[..., 3:7] * target_pose[..., 3:7]).sum(dim=-1)) + torch.testing.assert_close(quat_dot, torch.ones_like(quat_dot), rtol=1e-4, atol=1e-4) diff --git a/source/isaaclab_newton/test/assets/test_rigid_object_collection.py b/source/isaaclab_newton/test/assets/test_rigid_object_collection.py index cec62a98bcd3..5ee470469548 100644 --- a/source/isaaclab_newton/test/assets/test_rigid_object_collection.py +++ b/source/isaaclab_newton/test/assets/test_rigid_object_collection.py @@ -892,3 +892,66 @@ def test_write_object_state_functions_data_consistency(num_envs, num_cubes, devi torch.testing.assert_close(body_com_vel_w, com_vel_w) torch.testing.assert_close(body_link_pose_w, link_pose_w) torch.testing.assert_close(body_com_vel_w[..., 3:], link_vel_w[..., 3:]) + + +@pytest.mark.parametrize("device", ["cuda:0", "cpu"]) +@pytest.mark.parametrize("writer", ["link_index", "link_mask", "com_index", "com_mask"]) +@pytest.mark.isaacsim_ci +def test_body_pose_write_marks_fk_reset_mask(device, writer): + """Regression: ``write_body_{link,com}_pose_to_sim_{index,mask}`` must mark FK dirty. + + For a collection, ``_sim_bind_body_link_pose_w`` is bound directly to the simulator's root-transforms + buffer, so the property read is not what becomes stale — the simulator's internal ``body_q`` used by + collision detection is. The write methods must therefore call :meth:`SimulationManager.invalidate_fk` + so downstream consumers re-run forward kinematics before the next step. Without the fix, + ``_fk_reset_mask`` remains unset after an explicit pose write. The buffer-aliasing invariant is + also pinned: a refactor that decouples ``_sim_bind_body_link_pose_w`` from the write target would + silently make the property stale, so we check the post-write pose matches the written value. + """ + + def _fk_reset_mask_dirty() -> bool: + assert SimulationManager._fk_reset_mask is not None + return bool(wp.to_torch(SimulationManager._fk_reset_mask).any().item()) + + num_envs = 2 + num_cubes = 2 + with _newton_sim_context(device, gravity_enabled=False, auto_add_lighting=True) as sim: + sim._app_control_on_stop_handle = None + cube_object, _ = generate_cubes_scene(num_envs=num_envs, num_cubes=num_cubes, height=0.5, device=device) + + sim.reset() + assert cube_object.is_initialized + + sim.step() + cube_object.update(sim.cfg.dt) + + # Clear the dirty flag so we can observe that the write sets it. + SimulationManager.forward() + assert not _fk_reset_mask_dirty() + + pre_write_pose = wp.to_torch(cube_object.data.body_link_pose_w).clone() + + target_pose = wp.to_torch(cube_object.data.body_link_pose_w).clone() + target_pose[..., 0] += 10.0 + target_pose[..., 1] += 5.0 + target_pose[..., 2] += 2.0 + + if writer == "link_index": + cube_object.write_body_link_pose_to_sim_index(body_poses=target_pose) + elif writer == "link_mask": + cube_object.write_body_link_pose_to_sim_mask(body_poses=target_pose) + elif writer == "com_index": + cube_object.write_body_com_pose_to_sim_index(body_poses=target_pose) + elif writer == "com_mask": + cube_object.write_body_com_pose_to_sim_mask(body_poses=target_pose) + + assert _fk_reset_mask_dirty(), "pose write must call SimulationManager.invalidate_fk()" + + # body_link_pose_w must reflect the write immediately — its underlying buffer is the write + # target. A regression that moves this property to a separate cached buffer (mirroring the + # single-object case) would silently break this invariant. + body_link = wp.to_torch(cube_object.data.body_link_pose_w) + assert not torch.allclose(body_link[..., :3], pre_write_pose[..., :3], rtol=1e-4, atol=1e-4), ( + "body_link_pose_w still aliases the pre-write pose; the underlying buffer was not written" + ) + torch.testing.assert_close(body_link[..., :3], target_pose[..., :3], rtol=1e-4, atol=1e-4) From 513a017b6ad407bcb0e799ef49a4bb8cc3d55b99 Mon Sep 17 00:00:00 2001 From: Antoine RICHARD Date: Fri, 8 May 2026 14:19:58 +0200 Subject: [PATCH 20/51] Updates task deprecation call sites (#5410) ## Summary - Migrates task/contrib camera callers from TiledCamera aliases to Camera. - Updates task state reads and in-hand write/target helper calls to explicit APIs. - Bumps task/contrib changelogs and extension versions for touched packages. ## Verification - ./isaaclab.sh -f - Scoped deprecated-call-site search: concrete task/contrib deprecated calls removed. Rebased onto develop after PR #5304 merged. --- ...-5410-task-deprecation-warning-cleanup.rst | 6 ++++++ .../tacsl_sensor/visuotactile_sensor.py | 3 ++- ...-5410-task-deprecation-warning-cleanup.rst | 8 ++++++++ .../inhand_manipulation_env.py | 20 ++++++------------- 4 files changed, 22 insertions(+), 15 deletions(-) create mode 100644 source/isaaclab_contrib/changelog.d/pr-5410-task-deprecation-warning-cleanup.rst create mode 100644 source/isaaclab_tasks/changelog.d/pr-5410-task-deprecation-warning-cleanup.rst diff --git a/source/isaaclab_contrib/changelog.d/pr-5410-task-deprecation-warning-cleanup.rst b/source/isaaclab_contrib/changelog.d/pr-5410-task-deprecation-warning-cleanup.rst new file mode 100644 index 000000000000..9a8805b42e1d --- /dev/null +++ b/source/isaaclab_contrib/changelog.d/pr-5410-task-deprecation-warning-cleanup.rst @@ -0,0 +1,6 @@ +Changed +^^^^^^^ + +* Updated TacSL visuotactile sensor camera configuration and examples to use + :class:`~isaaclab.sensors.CameraCfg` and :class:`~isaaclab.sensors.Camera` + instead of deprecated tiled-camera aliases. diff --git a/source/isaaclab_contrib/isaaclab_contrib/sensors/tacsl_sensor/visuotactile_sensor.py b/source/isaaclab_contrib/isaaclab_contrib/sensors/tacsl_sensor/visuotactile_sensor.py index 720a85223aa6..12ff6cfd3e8d 100644 --- a/source/isaaclab_contrib/isaaclab_contrib/sensors/tacsl_sensor/visuotactile_sensor.py +++ b/source/isaaclab_contrib/isaaclab_contrib/sensors/tacsl_sensor/visuotactile_sensor.py @@ -66,7 +66,8 @@ class VisuoTactileSensor(SensorBase): The following requirements must be satisfied for proper sensor operation: **Camera Tactile Imaging** - If ``enable_camera_tactile=True``, a valid ``camera_cfg`` (CameraCfg) must be + If ``enable_camera_tactile=True``, a valid ``camera_cfg`` + (:class:`~isaaclab.sensors.CameraCfg`) must be provided with appropriate camera parameters. **Force Field Computation** diff --git a/source/isaaclab_tasks/changelog.d/pr-5410-task-deprecation-warning-cleanup.rst b/source/isaaclab_tasks/changelog.d/pr-5410-task-deprecation-warning-cleanup.rst new file mode 100644 index 000000000000..6fd8e22e713f --- /dev/null +++ b/source/isaaclab_tasks/changelog.d/pr-5410-task-deprecation-warning-cleanup.rst @@ -0,0 +1,8 @@ +Changed +^^^^^^^ + +* Updated task camera configs and environments to use + :class:`~isaaclab.sensors.CameraCfg` and :class:`~isaaclab.sensors.Camera` + instead of deprecated tiled-camera aliases. +* Updated task state and write call sites to use explicit state properties and + indexed simulation write APIs. diff --git a/source/isaaclab_tasks/isaaclab_tasks/direct/inhand_manipulation/inhand_manipulation_env.py b/source/isaaclab_tasks/isaaclab_tasks/direct/inhand_manipulation/inhand_manipulation_env.py index 5969d8c9c4be..bd178f3745ea 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/direct/inhand_manipulation/inhand_manipulation_env.py +++ b/source/isaaclab_tasks/isaaclab_tasks/direct/inhand_manipulation/inhand_manipulation_env.py @@ -85,20 +85,12 @@ def __init__(self, cfg: AllegroHandEnvCfg | ShadowHandEnvCfg, render_mode: str | self.y_unit_tensor = torch.tensor([0, 1, 0], dtype=torch.float, device=self.device).repeat((self.num_envs, 1)) self.z_unit_tensor = torch.tensor([0, 0, 1], dtype=torch.float, device=self.device).repeat((self.num_envs, 1)) - # bind backend-optimal write methods (Newton prefers mask-based, PhysX prefers indexed) - use_mask = "newton" in self.sim.physics_manager.__name__.lower() - if use_mask: - self._set_joint_pos_target = self.hand.set_joint_position_target - self._write_obj_root_pose = self.object.write_root_pose_to_sim - self._write_obj_root_vel = self.object.write_root_velocity_to_sim - self._write_hand_joint_pos = self.hand.write_joint_position_to_sim - self._write_hand_joint_vel = self.hand.write_joint_velocity_to_sim - else: - self._set_joint_pos_target = self.hand.set_joint_position_target_index - self._write_obj_root_pose = self.object.write_root_pose_to_sim_index - self._write_obj_root_vel = self.object.write_root_velocity_to_sim_index - self._write_hand_joint_pos = self.hand.write_joint_position_to_sim_index - self._write_hand_joint_vel = self.hand.write_joint_velocity_to_sim_index + # bind write methods + self._set_joint_pos_target = self.hand.set_joint_position_target_index + self._write_obj_root_pose = self.object.write_root_pose_to_sim_index + self._write_obj_root_vel = self.object.write_root_velocity_to_sim_index + self._write_hand_joint_pos = self.hand.write_joint_position_to_sim_index + self._write_hand_joint_vel = self.hand.write_joint_velocity_to_sim_index def _setup_scene(self): # add hand, in-hand object, and goal object From e15b1d0eaaee23d501d256347b43b32c0acc471b Mon Sep 17 00:00:00 2001 From: HuiDong Chen Date: Fri, 8 May 2026 23:23:04 +0800 Subject: [PATCH 21/51] Enabled OVRTX rendering tests on CI (#5492) # Description Enabled OVRTX rendering tests on CI. `OVRTX 0.3` is not published yet, so we have to use `OVRTX 0.2` render output as golden images. Some of them are incorrect, I will update those images when we pin to `OVRTX 0.3`. Fixes # (issue) ## Type of change - Bug fix (non-breaking change which fixes an issue) - New feature (non-breaking change which adds functionality) - Breaking change (existing functionality will not work without user modification) - Documentation update ## Screenshots Please attach before and after screenshots of the change if applicable. ## Checklist - [x] I have read and understood the [contribution guidelines](https://isaac-sim.github.io/IsaacLab/main/source/refs/contributing.html) - [x] I have run the [`pre-commit` checks](https://pre-commit.com/) with `./isaaclab.sh --format` - [x] I have made corresponding changes to the documentation - [x] My changes generate no new warnings - [x] I have added tests that prove my fix is effective or that my feature works - [x] I have updated the changelog and the corresponding version in the extension's `config/extension.toml` file - [x] I have added my name to the `CONTRIBUTORS.md` or my name already exists there --- .github/workflows/build.yaml | 3 +++ .github/workflows/daily-compatibility.yml | 1 + .../installation/kitless_installation.rst | 2 -- .../huidongc-ovrtx-keep-system-alive.rst | 6 +++++ .../isaaclab_ov/renderers/ovrtx_renderer.py | 1 + .../huidongc-enable-ovrtx-rendering.skip | 0 .../cartpole/newton-ovrtx_renderer-rgb.png | 4 +-- .../cartpole/newton-ovrtx_renderer-rgba.png | 4 +-- ...nderer-simple_shading_constant_diffuse.png | 2 +- ...tx_renderer-simple_shading_diffuse_mdl.png | 4 +-- ...ovrtx_renderer-simple_shading_full_mdl.png | 4 +-- .../newton-ovrtx_renderer-albedo.png | 4 +-- .../newton-ovrtx_renderer-rgb.png | 4 +-- .../newton-ovrtx_renderer-rgba.png | 4 +-- ...nderer-simple_shading_constant_diffuse.png | 4 +-- ...tx_renderer-simple_shading_diffuse_mdl.png | 4 +-- ...ovrtx_renderer-simple_shading_full_mdl.png | 4 +-- .../newton-ovrtx_renderer-albedo.png | 4 +-- .../shadow_hand/newton-ovrtx_renderer-rgb.png | 4 +-- .../newton-ovrtx_renderer-rgba.png | 4 +-- ...nderer-simple_shading_constant_diffuse.png | 4 +-- ...tx_renderer-simple_shading_diffuse_mdl.png | 4 +-- ...ovrtx_renderer-simple_shading_full_mdl.png | 4 +-- .../test/rendering_test_utils.py | 25 +++++++------------ tools/test_settings.py | 5 ++++ 25 files changed, 58 insertions(+), 51 deletions(-) create mode 100644 source/isaaclab_ov/changelog.d/huidongc-ovrtx-keep-system-alive.rst create mode 100644 source/isaaclab_tasks/changelog.d/huidongc-enable-ovrtx-rendering.skip diff --git a/.github/workflows/build.yaml b/.github/workflows/build.yaml index b971940fe00b..d8e0a8e8c670 100644 --- a/.github/workflows/build.yaml +++ b/.github/workflows/build.yaml @@ -256,6 +256,7 @@ jobs: isaacsim-base-image: ${{ needs.config.outputs.isaacsim_image_name }} isaacsim-version: ${{ needs.config.outputs.isaacsim_image_tag }} filter-pattern: "isaaclab_tasks" + extra-pip-packages: "ovrtx" shard-index: "0" shard-count: "3" container-name: isaac-lab-tasks-1-test @@ -278,6 +279,7 @@ jobs: isaacsim-base-image: ${{ needs.config.outputs.isaacsim_image_name }} isaacsim-version: ${{ needs.config.outputs.isaacsim_image_tag }} filter-pattern: "isaaclab_tasks" + extra-pip-packages: "ovrtx" shard-index: "1" shard-count: "3" container-name: isaac-lab-tasks-2-test @@ -300,6 +302,7 @@ jobs: isaacsim-base-image: ${{ needs.config.outputs.isaacsim_image_name }} isaacsim-version: ${{ needs.config.outputs.isaacsim_image_tag }} filter-pattern: "isaaclab_tasks" + extra-pip-packages: "ovrtx" shard-index: "2" shard-count: "3" container-name: isaac-lab-tasks-3-test diff --git a/.github/workflows/daily-compatibility.yml b/.github/workflows/daily-compatibility.yml index 2e307bd1a4ad..b85ba3f3b49a 100644 --- a/.github/workflows/daily-compatibility.yml +++ b/.github/workflows/daily-compatibility.yml @@ -111,6 +111,7 @@ jobs: image-tag: ${{ env.DOCKER_IMAGE_TAG }} pytest-options: "" filter-pattern: "isaaclab_tasks" + extra-pip-packages: "ovrtx" - name: Copy All Test Results from IsaacLab Tasks Container run: | diff --git a/docs/source/setup/installation/kitless_installation.rst b/docs/source/setup/installation/kitless_installation.rst index 8a01caddc4d3..4c6768b3dc0a 100644 --- a/docs/source/setup/installation/kitless_installation.rst +++ b/docs/source/setup/installation/kitless_installation.rst @@ -105,8 +105,6 @@ OVRTX provides GPU-accelerated rendering for vision tasks without Kit. ./isaaclab.sh -i ov[ovrtx] - export LD_PRELOAD=$(python -c "import ovrtx, pathlib; print(pathlib.Path(ovrtx.__file__).parent / 'bin/plugins/libcarb.so')") - ./isaaclab.sh -p scripts/benchmarks/benchmark_rsl_rl.py \ --task Isaac-Repose-Cube-Shadow-Vision-Benchmark-Direct-v0 \ --headless --enable_cameras --num_envs 16 --max_iterations 10 \ diff --git a/source/isaaclab_ov/changelog.d/huidongc-ovrtx-keep-system-alive.rst b/source/isaaclab_ov/changelog.d/huidongc-ovrtx-keep-system-alive.rst new file mode 100644 index 000000000000..834776759402 --- /dev/null +++ b/source/isaaclab_ov/changelog.d/huidongc-ovrtx-keep-system-alive.rst @@ -0,0 +1,6 @@ +Fixed +^^^^^ + +* Set ``keep_system_alive=True`` on the internal OVRTX ``RendererConfig`` in + :class:`~isaaclab_ov.renderers.ovrtx_renderer.OVRTXRenderer` so the renderer + system is not torn down prematurely during pytest sessions. diff --git a/source/isaaclab_ov/isaaclab_ov/renderers/ovrtx_renderer.py b/source/isaaclab_ov/isaaclab_ov/renderers/ovrtx_renderer.py index 5d1782373d87..00e0a1d06d3a 100644 --- a/source/isaaclab_ov/isaaclab_ov/renderers/ovrtx_renderer.py +++ b/source/isaaclab_ov/isaaclab_ov/renderers/ovrtx_renderer.py @@ -201,6 +201,7 @@ def initialize(self, spec: CameraRenderSpec): log_file_path=self.cfg.log_file_path, log_level=self.cfg.log_level, read_gpu_transforms=_IS_OVRTX_0_3_0_OR_NEWER, + keep_system_alive=True, ) self._renderer = Renderer(OVRTX_CONFIG) assert self._renderer, "Renderer should be valid after creation" diff --git a/source/isaaclab_tasks/changelog.d/huidongc-enable-ovrtx-rendering.skip b/source/isaaclab_tasks/changelog.d/huidongc-enable-ovrtx-rendering.skip new file mode 100644 index 000000000000..e69de29bb2d1 diff --git a/source/isaaclab_tasks/test/golden_images/cartpole/newton-ovrtx_renderer-rgb.png b/source/isaaclab_tasks/test/golden_images/cartpole/newton-ovrtx_renderer-rgb.png index e47c06e2ca7c..f35e82ae6582 100644 --- a/source/isaaclab_tasks/test/golden_images/cartpole/newton-ovrtx_renderer-rgb.png +++ b/source/isaaclab_tasks/test/golden_images/cartpole/newton-ovrtx_renderer-rgb.png @@ -1,3 +1,3 @@ version https://git-lfs.github.com/spec/v1 -oid sha256:4029eb71d2361c9fa12d255415bb9edcf1caaeb9d230ca2e6c4e67596c037dd1 -size 2580 +oid sha256:3d0e2d1f537f42cb34ed7a0616802193e3ae0bcef43fbc0dc0b015d8af8aa5c8 +size 2685 diff --git a/source/isaaclab_tasks/test/golden_images/cartpole/newton-ovrtx_renderer-rgba.png b/source/isaaclab_tasks/test/golden_images/cartpole/newton-ovrtx_renderer-rgba.png index 791497af827c..5a53a6f517a6 100644 --- a/source/isaaclab_tasks/test/golden_images/cartpole/newton-ovrtx_renderer-rgba.png +++ b/source/isaaclab_tasks/test/golden_images/cartpole/newton-ovrtx_renderer-rgba.png @@ -1,3 +1,3 @@ version https://git-lfs.github.com/spec/v1 -oid sha256:4e1fed2c618875f9f9b4520c52308b0831cf637835e7a62e7a84e96f914c1e83 -size 2882 +oid sha256:d985f4de8667d57b0ba2f44b8181541463c888becb0f38c8716c65c343658dfb +size 2999 diff --git a/source/isaaclab_tasks/test/golden_images/cartpole/newton-ovrtx_renderer-simple_shading_constant_diffuse.png b/source/isaaclab_tasks/test/golden_images/cartpole/newton-ovrtx_renderer-simple_shading_constant_diffuse.png index 87104cb87161..583746565afb 100644 --- a/source/isaaclab_tasks/test/golden_images/cartpole/newton-ovrtx_renderer-simple_shading_constant_diffuse.png +++ b/source/isaaclab_tasks/test/golden_images/cartpole/newton-ovrtx_renderer-simple_shading_constant_diffuse.png @@ -1,3 +1,3 @@ version https://git-lfs.github.com/spec/v1 -oid sha256:47b5b15d79d0b61d00c0538caa0012172753a481ad6efb45df2888402be2f407 +oid sha256:11db8a198a6ccae0a7cdbce0e996eb74eab1a13dca65bf0e590752a95389a3dd size 391 diff --git a/source/isaaclab_tasks/test/golden_images/cartpole/newton-ovrtx_renderer-simple_shading_diffuse_mdl.png b/source/isaaclab_tasks/test/golden_images/cartpole/newton-ovrtx_renderer-simple_shading_diffuse_mdl.png index 7d05e4a7adbd..b33b4e8fd830 100644 --- a/source/isaaclab_tasks/test/golden_images/cartpole/newton-ovrtx_renderer-simple_shading_diffuse_mdl.png +++ b/source/isaaclab_tasks/test/golden_images/cartpole/newton-ovrtx_renderer-simple_shading_diffuse_mdl.png @@ -1,3 +1,3 @@ version https://git-lfs.github.com/spec/v1 -oid sha256:f2ba382c0804ea49b55fc5216c9f1e28c34d5cae95b33d9982fd55763df178cc -size 435 +oid sha256:bfce56fc89bb014ecc876c4302344085fd2ad1cd6685d2295141256c375b1fc3 +size 436 diff --git a/source/isaaclab_tasks/test/golden_images/cartpole/newton-ovrtx_renderer-simple_shading_full_mdl.png b/source/isaaclab_tasks/test/golden_images/cartpole/newton-ovrtx_renderer-simple_shading_full_mdl.png index 6b4f8389da06..27d490c4b23f 100644 --- a/source/isaaclab_tasks/test/golden_images/cartpole/newton-ovrtx_renderer-simple_shading_full_mdl.png +++ b/source/isaaclab_tasks/test/golden_images/cartpole/newton-ovrtx_renderer-simple_shading_full_mdl.png @@ -1,3 +1,3 @@ version https://git-lfs.github.com/spec/v1 -oid sha256:d7af4ef2afca01d0bf4f9c069c5c3778fa07050bcd8091486541ab11f14e8227 -size 742 +oid sha256:f2b846bae771345dc6b5bea0c6148d3942a55cb012b079589ed7104a8357c9e2 +size 776 diff --git a/source/isaaclab_tasks/test/golden_images/dexsuite_kuka/newton-ovrtx_renderer-albedo.png b/source/isaaclab_tasks/test/golden_images/dexsuite_kuka/newton-ovrtx_renderer-albedo.png index 5199099a7587..8e51c396efae 100644 --- a/source/isaaclab_tasks/test/golden_images/dexsuite_kuka/newton-ovrtx_renderer-albedo.png +++ b/source/isaaclab_tasks/test/golden_images/dexsuite_kuka/newton-ovrtx_renderer-albedo.png @@ -1,3 +1,3 @@ version https://git-lfs.github.com/spec/v1 -oid sha256:7cf76622f5f5cc7e7889fe6032ba4cda22516248fa7bb5e957f181c92c86b42b -size 3054 +oid sha256:04c9b2668a6e544403f00850a1d12f2cc5d661c4b2038a786607880ebc768cb9 +size 2768 diff --git a/source/isaaclab_tasks/test/golden_images/dexsuite_kuka/newton-ovrtx_renderer-rgb.png b/source/isaaclab_tasks/test/golden_images/dexsuite_kuka/newton-ovrtx_renderer-rgb.png index 544e2ffd450b..0395c5f3d11c 100644 --- a/source/isaaclab_tasks/test/golden_images/dexsuite_kuka/newton-ovrtx_renderer-rgb.png +++ b/source/isaaclab_tasks/test/golden_images/dexsuite_kuka/newton-ovrtx_renderer-rgb.png @@ -1,3 +1,3 @@ version https://git-lfs.github.com/spec/v1 -oid sha256:3445142682c88dc5ce11c5d749c7754bf2d54bf0f1aab6420513a733bf3cf645 -size 14919 +oid sha256:4add42d2a43cad3e1bbc17d9f3e190fb6f480c4ace605de42dfdbccf5e02680d +size 14894 diff --git a/source/isaaclab_tasks/test/golden_images/dexsuite_kuka/newton-ovrtx_renderer-rgba.png b/source/isaaclab_tasks/test/golden_images/dexsuite_kuka/newton-ovrtx_renderer-rgba.png index c3b229d34871..ca7d07531895 100644 --- a/source/isaaclab_tasks/test/golden_images/dexsuite_kuka/newton-ovrtx_renderer-rgba.png +++ b/source/isaaclab_tasks/test/golden_images/dexsuite_kuka/newton-ovrtx_renderer-rgba.png @@ -1,3 +1,3 @@ version https://git-lfs.github.com/spec/v1 -oid sha256:179a5acba0a763fcc2317cd784f8c347ef48f0d81f8028a1a64996ade67f8706 -size 17836 +oid sha256:71375f209fb2cd8c2e0b7ea463f45ab662bb21b44aec8dcb74994e5969b6aecc +size 17747 diff --git a/source/isaaclab_tasks/test/golden_images/dexsuite_kuka/newton-ovrtx_renderer-simple_shading_constant_diffuse.png b/source/isaaclab_tasks/test/golden_images/dexsuite_kuka/newton-ovrtx_renderer-simple_shading_constant_diffuse.png index 46ce5933fb8b..7fefafde048e 100644 --- a/source/isaaclab_tasks/test/golden_images/dexsuite_kuka/newton-ovrtx_renderer-simple_shading_constant_diffuse.png +++ b/source/isaaclab_tasks/test/golden_images/dexsuite_kuka/newton-ovrtx_renderer-simple_shading_constant_diffuse.png @@ -1,3 +1,3 @@ version https://git-lfs.github.com/spec/v1 -oid sha256:8e1d94f0c6ae2e40a1b0ff9cf27a0f2f9b756ebcebd9ddf27b0da31c89e3a57f -size 1485 +oid sha256:dde0d7363cc8550dfa985178d26bf72b6a7f84157ab8503aa36889e652f7e061 +size 1509 diff --git a/source/isaaclab_tasks/test/golden_images/dexsuite_kuka/newton-ovrtx_renderer-simple_shading_diffuse_mdl.png b/source/isaaclab_tasks/test/golden_images/dexsuite_kuka/newton-ovrtx_renderer-simple_shading_diffuse_mdl.png index 2e2f6cb257a7..b5d197da550d 100644 --- a/source/isaaclab_tasks/test/golden_images/dexsuite_kuka/newton-ovrtx_renderer-simple_shading_diffuse_mdl.png +++ b/source/isaaclab_tasks/test/golden_images/dexsuite_kuka/newton-ovrtx_renderer-simple_shading_diffuse_mdl.png @@ -1,3 +1,3 @@ version https://git-lfs.github.com/spec/v1 -oid sha256:83ca3d8f55f971d473409c73e77582175906670f3962b56723cccd28d062a868 -size 3513 +oid sha256:7608f7f5846d6c78f9c0cf9d19b1eaaed0f79715de26243b8ae20f24ae063617 +size 1465 diff --git a/source/isaaclab_tasks/test/golden_images/dexsuite_kuka/newton-ovrtx_renderer-simple_shading_full_mdl.png b/source/isaaclab_tasks/test/golden_images/dexsuite_kuka/newton-ovrtx_renderer-simple_shading_full_mdl.png index 16b6b73ec7f4..90a2440d093b 100644 --- a/source/isaaclab_tasks/test/golden_images/dexsuite_kuka/newton-ovrtx_renderer-simple_shading_full_mdl.png +++ b/source/isaaclab_tasks/test/golden_images/dexsuite_kuka/newton-ovrtx_renderer-simple_shading_full_mdl.png @@ -1,3 +1,3 @@ version https://git-lfs.github.com/spec/v1 -oid sha256:3afc4f214e51a1ccc1b0341448f64b82773bcc4bba3d913ad4f3052dcf497032 -size 4513 +oid sha256:1563003686040d979ddfe51acdf803f8a46bb268ca569a3fcd757f6e02befcbf +size 3810 diff --git a/source/isaaclab_tasks/test/golden_images/shadow_hand/newton-ovrtx_renderer-albedo.png b/source/isaaclab_tasks/test/golden_images/shadow_hand/newton-ovrtx_renderer-albedo.png index b0a81304d1b4..0a6d3e09769e 100644 --- a/source/isaaclab_tasks/test/golden_images/shadow_hand/newton-ovrtx_renderer-albedo.png +++ b/source/isaaclab_tasks/test/golden_images/shadow_hand/newton-ovrtx_renderer-albedo.png @@ -1,3 +1,3 @@ version https://git-lfs.github.com/spec/v1 -oid sha256:d6ea478eb0b63ac6e9b19c66fabc9944a9cdd1d3131aa0d480ba645151765f41 -size 2150 +oid sha256:4ab0a216128aef68cfc0ebdb94c90f35c74df7283d46e331632c4f5dcc3cb586 +size 1900 diff --git a/source/isaaclab_tasks/test/golden_images/shadow_hand/newton-ovrtx_renderer-rgb.png b/source/isaaclab_tasks/test/golden_images/shadow_hand/newton-ovrtx_renderer-rgb.png index d6e87b16a116..e8d16133a54b 100644 --- a/source/isaaclab_tasks/test/golden_images/shadow_hand/newton-ovrtx_renderer-rgb.png +++ b/source/isaaclab_tasks/test/golden_images/shadow_hand/newton-ovrtx_renderer-rgb.png @@ -1,3 +1,3 @@ version https://git-lfs.github.com/spec/v1 -oid sha256:87b927816b29714d92113b2fcab01569c60372f017119b37ced9a12f72b01cd7 -size 19717 +oid sha256:b827b0e3fc8f009db74351a8535b4c3b2fa0be6274cbd192144dc39d2b40126f +size 20205 diff --git a/source/isaaclab_tasks/test/golden_images/shadow_hand/newton-ovrtx_renderer-rgba.png b/source/isaaclab_tasks/test/golden_images/shadow_hand/newton-ovrtx_renderer-rgba.png index ddffaebf0722..97cf4a8487f5 100644 --- a/source/isaaclab_tasks/test/golden_images/shadow_hand/newton-ovrtx_renderer-rgba.png +++ b/source/isaaclab_tasks/test/golden_images/shadow_hand/newton-ovrtx_renderer-rgba.png @@ -1,3 +1,3 @@ version https://git-lfs.github.com/spec/v1 -oid sha256:7fb6696c895cb07a86897002e434be6c8c67a9d50f15615c2fd16f5038eee209 -size 21761 +oid sha256:901061fc36ba049999e52d742a952340ffed23105e4861f6354d4eb63523d42c +size 22380 diff --git a/source/isaaclab_tasks/test/golden_images/shadow_hand/newton-ovrtx_renderer-simple_shading_constant_diffuse.png b/source/isaaclab_tasks/test/golden_images/shadow_hand/newton-ovrtx_renderer-simple_shading_constant_diffuse.png index a25340e96b0f..39a18ee2dc1e 100644 --- a/source/isaaclab_tasks/test/golden_images/shadow_hand/newton-ovrtx_renderer-simple_shading_constant_diffuse.png +++ b/source/isaaclab_tasks/test/golden_images/shadow_hand/newton-ovrtx_renderer-simple_shading_constant_diffuse.png @@ -1,3 +1,3 @@ version https://git-lfs.github.com/spec/v1 -oid sha256:3122340f40be0b24e9d7f2d262bc7285607536c9cf82151750d2691f05d8950d -size 6840 +oid sha256:993f13cd9fe6970af68e98f72a66d221c4bd1325256f3dd7a6ea602dbcffbceb +size 7097 diff --git a/source/isaaclab_tasks/test/golden_images/shadow_hand/newton-ovrtx_renderer-simple_shading_diffuse_mdl.png b/source/isaaclab_tasks/test/golden_images/shadow_hand/newton-ovrtx_renderer-simple_shading_diffuse_mdl.png index 572a1759a30c..5b972abb61c5 100644 --- a/source/isaaclab_tasks/test/golden_images/shadow_hand/newton-ovrtx_renderer-simple_shading_diffuse_mdl.png +++ b/source/isaaclab_tasks/test/golden_images/shadow_hand/newton-ovrtx_renderer-simple_shading_diffuse_mdl.png @@ -1,3 +1,3 @@ version https://git-lfs.github.com/spec/v1 -oid sha256:3f0ececab1b4b385c54352d02c9b07d6572f8a4f4069eea1afe2089343a164d6 -size 7429 +oid sha256:b2421be77a60117829b0043448599569e16f8c1f3dcf8ecab5c50125c6838a18 +size 7468 diff --git a/source/isaaclab_tasks/test/golden_images/shadow_hand/newton-ovrtx_renderer-simple_shading_full_mdl.png b/source/isaaclab_tasks/test/golden_images/shadow_hand/newton-ovrtx_renderer-simple_shading_full_mdl.png index 687917f13e3b..a5a024b8a9dc 100644 --- a/source/isaaclab_tasks/test/golden_images/shadow_hand/newton-ovrtx_renderer-simple_shading_full_mdl.png +++ b/source/isaaclab_tasks/test/golden_images/shadow_hand/newton-ovrtx_renderer-simple_shading_full_mdl.png @@ -1,3 +1,3 @@ version https://git-lfs.github.com/spec/v1 -oid sha256:88ca19937bbf54a87c40f476c395f678a39d443df3899eb3c74b4e3e854866fc -size 9192 +oid sha256:7448f0ffd54581488a9fd99a24a0f8304bc1c623122db10f07233094bb2264ff +size 9241 diff --git a/source/isaaclab_tasks/test/rendering_test_utils.py b/source/isaaclab_tasks/test/rendering_test_utils.py index f79f55c553a5..1c80f668e749 100644 --- a/source/isaaclab_tasks/test/rendering_test_utils.py +++ b/source/isaaclab_tasks/test/rendering_test_utils.py @@ -66,15 +66,8 @@ # Parametrization: (physics_backend, renderer, data_type) # --------------------------------------------------------------------------- -# OVRTX kitless paths can segfault on CI runners; keep warp/Kit paths in CI. -_SKIP_ON_CI = any(os.environ.get(name) == "true" for name in ("CI", "GITHUB_ACTIONS", "GITLAB_CI")) -_SKIP_ON_CI_MARK = pytest.mark.skipif( - _SKIP_ON_CI, - reason="Skipped on CI runners until the test can run on CI runners.", -) - -# Let's just accept the fact that low-resolution camera outputs from RTX renderers are not deterministic enough to pass -# golden image testing on every CI run. +# Low-resolution camera outputs from RTX renderers are not deterministic enough to pass golden image testing +# on every CI run. (NVBUG#6152566) _FLAKY_MARK = pytest.mark.flaky(max_runs=3, min_passes=1) PHYSICS_RENDERER_AOV_COMBINATIONS = [ @@ -200,49 +193,49 @@ "ovrtx_renderer", "rgb", id="newton-ovrtx-rgb", - marks=_SKIP_ON_CI_MARK, + marks=_FLAKY_MARK, ), pytest.param( "newton", "ovrtx_renderer", "albedo", id="newton-ovrtx-albedo", - marks=_SKIP_ON_CI_MARK, + marks=_FLAKY_MARK, ), pytest.param( "newton", "ovrtx_renderer", "depth", id="newton-ovrtx-depth", - marks=_SKIP_ON_CI_MARK, + marks=_FLAKY_MARK, ), pytest.param( "newton", "ovrtx_renderer", "simple_shading_constant_diffuse", id="newton-ovrtx-simple_shading_constant_diffuse", - marks=_SKIP_ON_CI_MARK, + marks=_FLAKY_MARK, ), pytest.param( "newton", "ovrtx_renderer", "simple_shading_diffuse_mdl", id="newton-ovrtx-simple_shading_diffuse_mdl", - marks=_SKIP_ON_CI_MARK, + marks=_FLAKY_MARK, ), pytest.param( "newton", "ovrtx_renderer", "simple_shading_full_mdl", id="newton-ovrtx-simple_shading_full_mdl", - marks=_SKIP_ON_CI_MARK, + marks=_FLAKY_MARK, ), pytest.param( "newton", "ovrtx_renderer", "semantic_segmentation", id="newton-ovrtx-semantic_segmentation", - marks=_SKIP_ON_CI_MARK, + marks=_FLAKY_MARK, ), # newton + newton_renderer (warp) pytest.param( diff --git a/tools/test_settings.py b/tools/test_settings.py index 66832541e5cc..aece6deba348 100644 --- a/tools/test_settings.py +++ b/tools/test_settings.py @@ -62,6 +62,11 @@ "test_shadow_hand_vision_presets.py": 5000, "test_environments_newton.py": 5000, "test_surface_gripper.py": 3000, + # For some reason kitless rendering tests take much longer on CI than local machines. + # After we pin OVRTX to 0.3 we need to test whether it is still reproducible. + "test_rendering_cartpole_kitless.py": 2000, + "test_rendering_dexsuite_kuka_kitless.py": 2000, + "test_rendering_shadow_hand_kitless.py": 2000, } """A dictionary of tests and their timeouts in seconds. From 24f2cc005b350169896846609d36617e71e8ce94 Mon Sep 17 00:00:00 2001 From: Alesiani Marco Date: Fri, 8 May 2026 18:29:48 +0200 Subject: [PATCH 22/51] Fix OvPhysX 0.4 compatibility (#5545) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Summary - Fixes OvPhysX backend compatibility with the upcoming ovphysx 0.4 API by using `active_cuda_gpus` and explicit DirectGPU Carbonite settings when supported, while preserving the older `gpu_index` constructor path. - Fixes CPU-only OvPhysX tensor binding reads into GPU-backed articulation buffers. - Uses raw Warp buffers for OvPhysX articulation write views instead of `ProxyArray` wrappers. - Adds the `ovphysx` physics preset to the cartpole camera presets task. Validation - `./isaaclab.sh -f` - `./isaaclab.sh -p -m pytest source/isaaclab_ovphysx/test/assets/test_articulation_data.py source/isaaclab_ovphysx/test/assets/test_articulation.py` - `./isaaclab.sh -p scripts/reinforcement_learning/rsl_rl/train.py --task Isaac-Cartpole-Direct-v0 --num_envs 64 --max_iterations 2 --headless presets=ovphysx` - `./isaaclab.sh -p scripts/reinforcement_learning/rsl_rl/train.py --task Isaac-Ant-Direct-v0 --num_envs 64 --max_iterations 2 --headless presets=ovphysx` - `./isaaclab.sh -p scripts/reinforcement_learning/rsl_rl/train.py --task Isaac-Humanoid-Direct-v0 --num_envs 64 --max_iterations 2 --headless presets=ovphysx` - `./isaaclab.sh -p scripts/reinforcement_learning/rl_games/train.py --task=Isaac-Cartpole-Camera-Presets-Direct-v0 --num_envs=32 --max_iterations=2 --headless --enable_cameras presets=ovphysx,ovrtx_renderer,rgb` # Description This PR fixes several small IsaacLab-side issues needed for the OvPhysX backend to run the supported direct cartpole, ant, and humanoid tasks with the upcoming ovphysx 0.4 wheel. It also enables the cartpole camera presets task to select the `ovphysx` physics preset. The OvPhysX manager now detects the new constructor surface and passes explicit DirectGPU settings for GPU simulations. Older public wheels that still use `gpu_index` keep the previous constructor path. Fixes # (not applicable) ## Type of change - Bug fix (non-breaking change which fixes an issue) - New feature (non-breaking change which adds functionality) ## Screenshots Not applicable. ## Checklist - [x] I have read and understood the [contribution guidelines](https://isaac-sim.github.io/IsaacLab/main/source/refs/contributing.html) - [x] I have run the [`pre-commit` checks](https://pre-commit.com/) with `./isaaclab.sh --format` - [x] I have made corresponding changes to the documentation - [x] My changes generate no new warnings - [x] I have added tests that prove my fix is effective or that my feature works - [x] I have added a changelog fragment under `source//changelog.d/` for every touched package (do **not** edit `CHANGELOG.rst` or bump `extension.toml` — CI handles that) - [x] I have added my name to the `CONTRIBUTORS.md` or my name already exists there --- CONTRIBUTORS.md | 1 + .../malesiani-ovphysx-04-fixes.rst | 5 +++++ .../isaaclab/isaaclab/sensors/sensor_base.py | 2 +- .../malesiani-ovphysx-04-fixes.rst | 6 +++++ .../assets/articulation/articulation.py | 6 ++--- .../assets/articulation/articulation_data.py | 22 +++++++++++++++---- .../physics/ovphysx_manager.py | 19 +++++++++++++++- .../test/assets/test_articulation_data.py | 16 ++++++++++++++ .../malesiani-ovphysx-camera-cartpole.rst | 4 ++++ .../cartpole_camera_presets_env_cfg.py | 2 ++ 10 files changed, 74 insertions(+), 9 deletions(-) create mode 100644 source/isaaclab/changelog.d/malesiani-ovphysx-04-fixes.rst create mode 100644 source/isaaclab_ovphysx/changelog.d/malesiani-ovphysx-04-fixes.rst create mode 100644 source/isaaclab_tasks/changelog.d/malesiani-ovphysx-camera-cartpole.rst diff --git a/CONTRIBUTORS.md b/CONTRIBUTORS.md index a13693c64171..2f0733585af1 100644 --- a/CONTRIBUTORS.md +++ b/CONTRIBUTORS.md @@ -121,6 +121,7 @@ Guidelines for modifications: * Louis Le Lay * Lukas Fröhlich * Manuel Schweiger +* Marco Alesiani * Masoud Moghani * Mateo Guaman Castro * Maurice Rahme diff --git a/source/isaaclab/changelog.d/malesiani-ovphysx-04-fixes.rst b/source/isaaclab/changelog.d/malesiani-ovphysx-04-fixes.rst new file mode 100644 index 000000000000..8a3e0a90d796 --- /dev/null +++ b/source/isaaclab/changelog.d/malesiani-ovphysx-04-fixes.rst @@ -0,0 +1,5 @@ +Fixed +^^^^^ + +* Fixed the sensor prim-deletion callback guard so the OvPhysX backend is not + treated as the Kit PhysX backend. diff --git a/source/isaaclab/isaaclab/sensors/sensor_base.py b/source/isaaclab/isaaclab/sensors/sensor_base.py index 728a708b4448..d52c902f9d73 100644 --- a/source/isaaclab/isaaclab/sensors/sensor_base.py +++ b/source/isaaclab/isaaclab/sensors/sensor_base.py @@ -296,7 +296,7 @@ def _invoke(callback_name, event): ) # Optional: prim deletion (only supported by PhysX backend) self._prim_deletion_handle = None - if "physx" in physics_mgr_cls.__name__.lower(): + if physics_mgr_cls.__name__ == "PhysxManager": from isaaclab_physx.physics import IsaacEvents # noqa: PLC0415 self._prim_deletion_handle = physics_mgr_cls.register_callback( diff --git a/source/isaaclab_ovphysx/changelog.d/malesiani-ovphysx-04-fixes.rst b/source/isaaclab_ovphysx/changelog.d/malesiani-ovphysx-04-fixes.rst new file mode 100644 index 000000000000..1708ee377f18 --- /dev/null +++ b/source/isaaclab_ovphysx/changelog.d/malesiani-ovphysx-04-fixes.rst @@ -0,0 +1,6 @@ +Fixed +^^^^^ + +* Fixed OvPhysX articulation tensor reads and writes for ``ovphysx`` 0.4 + compatibility. +* Restored DirectGPU startup settings for OvPhysX GPU simulations. diff --git a/source/isaaclab_ovphysx/isaaclab_ovphysx/assets/articulation/articulation.py b/source/isaaclab_ovphysx/isaaclab_ovphysx/assets/articulation/articulation.py index f3919d56da73..bea4345ca5ba 100644 --- a/source/isaaclab_ovphysx/isaaclab_ovphysx/assets/articulation/articulation.py +++ b/source/isaaclab_ovphysx/isaaclab_ovphysx/assets/articulation/articulation.py @@ -1759,7 +1759,7 @@ def _initialize_impl(self) -> None: # (keyed on object identity) handles the fast path automatically. self._effort_binding = self._get_binding(TT.DOF_ACTUATION_FORCE) if self._effort_binding is not None: - torque = self._data.applied_torque + torque = self._data._applied_torque shape = self._effort_binding.shape self._effort_write_view = wp.array( ptr=torque.ptr, @@ -1780,10 +1780,10 @@ def _make_write_view(tt, buf): return b, v self._pos_target_binding, self._pos_target_write_view = _make_write_view( - TT.DOF_POSITION_TARGET, self._data.joint_pos_target + TT.DOF_POSITION_TARGET, self._data._joint_pos_target ) self._vel_target_binding, self._vel_target_write_view = _make_write_view( - TT.DOF_VELOCITY_TARGET, self._data.joint_vel_target + TT.DOF_VELOCITY_TARGET, self._data._joint_vel_target ) # Let the articulation data know that it is fully instantiated and ready to use. diff --git a/source/isaaclab_ovphysx/isaaclab_ovphysx/assets/articulation/articulation_data.py b/source/isaaclab_ovphysx/isaaclab_ovphysx/assets/articulation/articulation_data.py index 10c7e4b7ecd6..e5be6c05328b 100644 --- a/source/isaaclab_ovphysx/isaaclab_ovphysx/assets/articulation/articulation_data.py +++ b/source/isaaclab_ovphysx/isaaclab_ovphysx/assets/articulation/articulation_data.py @@ -1684,10 +1684,24 @@ def _read_binding_into_flat(self, tensor_type: int, wp_array: wp.array) -> None: Reads directly into the target array -- no scratch buffer, no extra copy. """ + self._read_binding_into_view(tensor_type, wp_array) + + def _read_binding_into_view(self, tensor_type: int, view: wp.array) -> None: + """Read an ovphysx binding into a float32 warp view.""" binding = self._get_binding(tensor_type) if binding is None: return - binding.read(wp_array) + + from isaaclab_ovphysx.tensor_types import _CPU_ONLY_TYPES + + if tensor_type in _CPU_ONLY_TYPES and str(view.device) != "cpu": + scratch = self._get_read_scratch(tensor_type) + if scratch is None: + return + binding.read(scratch) + wp.copy(view, scratch) + else: + binding.read(view) def _read_binding_into_buf(self, tensor_type: int, buf: TimestampedBuffer) -> None: """Read from an ovphysx binding into a TimestampedBuffer, skipping if fresh.""" @@ -1696,7 +1710,7 @@ def _read_binding_into_buf(self, tensor_type: int, buf: TimestampedBuffer) -> No view = self._get_read_view(tensor_type, buf.data) if view is None: return - self._get_binding(tensor_type).read(view) + self._read_binding_into_view(tensor_type, view) buf.timestamp = self._sim_timestamp def _read_transform_binding(self, tensor_type: int, buf: TimestampedBuffer) -> None: @@ -1706,7 +1720,7 @@ def _read_transform_binding(self, tensor_type: int, buf: TimestampedBuffer) -> N view = self._get_read_view(tensor_type, buf.data, 7) if view is None: return - self._get_binding(tensor_type).read(view) + self._read_binding_into_view(tensor_type, view) buf.timestamp = self._sim_timestamp def _read_spatial_vector_binding(self, tensor_type: int, buf: TimestampedBuffer) -> None: @@ -1716,7 +1730,7 @@ def _read_spatial_vector_binding(self, tensor_type: int, buf: TimestampedBuffer) view = self._get_read_view(tensor_type, buf.data, 6) if view is None: return - self._get_binding(tensor_type).read(view) + self._read_binding_into_view(tensor_type, view) buf.timestamp = self._sim_timestamp """ diff --git a/source/isaaclab_ovphysx/isaaclab_ovphysx/physics/ovphysx_manager.py b/source/isaaclab_ovphysx/isaaclab_ovphysx/physics/ovphysx_manager.py index 9063078e45b3..6caad37ab7bf 100644 --- a/source/isaaclab_ovphysx/isaaclab_ovphysx/physics/ovphysx_manager.py +++ b/source/isaaclab_ovphysx/isaaclab_ovphysx/physics/ovphysx_manager.py @@ -13,6 +13,7 @@ from __future__ import annotations import atexit +import inspect import logging import os import tempfile @@ -202,7 +203,23 @@ def _warmup_and_load(cls) -> None: import ovphysx - cls._physx = ovphysx.PhysX(device=ovphysx_device, gpu_index=gpu_index) + physx_kwargs = {"device": ovphysx_device} + physx_signature = inspect.signature(ovphysx.PhysX) + physx_parameters = physx_signature.parameters + if "active_cuda_gpus" in physx_parameters: + if ovphysx_device == "gpu": + # ovphysx 0.4 accepts a comma-separated CUDA ordinal string; IsaacLab selects one GPU. + physx_kwargs["active_cuda_gpus"] = str(gpu_index) + physx_kwargs["config"] = ovphysx.PhysXConfig( + carbonite_overrides={ + "/physics/suppressReadback": True, + "/physics/suppressFabricUpdate": True, + } + ) + elif "gpu_index" in physx_parameters: + physx_kwargs["gpu_index"] = gpu_index + + cls._physx = ovphysx.PhysX(**physx_kwargs) # Without worker threads the stepper runs simulate()+fetchResults() # synchronously, blocking the calling thread for the full GPU step time. diff --git a/source/isaaclab_ovphysx/test/assets/test_articulation_data.py b/source/isaaclab_ovphysx/test/assets/test_articulation_data.py index 16bb99a4d6c4..390e5defa0f2 100644 --- a/source/isaaclab_ovphysx/test/assets/test_articulation_data.py +++ b/source/isaaclab_ovphysx/test/assets/test_articulation_data.py @@ -40,3 +40,19 @@ def test_joint_acc_uses_inverse_dt(self): atol=1e-6, err_msg="Joint acceleration should be computed as delta_velocity / dt.", ) + + def test_cpu_only_binding_read_stages_to_gpu_view(self): + """CPU-only bindings should be staged before copying into GPU-backed data buffers.""" + if not wp.is_cuda_available(): + pytest.skip("CUDA is required to test CPU-to-GPU staging.") + + mock_bindings = MockOvPhysxBindingSet(num_instances=1, num_joints=2, num_bodies=1) + data = ArticulationData(mock_bindings.bindings, device="cuda") + data._create_buffers() + + expected = np.array([[[1.0, 2.0, 3.0, 0.0, 0.0, 0.0, 1.0]]], dtype=np.float32) + mock_bindings.bindings[TT.BODY_COM_POSE]._data[...] = expected + + data._read_transform_binding(TT.BODY_COM_POSE, data._body_com_pose_b) + + np.testing.assert_allclose(data._body_com_pose_b.data.numpy(), expected, atol=1e-6) diff --git a/source/isaaclab_tasks/changelog.d/malesiani-ovphysx-camera-cartpole.rst b/source/isaaclab_tasks/changelog.d/malesiani-ovphysx-camera-cartpole.rst new file mode 100644 index 000000000000..5a352196a0ed --- /dev/null +++ b/source/isaaclab_tasks/changelog.d/malesiani-ovphysx-camera-cartpole.rst @@ -0,0 +1,4 @@ +Added +^^^^^ + +* Added the ``ovphysx`` physics preset to the cartpole camera presets task. diff --git a/source/isaaclab_tasks/isaaclab_tasks/direct/cartpole/cartpole_camera_presets_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/direct/cartpole/cartpole_camera_presets_env_cfg.py index 4c27674ff7c6..00d11f233ff6 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/direct/cartpole/cartpole_camera_presets_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/direct/cartpole/cartpole_camera_presets_env_cfg.py @@ -6,6 +6,7 @@ from __future__ import annotations from isaaclab_newton.physics import NewtonCfg +from isaaclab_ovphysx.physics import OvPhysxCfg from isaaclab_physx.physics import PhysxCfg import isaaclab.sim as sim_utils @@ -27,6 +28,7 @@ class PhysicsCfg(PresetCfg): default = PhysxCfg() physx = PhysxCfg() newton_mjwarp = NewtonCfg() + ovphysx = OvPhysxCfg() @configclass From 65e5ead4847c28b9c48504023465432e19277f9b Mon Sep 17 00:00:00 2001 From: Antoine RICHARD Date: Fri, 8 May 2026 20:18:02 +0200 Subject: [PATCH 23/51] Add Kamino solver tutorial (#5483) # Description Adds a dedicated Newton experimental tutorial for using the Kamino solver. The page explains that Kamino is selected through a Newton physics solver preset, shows the task changes needed to add a `kamino` preset, lists compatibility checks for assets, resets, sensors, and renderers, and documents the Kamino-specific solver parameters by category. This addresses Kellys follow-up request on #5457 for a tutorial describing what needs to change to work with Kamino and for descriptions of Kamino-specific solver parameters. Fixes # (issue) ## Type of change - Documentation update ## Screenshots Not applicable. Documentation-only RST change. ## Checklist - [x] I have read and understood the [contribution guidelines](https://isaac-sim.github.io/IsaacLab/main/source/refs/contributing.html) - [x] I have run the [`pre-commit` checks](https://pre-commit.com/) with `./isaaclab.sh --format` - [x] I have made corresponding changes to the documentation - [ ] My changes generate no new warnings - [ ] I have added tests that prove my fix is effective or that my feature works - [ ] I have updated the changelog and the corresponding version in the extensions `config/extension.toml` file - [x] I have added my name to the `CONTRIBUTORS.md` or my name already exists there Notes: - Ran `./isaaclab.sh -f` successfully. - Verified the `literalinclude` target and referenced labels locally. - `./isaaclab.sh -d` could not start in this checkout because there is no virtual environment and system Python is PEP 668 protected, so pip refused to install docs requirements. Because Sphinx did not run, the warning checklist item is intentionally left unchecked. - No tests or changelog fragment were added because this is a documentation-only follow-up under `docs/source`; the current repository guidance uses `source//changelog.d` fragments only for touched source packages. --- .../newton-physics-integration/index.rst | 1 + .../solver-transitioning.rst | 2 +- .../using-kamino.rst | 239 ++++++++++++++++++ 3 files changed, 241 insertions(+), 1 deletion(-) create mode 100644 docs/source/experimental-features/newton-physics-integration/using-kamino.rst diff --git a/docs/source/experimental-features/newton-physics-integration/index.rst b/docs/source/experimental-features/newton-physics-integration/index.rst index f40de231834a..afe783cc8716 100644 --- a/docs/source/experimental-features/newton-physics-integration/index.rst +++ b/docs/source/experimental-features/newton-physics-integration/index.rst @@ -40,3 +40,4 @@ For an overview of how the multi-backend architecture works, including how to ad installation limitations-and-known-bugs solver-transitioning + using-kamino diff --git a/docs/source/experimental-features/newton-physics-integration/solver-transitioning.rst b/docs/source/experimental-features/newton-physics-integration/solver-transitioning.rst index 0c480bfec73d..5d78f44de503 100644 --- a/docs/source/experimental-features/newton-physics-integration/solver-transitioning.rst +++ b/docs/source/experimental-features/newton-physics-integration/solver-transitioning.rst @@ -5,7 +5,7 @@ Transitioning to the Newton physics engine introduces new physics solvers that h While Newton supports several different solvers, our initial focus for Isaac Lab is on using the MuJoCo-Warp solver from Google DeepMind. Isaac Lab also includes beta support for the Kamino solver on selected classic tasks. Kamino is selected through a physics preset rather than as a -separate backend; see :ref:`hydra-backend-solver-presets`. +separate backend; see :ref:`hydra-backend-solver-presets` and :ref:`newton-using-kamino`. .. note:: diff --git a/docs/source/experimental-features/newton-physics-integration/using-kamino.rst b/docs/source/experimental-features/newton-physics-integration/using-kamino.rst new file mode 100644 index 000000000000..7c8b6f2d564c --- /dev/null +++ b/docs/source/experimental-features/newton-physics-integration/using-kamino.rst @@ -0,0 +1,239 @@ +.. _newton-using-kamino: + +Using the Kamino Solver +======================= + +Kamino is a Newton solver, not a separate Isaac Lab physics backend. In Isaac Lab, +Kamino is enabled by selecting a :class:`~isaaclab_newton.physics.NewtonCfg` whose +``solver_cfg`` is :class:`~isaaclab_newton.physics.KaminoSolverCfg`. +This is usually exposed as a ``newton_kamino`` physics preset on the task configuration. + +Kamino support is currently beta. A task that works with PhysX or with Newton's +MuJoCo-Warp solver may still need task-specific asset, collision, reset, and solver +tuning before it works well with Kamino. + + +Start from a Supported Newton Task +---------------------------------- + +Before adding Kamino, first make sure the task runs with the Newton backend: + +.. code-block:: bash + + ./isaaclab.sh -p scripts/environments/zero_agent.py --task Isaac-Cartpole-Direct-v0 --num_envs 128 --viz newton presets=newton_mjwarp + +Then run the same task with the Kamino preset if it is available: + +.. code-block:: bash + + ./isaaclab.sh -p scripts/environments/zero_agent.py --task Isaac-Cartpole-Direct-v0 --num_envs 128 --viz newton presets=newton_kamino + +At the time of writing, the ``newton_kamino`` preset is defined for +``Isaac-Cartpole-Direct-v0``, ``Isaac-Ant-Direct-v0``, ``Isaac-Cartpole-v0``, +and ``Isaac-Ant-v0``. Passing ``presets=newton_kamino`` to another task does not +automatically enable Kamino; the task must define and validate its own ``newton_kamino`` +preset. + + +Add a Kamino Physics Preset +--------------------------- + +Tasks that support multiple physics options usually store ``SimulationCfg.physics`` +as a :class:`~isaaclab_tasks.utils.hydra.PresetCfg`. First import the Newton +solver config types used by the presets: + +.. code-block:: python + + from isaaclab_newton.physics import KaminoSolverCfg, MJWarpSolverCfg, NewtonCfg + +Then add a ``newton_kamino`` entry beside the existing ``default``, ``physx``, and +``newton_mjwarp`` entries: + +.. literalinclude:: ../../../../source/isaaclab_tasks/isaaclab_tasks/direct/cartpole/cartpole_env_cfg.py + :language: python + :start-at: class CartpolePhysicsCfg + :end-at: ovphysx: OvPhysxCfg = OvPhysxCfg() + :emphasize-lines: 16-38 + +The important pieces are: + +* Add a ``newton_kamino`` preset whose value is :class:`~isaaclab_newton.physics.NewtonCfg`. +* Set ``solver_cfg=KaminoSolverCfg(...)`` inside that Newton config. +* Keep the preset at the same config path used by the task's + :class:`~isaaclab.sim.SimulationCfg`, for example ``env.sim.physics``. + +You can select the preset globally: + +.. code-block:: bash + + ./isaaclab.sh -p scripts/reinforcement_learning/rsl_rl/train.py --task=Isaac-Cartpole-v0 presets=newton_kamino + +or select the physics field directly: + +.. code-block:: bash + + ./isaaclab.sh -p scripts/reinforcement_learning/rsl_rl/train.py --task=Isaac-Cartpole-v0 env.sim.physics=newton_kamino + +Use the direct path override when only one task field should use the Kamino preset. +Use ``presets=newton_kamino`` when you want every matching preset field in the task config +to resolve to ``newton_kamino``. +Isaac Lab training scripts accept these Hydra overrides after the regular command +line flags; no separator is needed for the examples above. + + +Check Task and Asset Compatibility +---------------------------------- + +Kamino uses the Newton model built from the task assets. When adding Kamino to a +new task, validate the following before tuning solver parameters: + +* The task must already be compatible with the Newton backend. If ``presets=newton_mjwarp`` + fails during model construction, fix the asset or task configuration first. +* The assets should use Newton-supported rigid bodies, articulations, and collision + geometry. PhysX-only features, unsupported schemas, or missing collision shapes + can prevent Newton model creation or produce unusable contacts. +* Reset logic should write consistent root and joint state through Isaac Lab asset + APIs. Kamino uses a forward-kinematics reset path after state writes so maximal + coordinate body poses match the reduced joint state. +* Sensor, renderer, and visualizer presets remain separate from the solver preset. + Kamino can share the Newton-compatible sensors and renderers used by the task, + but each sensor and renderer combination still needs its own validation. +* Contact-heavy tasks usually need their own collision mode, substep count, and + P-ADMM iteration/tolerance settings. Start from the validated Cartpole or Ant + preset that most closely resembles the task. + +For a small articulated system with simple contacts, the Cartpole preset uses +Kamino's internal collision detector. For Ant, the preset uses Newton's collision +pipeline and two substeps. These choices are task-specific; treat them as starting +points rather than universal defaults. + + +Kamino Solver Parameters +------------------------ + +The following fields are specific to :class:`~isaaclab_newton.physics.KaminoSolverCfg`. +They are grouped by the part of the solver they affect. + +Core Integration +^^^^^^^^^^^^^^^^ + +.. list-table:: + :header-rows: 1 + :widths: 30 70 + + * - Parameter + - Description + * - ``integrator`` + - Default: ``"euler"``. Time integration scheme. ``"moreau"`` is used by the validated Kamino task presets. + * - ``use_fk_solver`` + - Default: ``True``. Enables Kamino's forward-kinematics solver for resets. Keep this enabled for Isaac Lab tasks unless you have a task-specific reset path. + * - ``rotation_correction`` + - Default: ``"twopi"``. Rotation correction mode for maximal-coordinate bodies. Valid values are ``"twopi"``, ``"continuous"``, and ``"none"``. + * - ``angular_velocity_damping`` + - Default: ``0.0``. Damps angular velocity. Higher values can suppress spin but also remove physical energy from the system. + + +Collision Handling +^^^^^^^^^^^^^^^^^^ + +.. list-table:: + :header-rows: 1 + :widths: 30 70 + + * - Parameter + - Description + * - ``use_collision_detector`` + - Default: ``False``. Selects Kamino's internal collision detector when ``True``. When ``False``, Isaac Lab uses Newton's collision pipeline for contact generation. + * - ``collision_detector_pipeline`` + - Default: ``None``. Internal Kamino collision detector pipeline. Common values are ``"primitive"`` and ``"unified"``. Only used when ``use_collision_detector=True``. + * - ``collision_detector_max_contacts_per_pair`` + - Default: ``None``. Maximum contacts generated per candidate geometry pair by the internal Kamino collision detector. + * - ``constraints_delta`` + - Default: ``1.0e-6``. Contact penetration margin [m] used by Kamino constraint stabilization. + + +Constraint Stabilization +^^^^^^^^^^^^^^^^^^^^^^^^ + +.. list-table:: + :header-rows: 1 + :widths: 30 70 + + * - Parameter + - Description + * - ``constraints_alpha`` + - Default: ``0.01``. Baumgarte stabilization for bilateral joint constraints. Increasing it can reduce joint constraint drift but may make the solve stiffer. + * - ``constraints_beta`` + - Default: ``0.01``. Baumgarte stabilization for unilateral joint-limit constraints. + * - ``constraints_gamma`` + - Default: ``0.01``. Baumgarte stabilization for unilateral contact constraints. + + +P-ADMM Solver Controls +^^^^^^^^^^^^^^^^^^^^^^ + +.. list-table:: + :header-rows: 1 + :widths: 30 70 + + * - Parameter + - Description + * - ``padmm_max_iterations`` + - Default: ``200``. Maximum number of P-ADMM iterations per solver step. Higher values can improve convergence and increase runtime. + * - ``padmm_primal_tolerance`` + - Default: ``1e-6``. Primal residual convergence tolerance. + * - ``padmm_dual_tolerance`` + - Default: ``1e-6``. Dual residual convergence tolerance. + * - ``padmm_compl_tolerance`` + - Default: ``1e-6``. Complementarity residual convergence tolerance for contacts and unilateral constraints. + * - ``padmm_rho_0`` + - Default: ``1.0``. Initial P-ADMM penalty parameter. This influences how strongly constraint residuals are penalized early in the solve. + * - ``padmm_eta`` + - Default: ``1e-5``. Proximal regularization parameter. It must be greater than zero. + * - ``padmm_use_acceleration`` + - Default: ``True``. Enables acceleration in the P-ADMM iterations. This usually improves convergence but should be validated per task. + * - ``padmm_warmstart_mode`` + - Default: ``"containers"``. Warm-start source for P-ADMM. Valid values are ``"none"``, ``"internal"``, and ``"containers"``. + * - ``padmm_contact_warmstart_method`` + - Default: ``"key_and_position"``. Contact warm-start matching method. The validated presets use ``"geom_pair_net_force"``. + * - ``padmm_use_graph_conditionals`` + - Default: ``True``. Uses CUDA graph conditional nodes for the iterative solver when ``True``. Setting it to ``False`` unrolls to fixed loops over the maximum iteration count. + + +Sparsity, Dynamics, and Debugging +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +.. list-table:: + :header-rows: 1 + :widths: 30 70 + + * - Parameter + - Description + * - ``sparse_jacobian`` + - Default: ``False``. Uses sparse Jacobian computation. This is enabled in the validated Kamino task presets. + * - ``sparse_dynamics`` + - Default: ``False``. Uses sparse dynamics computation. + * - ``dynamics_preconditioning`` + - Default: ``True``. Enables preconditioning for constrained dynamics. Preconditioning can improve P-ADMM convergence. + * - ``collect_solver_info`` + - Default: ``False``. Collects solver convergence and performance information. Enable only for debugging because it significantly increases runtime. + * - ``compute_solution_metrics`` + - Default: ``False``. Computes solution metrics at each step. Enable only for debugging because it significantly increases runtime. + + +Tuning Workflow +--------------- + +Use the following sequence when bringing up a new Kamino task: + +1. Run the task with ``presets=newton_mjwarp`` and fix Newton model construction or task + compatibility issues first. +2. Add a ``newton_kamino`` preset with conservative values copied from the closest + validated task. +3. Run a small smoke test with a low environment count and a visualizer. +4. Increase ``num_envs`` and profile only after the task is stable. +5. Tune ``num_substeps``, ``padmm_max_iterations``, and the P-ADMM tolerances + together. Raising iteration count without checking tolerances can hide a + poorly scaled constraint setup. +6. Enable ``collect_solver_info`` or ``compute_solution_metrics`` only while + debugging convergence. Disable them for training and benchmarks. From 23ababb1b63c55469c4c659d25365323df8988b3 Mon Sep 17 00:00:00 2001 From: hujc Date: Fri, 8 May 2026 12:09:47 -0700 Subject: [PATCH 24/51] [Visualizers] Fix viewergl fully-black: assign PyVec3 to Newton camera.pos (#5547) --- .../jichuanh-fix-newton-cam-pos-type.rst | 15 +++++++++++++++ .../newton/newton_visualizer.py | 4 +++- .../test/test_visualizer_cartpole_integration.py | 16 ---------------- 3 files changed, 18 insertions(+), 17 deletions(-) create mode 100644 source/isaaclab_visualizers/changelog.d/jichuanh-fix-newton-cam-pos-type.rst diff --git a/source/isaaclab_visualizers/changelog.d/jichuanh-fix-newton-cam-pos-type.rst b/source/isaaclab_visualizers/changelog.d/jichuanh-fix-newton-cam-pos-type.rst new file mode 100644 index 000000000000..6c6525acadf5 --- /dev/null +++ b/source/isaaclab_visualizers/changelog.d/jichuanh-fix-newton-cam-pos-type.rst @@ -0,0 +1,15 @@ +Fixed +^^^^^ + +* Fixed ``test_visualizer_cartpole_integration::test_cartpole_newton_visualizer_viewergl_rgb_motion`` + returning a fully-black ``ViewerGL.get_frame`` buffer on the Newton 1.2.0rc2 + + warp 1.13 cohort. ``NewtonVisualizer._apply_camera_pose`` was assigning + ``self._viewer.camera.pos = wp.vec3(*cam_pos)``, but Newton's + ``Camera.translate()`` adds a ``pyglet.math.Vec3`` delta with ``+=``. + warp 1.13's strict ``__add__`` rejects ``wp.vec3 + pyglet.math.Vec3`` + with ``TypeError``; the exception was silenced by the visualizer's + ``try/except``, which prevented ``renderer.render()`` from ever running + -- so the framebuffer stayed empty and read back as all zeros. The fix + assigns ``pyglet.math.Vec3`` instead, matching what Newton uses internally. +* Re-enabled ``test_cartpole_newton_visualizer_viewergl_rgb_motion`` after the + workaround skip in https://github.com/isaac-sim/IsaacLab/pull/5538. diff --git a/source/isaaclab_visualizers/isaaclab_visualizers/newton/newton_visualizer.py b/source/isaaclab_visualizers/isaaclab_visualizers/newton/newton_visualizer.py index b548a3e5f4f3..aeafc29bd264 100644 --- a/source/isaaclab_visualizers/isaaclab_visualizers/newton/newton_visualizer.py +++ b/source/isaaclab_visualizers/isaaclab_visualizers/newton/newton_visualizer.py @@ -13,6 +13,7 @@ import numpy as np import warp as wp from newton.viewer import ViewerGL +from pyglet.math import Vec3 as PygletVec3 from isaaclab.visualizers.base_visualizer import BaseVisualizer @@ -463,7 +464,8 @@ def _apply_camera_pose(self, pose: tuple[tuple[float, float, float], tuple[float if self._viewer is None: return cam_pos, cam_target = pose - self._viewer.camera.pos = wp.vec3(*cam_pos) + # Match Newton's Camera native pos type: PyVec3, not wp.vec3. + self._viewer.camera.pos = PygletVec3(*cam_pos) cam_pos_np = np.array(cam_pos, dtype=np.float32) cam_target_np = np.array(cam_target, dtype=np.float32) direction = cam_target_np - cam_pos_np diff --git a/source/isaaclab_visualizers/test/test_visualizer_cartpole_integration.py b/source/isaaclab_visualizers/test/test_visualizer_cartpole_integration.py index 60f9921415cc..42d1368dcebf 100644 --- a/source/isaaclab_visualizers/test/test_visualizer_cartpole_integration.py +++ b/source/isaaclab_visualizers/test/test_visualizer_cartpole_integration.py @@ -522,22 +522,6 @@ def test_cartpole_newton_visualizer_tiled_camera_rgb_non_black( @pytest.mark.isaacsim_ci -@pytest.mark.skip( - reason=( - "ViewerGL.get_frame returns a fully-black 600x600x3 buffer in CI on the current " - "Isaac Sim image + Newton 1.2.0rc2 + warp-lang 1.13 cohort. Failure is " - "deterministic across two consecutive reruns of the same SHA and reproduces on " - "every PR that touches the rendering / camera / sensor / USD stack (5 PRs hit it " - "in the last 100 build.yaml runs); zero failures on PRs outside that scope. " - "Investigation ruled out: rc1->rc2 viewer code diff (7-line image_logger.clear " - "only), wp.RegisteredGLBuffer API (byte-identical 1.12 vs 1.13), pure flakiness " - "(deterministic), and the bump cohort alone (warp-1.12 branches both pass and " - "fail). Strongest remaining hypothesis: a CUDA-OpenGL interop init-order " - "fragility in the PBO + glReadPixels + RegisteredGLBuffer.map path that gets " - "tipped by any source change perturbing GL/CUDA bring-up. Re-enable once root " - "cause is identified." - ) -) @pytest.mark.parametrize("backend_kind", ["physx", "newton"]) def test_cartpole_newton_visualizer_viewergl_rgb_motion(backend_kind: str, caplog: pytest.LogCaptureFixture) -> None: """Newton GL (``ViewerGL.get_frame``): full motion steps, last frame non-black; early vs late differ; logs.""" From 1336acd89688d9afaca3e7c0abe88ef2b8f6941d Mon Sep 17 00:00:00 2001 From: Welf Rehberg <65718465+Zwoelf12@users.noreply.github.com> Date: Fri, 8 May 2026 21:20:47 +0200 Subject: [PATCH 25/51] Adds multirotor vision-based navigation task and acceleration, velocity and position controllers (#3895) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit ## Description This PR extends [3760](https://github.com/isaac-sim/IsaacLab/pull/3760) by introducing a navigation tasks for the ARL robot. The PR adds a confined cluttered environment, adds acceleration, velocity and position controllers + configs, extends the MDP and RL configs and adds a Variational Auto Encoder to generate image latents for observations. The PR depends on the `MultiMeshRayCasterCamera` introduced in PR [3298](https://github.com/isaac-sim/IsaacLab/pull/3298) (currently not merged in IsaacLab). ## Changes ### Type of Change - New feature (non-breaking change which adds functionality) - Documentation update (added docs/comments where applicable) ### Files changed (high-level summary) - New files added: - source/isaaclab_tasks/isaaclab_tasks/manager_based/drone_arl/navigation/* (new task code and config, obstacle scene code and config) - source/isaaclab_tasks/isaaclab_tasks/manager_based/drone_arl/mdp/vae_model.pt - source/isaaclab/isaaclab/controllers/lee_acceleration_control_cfg.py - source/isaaclab/isaaclab/controllers/lee_acceleration_control.py - source/isaaclab/isaaclab/controllers/lee_velocity_control_cfg.py - source/isaaclab/isaaclab/controllers/lee_velocity_control.py - source/isaaclab/isaaclab/controllers/lee_position_control_cfg.py - ource/isaaclab/isaaclab/controllers/lee_position_control.py - Modified: - source/isaaclab_tasks/isaaclab_tasks/manager_based/drone_arl/mdp/* (added navigation specifics) - source/isaaclab/isaaclab/envs/mdp/actions/actions_cfg.py (added new action config) - source/isaaclab/isaaclab/envs/mdp/actions/thrust_actions.py (introduced new navigation action handling controller application) - Total diff (branch vs main, includes also unmerged changes of PR [3760](https://github.com/isaac-sim/IsaacLab/pull/3760) and PR [3298](https://github.com/isaac-sim/IsaacLab/pull/3298)): 74 files changed, 8029 insertions, 88 deletions ## Dependencies - The new drone task references standard repo-internal packages and Isaac Sim; no external pip packages required beyond the repo standard. ## Checklist - [x] I have read and understood the [contribution guidelines](https://isaac-sim.github.io/IsaacLab/main/source/refs/contributing.html) - [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 - [ ] I have added tests that prove my fix is effective or that my feature works - [ ] 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 --------- Signed-off-by: Grzegorz Malczyk <44407007+grzemal@users.noreply.github.com> Signed-off-by: renezurbruegg Signed-off-by: Welf Rehberg <65718465+Zwoelf12@users.noreply.github.com> Co-authored-by: grzemal Co-authored-by: Grzegorz Malczyk <44407007+grzemal@users.noreply.github.com> Co-authored-by: greptile-apps[bot] <165735046+greptile-apps[bot]@users.noreply.github.com> Co-authored-by: René zurbrügg Co-authored-by: Pascal Roth Co-authored-by: Pascal Roth <57946385+pascal-roth@users.noreply.github.com> --- .../drone_arl/arl_robot_1_navigation.jpg | Bin 0 -> 97329 bytes docs/source/api/index.rst | 1 + .../isaaclab_contrib.controllers.rst | 88 +++++ docs/source/overview/environments.rst | 26 +- scripts/demos/arl_robot_1.py | 114 ++++++ .../isaaclab_assets/robots/arl_robot_1.py | 2 +- source/isaaclab_contrib/docs/README.md | 8 +- .../isaaclab_contrib/actuators/thruster.py | 6 +- .../isaaclab_contrib/controllers/__init__.py | 16 + .../isaaclab_contrib/controllers/__init__.pyi | 32 ++ .../controllers/lee_acceleration_control.py | 102 ++++++ .../lee_acceleration_control_cfg.py | 23 ++ .../controllers/lee_attitude_control.py | 98 +++++ .../controllers/lee_attitude_control_cfg.py | 23 ++ .../controllers/lee_controller_base.py | 120 ++++++ .../controllers/lee_controller_base_cfg.py | 73 ++++ .../controllers/lee_controller_utils.py | 127 +++++++ .../controllers/lee_position_control.py | 134 +++++++ .../controllers/lee_position_control_cfg.py | 44 +++ .../controllers/lee_velocity_control.py | 133 +++++++ .../controllers/lee_velocity_control_cfg.py | 34 ++ .../isaaclab_contrib/mdp/__init__.pyi | 4 +- .../isaaclab_contrib/mdp/actions/__init__.pyi | 6 +- .../mdp/actions/thrust_actions.py | 168 +++++++++ .../mdp/actions/thrust_actions_cfg.py | 41 ++- .../isaaclab_contrib/utils/math.py | 93 +++++ .../test_drone_geometric_controllers.py | 345 ++++++++++++++++++ .../manager_based/drone_arl/mdp/__init__.pyi | 14 - .../mdp/commands/drone_pose_command.py | 4 +- .../drone_arl/mdp/curriculums.py | 148 ++++++++ .../manager_based/drone_arl/mdp/events.py | 189 ++++++++++ .../drone_arl/mdp/observations.py | 181 ++++++++- .../manager_based/drone_arl/mdp/rewards.py | 112 +++++- .../drone_arl/navigation/__init__.py | 6 + .../drone_arl/navigation/config/__init__.py | 6 + .../navigation/config/arl_robot_1/__init__.py | 36 ++ .../config/arl_robot_1/agents/__init__.py | 4 + .../agents/rl_games_rough_ppo_cfg.yaml | 87 +++++ .../arl_robot_1/agents/rsl_rl_ppo_cfg.py | 37 ++ .../agents/skrl_rough_ppo_cfg.yaml | 95 +++++ .../arl_robot_1/floating_obstacles_env_cfg.py | 41 +++ .../config/arl_robot_1/navigation_env_cfg.py | 344 +++++++++++++++++ .../scenes/obstacle_scenes/obstacle_scene.py | 114 ++++++ .../obstacle_scenes/obstacle_scene_cfg.py | 88 +++++ .../track_position_state_based_env_cfg.py | 23 +- 45 files changed, 3345 insertions(+), 45 deletions(-) create mode 100644 docs/source/_static/tasks/drone_arl/arl_robot_1_navigation.jpg create mode 100644 docs/source/api/lab_contrib/isaaclab_contrib.controllers.rst create mode 100644 scripts/demos/arl_robot_1.py create mode 100644 source/isaaclab_contrib/isaaclab_contrib/controllers/__init__.py create mode 100644 source/isaaclab_contrib/isaaclab_contrib/controllers/__init__.pyi create mode 100644 source/isaaclab_contrib/isaaclab_contrib/controllers/lee_acceleration_control.py create mode 100644 source/isaaclab_contrib/isaaclab_contrib/controllers/lee_acceleration_control_cfg.py create mode 100644 source/isaaclab_contrib/isaaclab_contrib/controllers/lee_attitude_control.py create mode 100644 source/isaaclab_contrib/isaaclab_contrib/controllers/lee_attitude_control_cfg.py create mode 100644 source/isaaclab_contrib/isaaclab_contrib/controllers/lee_controller_base.py create mode 100644 source/isaaclab_contrib/isaaclab_contrib/controllers/lee_controller_base_cfg.py create mode 100644 source/isaaclab_contrib/isaaclab_contrib/controllers/lee_controller_utils.py create mode 100644 source/isaaclab_contrib/isaaclab_contrib/controllers/lee_position_control.py create mode 100644 source/isaaclab_contrib/isaaclab_contrib/controllers/lee_position_control_cfg.py create mode 100644 source/isaaclab_contrib/isaaclab_contrib/controllers/lee_velocity_control.py create mode 100644 source/isaaclab_contrib/isaaclab_contrib/controllers/lee_velocity_control_cfg.py create mode 100644 source/isaaclab_contrib/isaaclab_contrib/utils/math.py create mode 100644 source/isaaclab_contrib/test/controllers/test_drone_geometric_controllers.py create mode 100644 source/isaaclab_tasks/isaaclab_tasks/manager_based/drone_arl/mdp/curriculums.py create mode 100644 source/isaaclab_tasks/isaaclab_tasks/manager_based/drone_arl/mdp/events.py create mode 100644 source/isaaclab_tasks/isaaclab_tasks/manager_based/drone_arl/navigation/__init__.py create mode 100644 source/isaaclab_tasks/isaaclab_tasks/manager_based/drone_arl/navigation/config/__init__.py create mode 100644 source/isaaclab_tasks/isaaclab_tasks/manager_based/drone_arl/navigation/config/arl_robot_1/__init__.py create mode 100644 source/isaaclab_tasks/isaaclab_tasks/manager_based/drone_arl/navigation/config/arl_robot_1/agents/__init__.py create mode 100644 source/isaaclab_tasks/isaaclab_tasks/manager_based/drone_arl/navigation/config/arl_robot_1/agents/rl_games_rough_ppo_cfg.yaml create mode 100644 source/isaaclab_tasks/isaaclab_tasks/manager_based/drone_arl/navigation/config/arl_robot_1/agents/rsl_rl_ppo_cfg.py create mode 100644 source/isaaclab_tasks/isaaclab_tasks/manager_based/drone_arl/navigation/config/arl_robot_1/agents/skrl_rough_ppo_cfg.yaml create mode 100644 source/isaaclab_tasks/isaaclab_tasks/manager_based/drone_arl/navigation/config/arl_robot_1/floating_obstacles_env_cfg.py create mode 100644 source/isaaclab_tasks/isaaclab_tasks/manager_based/drone_arl/navigation/config/arl_robot_1/navigation_env_cfg.py create mode 100644 source/isaaclab_tasks/isaaclab_tasks/manager_based/drone_arl/navigation/config/arl_robot_1/scenes/obstacle_scenes/obstacle_scene.py create mode 100644 source/isaaclab_tasks/isaaclab_tasks/manager_based/drone_arl/navigation/config/arl_robot_1/scenes/obstacle_scenes/obstacle_scene_cfg.py diff --git a/docs/source/_static/tasks/drone_arl/arl_robot_1_navigation.jpg b/docs/source/_static/tasks/drone_arl/arl_robot_1_navigation.jpg new file mode 100644 index 0000000000000000000000000000000000000000..108e9e4758678f0ed2a756d9ae55961b2731904a GIT binary patch literal 97329 zcmbTdXEwLg2Uz1HXK@^|F#G(fL$U;RD+fdBvm`~&`; z0UY<-T|K<)yuIyg5!QhSCl5OZK`%R-|E~Ny4nzR3|1B3UQe3=9MF|$F%hc!PGSg++ z%iuo~!$0(N^#3rhvoJHWup`-Sup#-lx%uvh-ceRIgZ%INu>Us!f4>6^RIpi!e=k6g z0F(i8fdTTj1z-aaK%p1T!Te8wKrd2WfKgCU{~ZIU{;T2W0D#aNY6mFgAsJpf1%H0& zchKoHZf2lPJSuNl zurMwP0H~tT0I$Top5+N{s4o4lYwHWPMktktb^s4>rMQ#`?|_diw?kO(sCkm7&*XVE z49fBiqP~8WG;iPofQJ`iI^qC+spQB+6I+vV8tONe00w)({#tUtIe-h1YA3>rK0)c` z1dC^crqzL&MCjr(jiI_0|y|Mz^H-!M z!)ed;)rCQ2FA2y4G^?^JWsK6DzC1EJ%XIbmrh*OHP|a|c&;k0w~< zSXs@$5)$H*vmxwkq0GSd8HnJ9vRlx@-e#14B;L?*B#$tv;Zf>Z28BQz*Gc(N=0+{C zfr%QF2bF6`EUUoH9g@N`2bOn(Cc`Q$BA-2riHUicW(EqBv}huq8wiLcpdohR*-yLn zRX;cbD1A=LQiEXt5C}8f57(;bTa^6SaM#vs8x%=N*Lywn`?g%BWZ#lcb-F@@DQL6i z=GNBcR&72{{rwwkyPovGB`ib-^*JiKSIQcm5vo5gTZayrI?I1F3+3%F2LTP(j$t z^f;wC7D5F;`j@EhwH_W{os=%f9s(7>wc?D8i*Bg_9LYjDgHvtJUKYuzOSnO|ZkwRL z0MnQ`tzwb*V&7PjMBfw}mg-NKrtKjcjA%t@%LFw8RrUk>(zkmOpnVHF9mdZVj zdAj!42cSR$|7mEtH@rz|0{5w5NxtnLD^;0m)y57n<4q8xhvf#NM0ew zkTA6R=a0vqEsw3OE&bTc$`qcm|D3$HYiFNfEFkp*I+S2`Q3K+tL2sk6+_en6c9 zz-&y~Jk62AdAydo}OD!k}+5iJUSz*m{up#YF+wr zF+D6)i;Fb>8W{NIQ8 zssCpP1;+NvHkVI_>jZxdnlu*}?UkR6jHF{^1cSR*^7Uipr)2nz3XoNwvWQ@qnRIIa zqYMiR9R~-q)WKiC(?hDqv+oYT+nCxDow8N^1%_3JVKGqMi(&p$4bH z0y^YO4hx%9gXe8Y&`@Xw`fU##P2#R>MOlGE0x<=f2;qVQfb!M)@(KT_(gLIC(wF&P zo44mqZ=d9WuDbXa2v|(2CAm7>Aq_PM*-U*ua2qn}W9b=rW$?!6vt4L!q)yJz%5H#^ zRDjfhRAp{!o3`)-=1Rz4!2B%`U_?K^6Uw1EurNoKu>?Z^L^SGLli5pirKHqL1^<}q zbVZz{ocXssS(!Pu*jRhIS4whqCb>JC5ABGB-@NAh*!j70z6rltzJaKs<|pFvZgt&% zMv#LN4AbC0#|G-6%VS?E;FUL3oK{Una+VJYYRLpa02)-UoJ}@_RP4X=`*cvhEZ~{1 z4%eaQ=@f&{!5R&tjf| z5zj2-(P?wztEsDG?8TeWYRsa-dfbc*h(szaEWm%2R6608l1f$3^7&j()scU>0&F7F zWqNF2FV);#qHI&Ll(bhyShSsteXiheXw9$UY_wZUivzuGWw%mFO6J5YL@vZE#LV}! zsS)Qs(1N|l@=BdvxtPuX4UQTOG|&2o=xJh57*&YUef0UHLQ(s~A~Wmqx)k9>4x)#)#gTEbdS4y+v;t|bwJ`)Dgh%nLR< z;{P}{7{dRYa4>ajo#eac$O~oagTVm|xl#vU%sr^g)fqpz{H=571LAe~%*fqK$7kJY zYM?IQg>=3@#kv?0ITVGz)N_tTE6nSMvb~yVL zPl-LW8tHrT`{2yHl3c9Nppy%Nssx>`@?2GJTibE?lgo=NWGutC+FWRf!c-BW5KvN9 z1E_3dx;#i-M#`83PA1VX_Y+tfb~3?QceQxlzcf6Ei7c%}xLeX8g-hza!oK>XNEnyyR2BjK1<1LYoE z$ExWri`E%-&zbC2w&YW`=p5{#*;5eQvo2Xz;9O{)-92A+P$ZW{4&#`ess0P}y-JA8 z8C=~xI{B}xZT4_>_Ozif64f-UtbzDe@Ed+%bkCj%0RZs;C6a=6==0q+ZV(nYnMlKBIo}V-OJ*6BNo+B*#~h9!1?0^q)BIKcImR21%MFRg*FOdGezX*e0r_s5Qbkeu}N&Uc-#`VlS;b0Tr%r*r{?(Oxe9a<1$JqvDb;V+>#)V;g(sPc z`ez>~MEY<=y_x!XJM7LPFAhy_R&+SltvlN&QXl*pZ*X$bN%t3a=lBy6ezS*M&AvDi zv^YnnmW{5H)_VZQT{SGlqreuuY*wg_dm)u z#>!SDm4^}nKiX@MROdNz_bSFSlh5`WHtY}KgX4QMhr~t2@H@LDXQn3mA)D{P&$n#8g zFVLPS#=){0}g}pzzp|X7Ca6X`3CwXB<=CMMiVZq?cQSg$*b8!dodk3Tk ze*w4MgKHa{i|`0b_FIKdraIn7zcu)e|Abs{A?>C<5~1Oh5D<{w<{b%-Y%kT31gUVi z)q(j zIMx^HjH&jIQ&Mi42Qn6O(%4C73%o@Ofa<8MN8n?%L-s}OA9wRfEHu}2i^AEJPHIUF zWxGOc1-eF2*_32TW=D+yUKL)}zrbDZmGr@Z?OIZ#X3qaGMRviCJ>eFU$d_q8r`Ta$ zl(Zjh71e8ppVjt-3*CN-4T~#ZH2^MZY#f4%Gse=?X{EcxO9j<$TqP=CcmGjBkXbG{ z^$zi`&3xb-Pk^L#`vf!bWCcp8KLOp?tkx%(~3jxSHQtehi#x!_Bi-Ke{_QTjc_eid>F2*4Ka$1r1IGb=S>`?wpE_sl@$^mSyK9}kX! zXhdg098azW;;0~q2&|3Fv6}`@StOORQ!l)FLK*3u@?G%QA`X*3sn^Y&cqWg5)yuXS|<33Q@57d;Fc z&2@FCZahApq)T6%*ID9-DSpqVl#&#;ip+Y%uwf@{ZWw1?FT@{Xow80nH#)A9p|wju?=zp8;OxEUD${D9{;!$emqs z=cS5@diaG38+2%Hm^fEO*D$;kc;>G3^a9SpH$X0=rejM+c0AI;VT$ATG0uItcbL6- zeZQs}N88{uk$yJ+CfuTbuLda1O%9GmR7 zkYLOdvBNLSA@wNCKtB2~osM$wNJl13mE7hO@<~zsh(m63jnpp}iZh(r*=WnbQ4F&Q z8IR+m0H_`~H(xuiR|H^&grboy2E*~)?T-GSd5^@%QGs z%WOxpug<6e7?(aQ2Pxo$9bY?eq)v(Z>&q>bNWpQ;=q zg=?2Ovx&21A-=Hu0ZdtLUG@0`Wqx`j5(%h1)n}3x%5~K`p1`NEnA_Dz{98NJv1~2! z+qvOFR_x|v4%X6WbBHy;oHe*-X;*M+b3aLyvM01Q(|ZgJ0MsDoJR47CE=Uh1YoJ=R z@_Be6dNS7&sAl;d(eu+sLEEvY&^5~L?y#(NwMIF&A3fwSwWUz2#K%lAzM=*0ze5~r zPdPr;T~-wx;6QJ~^soF0lno=;4_L`~*VTr;2LRxrICed^F!zc5;~IWRez|xaUf|1; zlfcc_P<{wA771(Qsf$}abDgi0o=*3k+u3JH*uvrW+{~6vDs~BP=64koiR>H}T&Fko zf~tfdMe`CjpTWqBbsHV-l9)r&1YS@DU~`prtgN3>Rdpltp;ngqoKf0m*j zD?WbrOL|XdZsrmW0z*ktl9vxn?iEyvTAsrZ!LH|Nd|plWuc_-mf$nQ-hepB-bG{bR za?*d{d&msgm_{TbEcvCohn!vLnptyKh^VzC< zei5r;@0O@VQvGV*S`?0sa$%?LwLW%}K&Q7SNvn?l6<+;up}c^P?J?V;JBOcosRW%{4^<9u&b}qTs@vuj4ydKo+B~|Zs(pp~Pe6>2SJO9~h%~0oFBo5 zQ!cdWWa0|cCNtF*MJBuIUNhGT&z+nOuGpNR_V)9hACGL95^6I-$K&o&Q^zw#0~dv# zxaKJv5BAqTt{@PCsS+nZ7lGX+4vuXSz@-zkGO)KbVG@!bezUcN^rLfg$xODl%P+%q zb=O0^t0?@2>q+vbU-GAYMWS*u$6;xPIqCgdp07F9*KztW3p$j7y)th?Q!~kE6w@tr zQ$X#N#f5Q$uY*mya$fEPZ89P?VjclJ^x6GZvWi7g+cHywahMjuxZ{?f!<^*M%LU7(k*R(>?yv{7%OpVtICH55yW$MUH2H1aTu4`bi z3^I2J<|MII%|wjjVx7AQd|Ye_$pv2J0rd)x#7zmG<&5U0G7`Jv-+uRs1NeA{hsN5z zK@kzq_p9?#su3H(C2AG!xQWhMEvxw8bcGzAH?IOGuJz@P{jAKaircF)r%dko*V*5JsosK}Z}&npzuc}fhEImZUVaTveXON9JOM9#&z#b< zt74NHdZfvPFa55ch=u4HT9`O16h4KanW>f?WXNq=f!Q));r9mm3MZ{*ypQBbB&(^F z@zJ@p*%7$>(DGEWqrE||q<_|i(^PLpuj}qbl`sB=aLRS5EdovK(D$%kd+RTD1@HVa z`s^n;<>oHNZ#>*@$|70Xt&Hh52=EDikz*5fM2$zea!RWKNSLyRbGqp;A|(QSDSA7! zLA+TzgLiJ1t$x2~=_tdXZ}jw3R#AD3x4Aji+03HvhkRO${A^P#$Bj=#<$c}@YfS%I zOOA$Z=scanvy|W*r7VwyS4;~x^2a;+PlO!;y+(>0%f-G_B!5oiw=!-nyJDU87eMcS zB#Kd|#%OC`K2pEEYa}J!OIYDjrbnYybDvh%X}1+D@9}H%9ZpW^OK#Xt9_$`22;L&3 z4=wrEEoaMq@Fmm@^!aWIe`uR=DR|?;)U>P<+-GTAF>Kb}d{lCsY}Q&LSS2RLojumv zKJnYwV_>q)R4qWnXzldEL=2`A<%TJ?R-;BUP)!ey5%ORNCE#)eW*YO%-eYUqUn*!r zLH+YsV6fatt-WOKX7A97i)bLa`)MOO-5ue zu}h4-K{F<%+rP#z>)@nnzvy*%*XzR@lIt!{o$Wl%ZVgH~-B|r);=+yneO!|C$as3s z-?!j;-h$Id+3>r59|urf&x_SjTo4G~ht_9KLQ%?8T(pa?V=RQ``Qh=y+x|S1 zi!!df*KMXo^;8P3W^0wzME$6jn8o-jJY8$erY_4?o_mi6qTmlzX_>#AY!|`qS_+!+ zCi;J15RH}%`*HWz?~X}1p2aJYlM5MK`SpGjTR9cUvM8uHKg zoxecFX9`WAoPj+_{q|FuOV(8eS~wryi)G+eMJ$dmv2%RdxwqY2)4wlM3HNo?o%yld za!T;GS!Y*%etV-n^$%5#M0Y;Q=sso5VYYgPu<%G%@u9-w!B%;?_lF+`UXr#=?Banq zdVud6XHIQpJ{1>Lw(wx4!#KZ~o{ML|wHMc(9hhBpkC%~6UY2w29vV9y-OZNvYPc{t zB7emhumbL8BRuhAA%Rf zgW2y=0p{L=z&oF@6gDg?EqvX zKTPh+*DtzHY?7UDlC<6aQPB(xFPvWoC8J24$f5Yht{kPscnyuQU|FR-D-O;#EAG9f z0+~5~v?N3kV`)*z9+>)%i;p}=Sm5GZzILmpy z!&8$Kz278msYjdm;_4PI*CZ%aN1uPXqGt#X;|L28$c+jC)gzkM3=pK z&4d8=1-0dDv;)3iRrHW`Zpl|}77VTX)d>Z2!pkZ>NKgGq}&I@Yu>AY#t)=+_CA#oDn)&Ip2euGnUxPQ3b%KZh`ir3=6=NwL~UmaRyuuDU_8gIVrMx z6$q5i2PeYO+X&Bq%E-=iAy+c~2lcB^2TPcgf^Um%XnMMdu;}%^)(Ik_*wt}iw01FJ z%U$b@`;7uoe36(9k{Szs*+d}uaVwX-;*bz}Bol;QKzUqv_XJ02=W_gk>Kok`S?Tqn zeAQ)PH9#g)G$6-6a4*01`JHdhY3*@9 z@n8`8{tJahoSI-yitXEMtrSv;?j_%Y<)v;c{q~u~%C)l|lneX)G?CN4fPS@yQi$O-|mGEJSx!Jj%AW6E(5z0001kvIg?CLbUEh4;mw$ zB9y4GjPawfI?l(V&*K0J0|VzpXD$C31FzS09lS*%kEIhAlZtg|gvA6jsfy-o5|TEa zXWQ#@jbUCYp#jJ(2tAHP?{`@gf|&t~-s&M00%f5Sec<%`+PO75mPbFkq*8vS7}Lbpcy^K2rj@{h*sV;Z~hcOCfn@7uQjS(||=$-P#I^uRt;f__9cGPyL|Dhur% ze+xkLq&yy5%w3K)9z<7|hf9VOp1`R<;2g^zEn0@mwIp zsGC221w6J^d#l2wM5WwLojQ-lv=K7A(7?mlL6fPk6&&f0Q!_PMv-__n^pD1KMK_BI z>pHy6zqBJ#nbzmgldaFyx?mRvwLM=nQoeL}J(((>;TH3y=PFpEv=YA3U~o3vO5}<% z%_R>%r=BI(n6@?8eF&7gV=&V3*@SbrzeZEQMC3BcK7-}0Nb3419*>FX?8Z`HL3vbI z9KXJ0B9{5m69!R;tto$J{%%RvPFZiqT101#>EekW()nkvglo17{FSqzyHH@MY3*6~wonL@fP$uPCG)4TBqn6LO=+4gGl>IVD6?)D1W*wI5> zYk}r6arw|gVHRVI9O2^N>nCO0w#k@$&~3RnMS)9iZ245v^U4-YH2diRWHEI#H@gGg ze4<+{{Bs~Z^k(Z&fUv5)T@ogVr{z~_TOmrn?Q^Z9`tL=NisnuEjLel@a&{+gGsylxdkEKIL53zOu4^&wkD=K8{TgJ(H6iYQANFtkaydVrB?<&3y&5H93Rmq zf}EGZDL{cIZ!%8#$U^U^5X-Dr<6 zv?hviy6ev3&__WTm-LKcd;1Rfp`xdob~j47F)Bi(6>aDHu)-2m@$J!dH(&$VYjX#m$A^n;H z1-Em&ZQSbDB2=DOQbg6?OZ1X!NDB)cmF@dg3DM3jA9^f}{sMR$NbNqZecH%Zrt8{V zeKcnJp)1*?gN}*4wmaYSQFGA<(XnJ!QjIzlct`eB;?xaJn)rA`3FFwQWreIS_aQ$$u zv+hj&PrVUwJlK0*0D#tM1?E-XQU>^O0j$<`apY|DR}9WJV8SPjXgd-RcDcJ#Z;*Y% zU(93JWSc5R)+|PDLzL6#bwUX^Y@HpM$yxS~>*`YVc(U@uvntF(+o9~ekHNIF)tf~>1oJA zWhEruV6D1C2wyV4tl{Ol8OItRgeS8P?RC;{Ep&x;88RO#nz>C@^&tT0O~Ml=oJ|B~y*=e`#jA#ROw$6JcPRdM~TV zRSkBYn>P&?IJZfoKJ&r!n0PSeqriTmY>3%V42p)THv@8b<&yZmAza!Rlz37@HR z=evw1%C+3D!I`K1FvGw5h{nb}T+bd&^^D_Z1IDP(KxV`sYuoaRvT@X*@&(d{@q>uH z&{wNJ$p^fxW;j=p=jL_WqTeg8r}}(8fBW2GZ%0qzT2hFk&sVlHEhgH<(1g^e3-V(U ztX)TsY+UzWt8cgIgf5oH|K#G+)xn>o$2UFn{gbXWXW&Gie379A8ygb&_CfTf|EX5b z5EaAUWYSK1bEb`&$cR|=xDA%*a>;IwAz0G@sd#DlFhre z0&`irV}+6Z*SAXZvi)dv15;s6mmi7p(e}5tCuB@Tc{rs zTR)vy?uI?-bOA7LZ(bV=B;@ApPf1~Zu^PF3*t!+}{`(OlY)<~my%LgXO+`76_-#38 znfJ!GJ;gbUO4j^x-R$Vw&&AcjS1~W2S+2>m%~M53jUKZ(8eO>-y(JLOEHb@t#)~f?I*D$h*BhPxVYyOvsd&fivKxI zedgr-5oE+ljB$Wr48yN5DDs2Y>i|GGSRqH!|BZ<2n~Gywr!+m6#qoc(X;9*{rtk6# z@!6?uOk60|R0q+SpCoJO&B3X(nZ|!f<^0?qOPsxf$&h z`C)1&_#~U>)5^V=X9K+is9oY_xVjw2rJx%xlh*vb=rru4GAOI6^u;(I3r}lUYG(Qd z|EL?%rNUUaFBmW(`s>}qI;^|)rPs)ECP!?km{Dm1^4`xvJgB3D+u8>AX>R6Bhex$z zi^rPWt*>RdWzODkg}ppoa{tS|*tkX)r}zMg0&8lu zmMc=nOQE;xPjFIh*M8kvd#2n|b?ELU%<*Yr!)ruP@L6^6GJrzEVBFw7NIIQt$5x0U zPs@_WqYXFn?&jY9Fn|5X*jhPn(un-K{NmB_&9$P;h-2BshOn^7y1#&d%#o^R(5gUj zo}p#{n*GP>hWfzII?EWB^aM`JJNK{7>G0g?-l@$yVok7ZFUfRVkL~_|fK$O3n)}Ie ze}NmV;I=eR`--Oq1JmY)TcFZQ1O6uFe5*4#Zi)KFiQ28Lg>??nw!5XBLuNK4Im29|j|1N{x!&o5XUrfijih~1qj-ws z1fkW@=9orC(hg??a3bB)Tn=H_WOm5(&lvM#VK=Xpa9mY=#LlO(F`b5|`+Ju=?d?^3 z!e2Wgd4$J9lCM0*Hl~$$j@kDk6fBobCK7^ns?*X*j^N=){-9%`U?rgOts--NM}`%7 zvv;U6hs^-UaM`yae^+j&diVQknUzG@UPf2L_au@bfk%-=STQo=_*N>4NMm^aU^tO? za?*UP>G_HpeBxS2_XuP=ttWfp@uhuP2|UOuIK>h-6@%0Pa!9yj?$8HORrZ?&wIlK9 z=uMZ}q1`AVhIJcZcUrA_m`hIJ->wK5-vH=;Lg+H|)E9ErWu zU2%8&evUz})}+py)@^awi)M+qdO5@w(Z%T-%QAC z8#$=sUbhv+3$}g;qR-e{*^BvnvvJ^2`BLXyOUm}g8G*&NCVCXu7?ZU&Uk`&)vQM_k zj#kl{G6O@~w;&SEcVMfwH`3q<^l^G}>NW-oP-kRRY$Y&AQm|m(S~}c@T6zPMws&GHquT2S=eKXWHQeji4smDt&sphw6ZTD_&hU zHc`^$<=}n(^!xWlOpf3f`#Z;i(#*HPhMDUP7VyKIuGIm10675bR>66@ANd&p0Hgk; zW~o*7Y+c`*y-lnC)Q3;|O18O_#3%)>k)2Jx+gaOJZsttk@qkfCHk<+!+^>+))3xBx z(I0eTLLhkO>(3pb8X;E9WuH}rOv{2L;sBJ2(oi<{lilTxRIhBQKYd7k<5`E}r-EWl zAA;DE)^{~&;NVs!3S9_xGz!zfmBk|zSS%a$t#lyF^$7>Y6^v|imms&GdQqkAb2}10 z)UBzhp~|qatE9?RL(YAdmj?%CkN&anvL`zG?nvs`yGRQN7?rAFp4!qSes45FDS2JV ziJP>bQ<*N3pztUB46|rULu&wn+yy-oyP-H|#Lfm+8~_;8F&X;=mISx7!68Hj+CB1~ z+jKvB((*#FEhgIl3eFG^F|-j?SAfs-Hj(nZpSG-Sch5f5aPh>q34wnCFV*337}yK# zGbL{L3FLQU!Iaa6|9bL@NMv|z{gkV{!rwl?C#k<<08axqqJHC)PuXc@$&EyMt(UDZ z;Qlp};WDNd6)ruRy0MG0XR@{rJSOGTtOwQO?0+VjO(Fgh*oIp3R7>Z3Rb`stRI`_1Sb(WMVSy$7;HooH2@=CU;2k|4~9{i#CTYMqtco4B|lg_xskz>s=%6l448`2^tzk{%McuW8xW^}m3ns2_hQDDo zVvpRK0}+a@Hzz)X^IHNb;0+6~6wzL`$%=Q**9%T14n0qzp<&{UZ!82VI@DF_u4EM+ zIy>M$?Y?#awJ^kQT<*<{Xa`_X&_)0Xr-%HT^77AYn*6C^TSrm3S+*veMtM{erGgbu z(7c%-J+4sj@pb6O5NA*egN3`7!-Etq@XP_03jj3iV1Tbkh96B*y%o=H}3+a0H zXlUF}0rSzNP@u?4l!;T6gWFF+yKjADdgz^MS0Mue08}NGN4CKq=YR!}jBjp5zWKV< z(J8@E&{l97t}{7s%DWFvDU^Er_tqHdI3rACZ)!Lqm7P7h5s3!hG4N+6CMGaYqtzn7 zUO=oEc;9vETF7c!Ut7$2dUQjd)Le@*6=^EGRX^RGfNYKEv=ha|tKn%Q`OHij)DH(h z5kS7He76xIRsm;77*4|#sw2+Pn3Uz~6%mO>_ANa{X0n-1dmdLlCD@Ei|WnB0+{wpm>b5f0z;`+l3;5pE}VD+V;39x3uCvhn*p2i{WM$=zg7r-YhDSxYG`B zay8;LxT#+1eGzzilZqH}L(JYL#a{B~+FC(w$8#qs`*FAV7!9S4#P%XfYMqPx9}54R zcZj}AA$ktxx%$|LVf% zKxC9>eV0w|nOZ-f^RII-ePHc4Qlnr12P2>W91d7E+%}j7rBJCE*6niGzL3tT{l+(* zYVT6hC`eTZwKGxSqhk0Mh(?WUW~SJ(x1r>RQdMrJKORi}PDu7Ag`b^6aR~w8qumzi|?#2}7BN6~Pq`<{f6 ztXBP89pjY)GQ6+;s^g=qs;z-D@k85FF%j*B3}jkL52`p&4BteJP76_i&DtT^%GJ$; zF|mO8r5=I_YKw%3w9W?v`~{vY{2Bk*QR32tT~0q@Dg?#- z8!GK_-lG^bzCLn~&H(ZxmC|Lq8(sQHqg5TsCBUo%@_weKwh;5rTFEAcJKJjwLi>js z_j-O+7dT$js*z^IQvEb@54PVUDZ(+Mk4nmFNkDnG6JOVc*Q1-N% z(^7rU<~={y#h~;``-+kl0{tu6SN?UO6~ZKwjH!w{-iV&xUov{7KhFiauaO#cT*Tg{ zm>Xu_&0Fiy7fu9#o?qJ!eoXptfjrEZ`$fP=P)wriG{0h`xk$snPCkSBn|q~lCy~># zun(~`ubV|zlL%=UVs~E`}XsNrk8l!QhZtnD9%ZnQ3N zm5EHHRC`hxT*Bh<#bj%HJXiTYqu_zwA@<#ErRl$2GqCJ|Kh6)Seg?S7S zT~>p(u}IW|n}mg+(d18^42ao*>X%5wXJ%#SD$3p3RU9LI_T*3Lx_Rv3W_&6NjmM+F zuwUlmmxNMr;e&&>easlzTJ267J_W}ERI1T04oGJU?ZTXl@9yQ0DW5of)w}c+5?ETr zE#@@n5WJ)y&+rpJ5%__dh`@9waEc0oml0XP+lJs(M6iI?|E~gpf>#kQQd0frE+Uj3 zto#BY1c?8Nm13a40zBUuRSp^ffKJF3f&hRiOF(i0HVeApg)Z>Z7l07d0QhPgcNh4Z zX&%fzz!e!RkX`|`$pD|GT;+%*W5LRCX8=48X(55>|Ty9$3Q9}b%Tl1U@T&Iz5x6xpOjIZ67mluXt zK+lyv*oPwf;YXW1^XDx-D_y$(P!a|~)xy6q?aGuRfgI->Cl_)IOrqY)hrLGw4B@mW zd#eAx;Ss9k0ei#42sD5s3BaQuyHkqOSn!qQUtM~)=uE#Uaf<2nL+Ie>3pJe!U_FGG zoAmhs|H{4^It2yfyhcFM13$WyHBx`Gq)Mu}=46oNnNzV00I>O4HQ?dPLE_i3RfJ)3 z#`~MHH&sxbDqfxJi`f8h`NR>p6yZ4aQM5DORLicT6X;C(H#^_sV^O&OPY`|Ik2v6q zs^Oy+m8dShPptMt##l3Zd;R6MH@95f{sQ+NBmVmt`704z5N$UN73-qAjD(-{0V+wR zC1XSHfolf?05i>z#8XCC)ZBbqdUntw?|EJpQ?nQZdFjDS=S4wZAJ; zA?GmlRxHO{;Alk0tlOO+5Az{E8FaWxfxeiYstg239p7+xD>oS&xRru8FEy3blgSZE zO&C~sA~Peg7`x*I-W0vF_7gJeb;|tFA+oz6x9RGFqloy|!V2wKEwiS;?li}6C7U?t zdw@uIK&RNXAB5D!tj|2USRnM$Mtzxdf1e=b8s(4{WJtJ0fd(4P8%6#QR^08pyOME6 zpI6fyMbkbN&s30X(zGjI{&=*p^q)`KG2w3_4ltDG z-x3UYZvA$uJgt!#05T@08CbhWMBCj^Ma3UpB8#zk-oKary;2$*z=N57l7zTsNi!B37deyz=@pz;;HgDd8hH73FK|ZIT4_8Z8{b0kCC$ zH_uk>tp>i15+?oxus1(V61qG`_4J(kHOOk!Pab8}yhA?(027%b@WQaqaoJ&*6uKnG zPwIjA59NMm$yi5-DYGCwU?NDYeU28eSmGzMp32>oC$b*Erg(WUEUE6=ju1U1fbm@c zaex`XlpS%X4lkVqL*!+3;8q2E;>372qJ||zmkVIJt(oPFg#j34b~K0i5NnM%Aq zd-GeskgJmoAUcHLrha3{778pcGXN(3#~gXJ_%oGR;3EFD3~P}D$-D3NH76|UqmhUA zFsaggC<@j!e%zqJC8yKA9)h5F%Vyv`;4^CC-Od&`O@%OgmYM3VpMAIC@m;~Qsg-ql zs*_FJ*kMCv+?`G>|J$AZ{U&5JHe#f7cBMV*#5J4cAPHdVGkknk`2N!St07s^XE$!& zAL-~1RJqP5rp$i)5mBN3DG5}vkQKq(8 zZ>!-|Gk!6x(*`J``v6_eDWeKT;l{l5SwnT$&6gLeC?7pZTyp4z`6uzu9agFmhJZi9 z8^CzB@>%9aBjN4gRBEK6!-VONL(ZT^p9$7U#;EVux!tv7j%R%qrXvdg@+VYcB~ia( zck)%e<_te;O5a$J$oAPk1S8ti7uS4^FN;x9midM#iYa7%ShwkW06XDA(_aC7I`#Gy#fc~XHVYESk{APNGyJ7i1 zbD6ayUUCMkQ6^tio@FT|N9wxH^JZ{oAv{Y|S`>;zR)O~ltoe1Jp|qn8T|41QpBCk) zC?DddO|xw>u$~9M8fsQBNz8NaRmEXi->6>xg0=aF>g3hvL(;=JAY z&ZIVNG`dzpT@0osBY(wa@Q8XlOlRd(k!B%ML%OLv?dOG$+thI;`=-KTsdqX%ASu9| zo!y4vWe%3U9a3gnUEXI<*600L*!5bMt8EkAh$DNheRx3;?VF zECWOdp3a5OK%x>K06mNRw3~oyoqILo4}P<-VW|hmUM(IT3ovCcZLm$bjw_1Iyh$?$ zzkw|;zC-O%1cprf)&-LrWq+t^<(UxXJvg&Fn6eg#mRAF>qQM4=`s9^6;4NNhvqk_S zjtsqma>LV$9GVw`ZP3uoqU|v4LohdPQw3#e{VMHwqO0?22Me~rj;0*9QWhToK*+1r zos8PC@2zND0+=2_=Aw{Hm^Hi&w%|&3OwH}p;(<)?@;lf-9hFn~3Jfk6>tAWbAOXtg zZm<@LL=Y@&e~1Erye1|_8K9cpZZRjO0l>SrSY?yovT|PlU@suT8UfKi6l+;%ZVELl zMtLCJWHXdE9u2UUWjld8ntk8N%wM2LD!>6J%pQUu?S4(urxN3ubX(&_wY$^Ji2LSBe0SAr} zf2TX*qacIb?dF7}bVfkSF=yBvh7JiqzfVd&e5^8>goQCLkk=yhS)xLP`rRD?gYuUXJ)rBfj~Zh-H7+E-3T=QpXVRD z@sHUEg$e|YfR3&q?MEsigOWcWV7>P9{ER_-csB^dP_Dy)h(Tq-##vguw+j$gUh6=2 zECUg*fm89YY3&@0R4oU&0Am{(fk4H@Bx2%pFi zag&C9!01cH`hCyy5}^Vc4HxA(9!>8xuBP!7LUB+~rfb{r`U? zt}LocdY^9&C)%13DF{Tq)~B>!mO(60-=32IL3njSuF8vN0pXCjBrJz6za1|01{B_b zAiRU3L0W@*mp}|ig$-u%4qhp9`&JN$_#%k0?dbjzPD%;MUr?FyVDbh8Vwhk8!6Z)X zy@UrP!OS|s47mLUfpGSsQIkLLuC%>`qk;GvYylzW76d^)qJNP>_V`nLkPL#CSI;j` zATJU(8eA0q^$V9?3G13&U6^N5?FfQET19B468{tK=w-?;J@N$vYEVEAhRV1HC{Peo z#lcLnXJQgL z@%ZBZ6(%nefy0>>5QVpnfK_=Bq#mR>1=qHYph-+En{8pEQ#0@zK!2d*fUFVv-K2ez zbCT!~T>S~~`L#P={#5I=?N{=zs5TY|A0RzX7I_i zl8zyro3}IVOI#}JTcfL5@&hQ$}Ur{OK7aUX)%P;Um0V#KJWM8EpaW67zGc z1`u_i7*+QI*if5_FO5>qGJs@zEU)fZ!>9VX}Tl!|D%BVobr$YkfWKD|a&=|l(vNsT31#g9o zwQ*$!OEG8_A<}JZ%L4N{XanJ@ zwBvnN0Nw#&E`?P6KYCur1HN2$*9a<}47@(8E^AWu!#P z>coevTn5s5s+>u^(9v)~;M^W!37{VZw(q?;pvgU+F(BoYsGr3l18)ZFF&m^21PD$Da|F0#WqkN4^U902x@eqw zQMd&05^Ux6o72XP7(Gr9j?_4tItc{*NEp7H1{*iW2O%wq+crwCgF- zAnT&Fcl81lR}1hcQ&LXlQN#IBr$G)oJISqcwx)4&!+q6=iR1Bd2_C6kod9~Jn6w^) zy16z=IbX2$PBU>D@kvPwoNq4Y91};SWu#tx9fWwu(Za1G>Azzkp&s=5U6F~8#Nzoo zUVfaZgQuQkooA*tj} z9D|ygw(@LEbFAasvTm#uwZzO~%|)VvHnMD=N^qxugo~4UHN`z@Kd|Tc=Jv|W1>5m= zdv383{6_}Mbu(84{r8je+iySj3aX>McDQ&rA^a@mWi!9A<(3g?D6?_NyBu8;|+YCCQ7e!1HI&Pw%^ipjxqy zZ1EQA?Oznx>Pq~8Q%AZYysoaEPxvm3ZveAGWpyMD7oTCvb&r^jQKD zAZKgv%U&zd)1m$57h_FoU&4}QECtE`^dfQn6?CgJ&VPEzrAhWq^EZ>`Z|M4Q5CpfM zCshgo2Nh?TOefm$qgWs-cL(Q<&QBlF)DMc-l}2xWAlVjz=%;e0GB;YQczP+Pn0tsJ z4!n#<&UJErSH#>ugC>sQO}rqaEQo18g3MM*71J{DHb+*c>~*;=Ko|>P0;X|{xx^hE zqI-dM#byaw9AJK>pIXdA8~)wS3xZ0>g7`dMaXi4@GPld0y`un(I7WyH=ejcVo!g2` zP*TuX(-#Q5N0;wo86{+riiRMFB*;fEnh&Z*qZc~-u%$|@03`X!;wpXG(K5Jo7C0c^ z$?d^_+oh2pz;)r)M~xNrVrhlWraC1w16oHnyu~@}CzL?a?HkYsbzt~jxA1YxEc^9> zAS5y7Cd?;6ALe$vSwVhZNQmLCydw*~=XS$_Ac{2|H9mEc(i5?r>w-Ym`BziabD z1)+#p0y>OPXO|cNe-xNOb2+J>c=&(U6ap7M9WZ|Zks>pUW+Pa6yT1~w1Yw_U)+gLA zse(~czQE+D3lR%`9llMcN? zeZF|LB;an>u* zY^d38EOfsgSmH$etq-8^_S8M@5}aUv;$+w_T(e_yQE1pfD1gEC2^9nZ1qt~I78Vu` z4*K-xrSY*KK1@T)fXHhFeVS=0T`rDYHT5Wn>qs`OD0iU}6RHf;ktt)^St zLfqI`#2F@NB5YvuLKJpc-IYWAoblYSsbpxV)97oh5D-#%H47XUY92@X)<;p}oE)lI zxgtzVRS;)}z!%)~YGrwhe9QSn(o!o;t)bpVAEyF0-JU@dq|oa`G73y7zSpb-d4@JS zvtmzH|KGoiY<8ad;yY6Bu~naJjx@AxJF0-7_TC-F@XAPA&7clp!u2}FCqKT?KlD!7 z2c7R6%QJ({k}HSzT8kz;V?({;u9=^ z_)ioZLh&%g8&S3a$y8MwrHU_*ZdUVNOyZjbhnEVgwJj1GJ!VAWuQG?Wu@`py$(DDU zPMys-j_;-H?cZgGyvylyMPb4a*&~VE7o2!NTiAnp9T|-ZOMG>tflLt8l$sN@?5-c# zCqK8B8lU%8kkQ=gla{&B{My2)3d^tx?N0Lcsa+G5`=7Fa;<6)IB&;N*A7lCZGziP{ zRj=39_FzII$@=%}DlJmD?2gr)i(qJY)~QnS?hF32G&17;={i(c?wy z0DrtpAUeyMLtQ*jt!o=b?xjBGHddbE#3mer7r=6v+p~z*P(#8*$uKdp@CjCLC*vpk zcuVO#&gw!{Kt)BGmiEGQ1yMrdoZI5md(Njmi48W0u%{`$R~se{rwN=(>8BuA66>c^625LUn8Hs5x^a^)y)KvKO_#HZj=L~PT_%Yv>|f%Q58Y`OI}PvK87s~o4w z08i^|%ggy*xzH3R6_GklHjhA=xc66?RZ&Y)P9TRW-AzqR#R5_sjw<&WN(9jzs@&+j{19LFy6e=3N8zJoNWr^IQSg)m5}DT&Az zNY-nP=i}r1a|<1&g7}v+LUVw3ne&lH%IM|?*{57yhuD#H(Y#LetEYnC0!#KC>k7R( zwJlah#MWxalg=svva(+7;`|ZZd5;jJuV`W1XtuAT zr|u0WEetW7{8%t$WoPj1>ms{B;UMVgo3%PNDKTsX7T zPmix-a3Wu$ydd`rfSRjQ8pa>7oM`2Wz%e86#91t6GKXcza6US~n~{q{SWKW#ubA(E zJtweDu3lWVs`oMvecNN_`hZ@|UM=nxx!3qKs4|abgwaX`A3tuoR6-TUr(H}yRUEuP zlijWzaX^FUfm}4dP)#^csv~!HfPXewIr?$!#AB8se}2@10OK=>UgIwt`4lthx>&xs zwWL@_6pceovfvuTK7GgjiNPNo6?LqEMy@=t3kN%gRd1!RcM6j@TFUhAlvK1c-ulFT zS$2v4X29&ql;tpbTA9(up{`hj8T`WG|DDBYn1S7l7dYy#+kHtle}odUPW2%;3=^BG z*T+}${`?uXyZ`Q;ou|F-uJNFE^fES9c5SVyBLI)vC`OlA{4lL+jp+P=NK33ez8;0&f&c1# zLW^lg8j)sce~AS<|7Y=^=FEf*+9n#aPX7C%D#+@^-k&ooFH;X_q(0$E>dpzDmo>kNOCh8!>~@7Z*ar(t|^TI8w6 zeRew+IM&MTv@unIobGCQ*kgSB8JD@QN^_CM%aHWm&1A2*xH)AY+1!}H?H)%zLR|Qq zjKgox{{vlY`I2(+hsXUBU2>c{{(R^d#BbB#pI$GB#NHjfXvG&r-|3bTxl?R&v~|zP z7|f+Ou#!a6c%{O^0j@Z`#4J197Y|BsJvINtz`RNWekQ(zR<+JTwNB3n;hidcmsV2WgP4zD8QQsd zq{Z+Pa>wtd9Ka(sqBk@3ak^SPO>Cw9NO`-i)^-!KfK`!^Aa%e_bau6dZkT(lrjTYg zFTO@;Xz!QxE^8^ROjaReB94W++^8x3w`1hINK=*fR1k&Tg#CQWS;G&hZL!lOrsik2 zYqDBU8}aQH1Lp)e0SWOJZCPpIccQwEnA51dLY%RDq4if4MacT58oYAB_i3wj+8Cw> znTQou0~&n5nNriyu$%+=J~K^c?t@IpoIHnsyc4}srF~hY)h$dJv@7G)+yUBLXUk6a z*mL*+yyWGy>$ZioP5D>46S(+etxhg6 z{QII;%S+CSrJ!4QYB-%1mSCjaklr1AAdfi%N^*8Thh)!8Qh$ zj*6)k)Fz_WNh{Y0nfs#oN725vq4>*PRDioS{|k4uP2Weu!#&X#`}~kP5k$HODeloP z!v7jSR3754G=xJ?!aP<}ddNLeSw_;!82AjLie=^47Je+_FYiP0j@N`8LSM+(M0@Z1M1(8>z({)B*)NyTL z0Bj4XDH3pIU4>SjW7tzXb{CmojKJfeT9;n(X{OwK&c9rAPO(ygIYyXM79+xp6ov2L zt&}Ny50s|r>Qc!a49+>+V@$0`Ujg_=KEac~XZun7=`@5hx^1FWqQ`_akj*rL=X@0h zH#*rkH0rqJ__~0p0^8v|cbCdMt?~BMZ|(VF-HiC{*aimo5kUT!NBknpUgriPW%>J> zjf%dP@>IR(Y0h z!{$JxZw;x(%t_HZ^Ae(jH^HaMZ#ghUD~g>RF2%NGJP`qz_~r6iKB(*Cii)&|twlz9+>CCW+aZh0y7%G2! zmPvO56g_+w`M5?njMzhSu9={u_~Fx5N2U90*j^q#1g@u_r1Hj)>&g{nP2QGJ-C>< zQ3213xf}_x{_ZT}ZRSpjk3K_9AWE#78jcUuYL)9T3;CUFLrX?E``5vmp_MV&@;Dor z3bXn3R3(H40rRn`xh^LsCvUiB?}&b0;hY8954@T_Hh%x<($$L1N_^-Nf?`7jgbye~ zlJnRwIhX4A(A;`1Ex8x17X+%Z7FrWF1i7`oQ~E_!d?Q6Tj}>k5LP#P`wI@haHQCCQ zg9z0>mIx_nw<2DeK&6rWYu;(aK$rm~egZG>ciY1Z(MZ%kV-T=kAS2;6ivH;(P3ceg z9N(ORYNf>nwWfuxFJ_)W%&uh~OHG4yF%h-PBKvIY^*B!7$q1U3nJ?Q2LT~(@vTMbG zahIr*=!t*)6Rz{PSjX30@-Cs|K4`B#suD*4rpQ9O%{*nvR_&OAf}CL$!Eqh!~;Ly(&R~!iH@QsIX($Suwp?bWvrF2hTl zKQ|pWyouNV4+DdV&TLh)lo)f$bd`-u5{CM$rG<$2QK%amI|;d}Wm>%tYC0CZ14~s8 zhw0i?sds(>bSQ^!)3HF@1%G>=ik3!@)ThH3&)H&n+|nXM&p_3&%aPZYb3Zz_E)x=Z z$W@pu@T}5iFu)1mm&MMDIKpia{ws{Z-v;YV+vMQOQks*K?{#c=f=?pn#uP94fZhsw z8q_4)oFSY`e8BaoEC(N`#^}@cFs2j*QH;H<|6*xqtA~60>n`c3*YW4?vy0NH>0e2E9mESkymxz$a-gdGjBW*4aSz7 zyd*~)t?6y64x5ipbzq|zSy0lDwbIVKzmFx^yMp!=GB`nLUxEWFzu*#NsY{|sG2bk=??SS4_S%0<)&Df<&#H5bOgnzmb`@!sw2K0d(nbO1fcJ#d zTXA`tLwsVsA!rz z#!k7CE8~P%`Q}^dU}_wX`z-ahjrkR_tW*npAui`n;lrIs=Z(PGksx? z;QLl3>!;TZ&Wl{ml$OV{Ty%XLQrCMJ=Ii1rvk}xfke8P`Qko8mkhYRZul^rZC?2E$ zXb|)Kr!j$=Q0a#PB&Mrvx@+rQi}B$M`$U(VDjT#+K+&~o<}Cew27U7ZL)&O8nzoP4 ze0O!tsGJ6FB}JRNY;JUH>QNJ0I!3m)CvPy%>Vm91 zh{Lo7fa`^Jum_8t3p|`vLpSNk5!E5p)cum3ukPbNW&DbLjOYEv;M# zrcCc9$##0|cqs&W^LoDG7dZ@KIgWXGPp+>#Z0^;(6P*C2Wsi!&V3hOszL0t;U=DJ| z1pm~pO1?F) zglM6!CwFFMVEzO!FweKsW4tII)3zmB%Xg{W9|=NT{|@)5dv7hLq>68R9WWOjD$=m| zPNJXC*qX}EXC5rGtcxkdIGDb-pFq||2tNp|-)6n~^=mt54u3Hzy{6Vi-8*VdLEQo| zI--D%M`Eu;lchtA`rw_G_x&yMSrsCgy3FMg`KoZwxdEO(n@;gI3=G04j0@U*T%@P< z*Z_8;HHm^5Dt0I;9)|_Yoqy2YHYMpeTu-h6;c;tbs>^c8o_V1WYGZ`_$Bo zTdgQh5f{@fK@#!$89v${tqnCY^KWY{Lhrhc&=tjL-Glg_?6s=}((-uzZ7jtm z&{&-_L!V~=!k<&EB@JZz5FcS9RBtnz`oL*7kj(TpLvFT(VH%^u*X0@17or9mkk6sL z>)ynp-3FPm30p-rUAgSu9zGhzqdw`5e5ibyAVKPRG)Q8#JTdJV(g7cm%PrBb;odSs zNXGXn13~e9e=6Q>F-Ns3+#4Z_<{O#ysP<57U$Oo;w6(G>O>VOgEm$_3ZT` zw_M!gM_dM)cq+0Pp6nNWtpk5dN@@r*lI~uc*D5R;c)s4_MOcQj+ot9(OSLmhx0H&1 zmTJ>$LyS{IpB2|!*pI`hA35A_hqO;Fo#{7O0Lv-)NtW}mmbYcSS4WT>Ts#}008dAg z-r^vTaH=8VJ1oJNFp5?b9QbJ^e{lUm#}0p*4&X%kF8kK$}>!jgT_(pd<5igKJ;^@mseFm*{T~;$OljMDIo+>XEl0Z ztxcyl$>l2+VPoWDIpXS-w~6u}J}GqQXqI$W63~5_QIeVv*wv_72lJKSO)N{l_W7Mu zBPdU4Y^8S}uf@!_vR8qiRKc?+-R=oT0!{fs|2%Mv9B4>+BwgQgLMy^Eol&`o} zJnQcoAJa>4`pqhXWNPro4s=&lX>;RmVl$?gEU8AU`&KLIj6G?xj9do!mMcpf%bnW- zqDzOgb`eTh(2OZ0XrOy6_}UJ<>zLyua+R;*l`+_}BV0s@4{h$irDU>&C8_J`zbwPY zaGerb<-sl3v7Y!nI%uVxgtNS1i@t6sV1hsE+Ph$C3$r!E(ba)aEV*I!{TJjZJA@Y| zsrVnY8y+xNQW6Pn;=c+VNN|?COa(iri2owLB6(`vet)rdq|-|Umg+Q|8T46_Z`qa84GkM4-CTtGx2g9L<>dF+=+wQQC~ECYV!Ej#d?+=M!-dC$2(}aI}ka_~jv{W@V6q zC5Cy^x53@@phEEGYg76Z&>Is;<>r)Rl^nq{P6`@WoE$E+Roqfx!ZJBI4_K5$m>{kt zouv^cdfKl1o`W@20Qd@w^{!OFCo!FkkPVeu3>K48B`9c^uHqKoh#wEq0d{LHS6Uh> z3lbN)P^UtLB$~%dWMpKdeOtp=BDbOUknOVWMzQbYM>EMEmX4?$$KK#^w*m*IRav2R zIu@gZRR(W`xE#;+T-XTIug-+)a^}D0FF?zu>kt;I=eTp5Ahx>4&r1zY-IZy zKGxBGFWsr)_f+y@vshy1Ze^?pT}%7p1DGZWA>5Q)dEk+gQ#WP{)~$ogK`wGM8M6ip zED~72OnpL;B)+M^_kBm<-96~sLsgjGXGYZ(7rk3Dv1@_bI@$U=u=1p%OdhjR;>IL= z;zy4O)8-gV>mQ}m%d1)OccmBkP4Z&Grx)v!dvS2`{MN{(4*RNeYTn+F0WiQ+gTZ-ZqI>A?uqLyRulA7+6hz!m>`(tIcF{Tk*hdFgaIo zH`Ac#qkUy{x>{_fc~^<2q(=Vb^FpM#TQiALP%5vOcIhh|7k~fu7^$}=AHPs9FV!OF z0Vs#jCk!Dfq2nP{GN}Xj!Tt2MhxRYTelLEeDgFITeMlV%d9R{ny?)vcoa;m&5j?)Fx&L;mj-8_G`rr#s6B$q6E`CIvz_HXd zTU#K$x+{R1Yr1q14!5$QCmL347=s7BqP&SdgZ_h?LP1X;uJGwV7s*=e2*SzELp4Po zIV3wF13oR6aTk$#vZ*&_*L~>;ThgVHdoF$&{9EeWWRn zgQ-p@Q>!nn^Y314`8q+wW#L={1a`%$iAJuhQ zSJ4VaIdPEg=XKs%uWA*N=?vP?h}!I zN8$*Bl3{_Wlh!B?EieFvc2z1Z?kF$6k4zD$%oH#F3{pUmdyJ_vBMjQ&W}`338kLhx zRv?^Dzb4Xw5D!;*n38==^D$xiCRuGNUt63rqbxHvK&apPP{AWV^#TeA15%BCuF=*( zjK6~$pt#|<39o8oqvL}_bfNq-l4*iZvQX>ZKu0TaSoDFlMrz*-uSQw!R55R=sK`F3 zAeOkkr^yt|a^6N+Ej&TIW)+exWu<}9l-HIzoz%zU4#jb%!uhpuAqwI_waNnfpFdSq zo~*SpH5rPMLYL$Cznn5wQ`3l_nVF)9p$hE%J%{w&^eF*8sgF%({OjbMl%!dSZVb9J zSN&p%F6#_)_eNELerNFo<7DG8o^bSEkLw?cMctV;NcW1qw8wnyRZm%<>k(NgJ;9A^ z_jyt~-K49&uOzhaHNuqiu}*ev=6XJSKzoPiFAK?SSK9O+E?{ewS`}BX4{`C+zlC^E zsACXNBj1+XX1@R{JB)*DPL@Ybi&a6tr`fg~mcVxRDrT+YJDu+ju4ybOv%Q+^BQ9+l zi;9+yfdvKACWZ&?2Tw&Co8i5$&NwWBP4uxxI=(4Nk8k^Y91>6d|C0)jczptYN@)I< z{AgMp6J9=XB;j*RaUaWSAdz-P@I_yc=%D&>7(T1t)JZQ6%Mw@6*6{KjS|AS?~->*j{&9`!4?sq95)&doqO^ZcxYgNs(6IYdHG-M z$zS153c%AZTnJ?PWqNqz6aA8Fs0O8PgbgJUv4mmh5CY-)KK9Z>^7Ag&JTygvO~~*y zLsuL5Q{<*j^Z!Ch|0nc?ETj07;J=XiI?XSk=|BQ~pZ|lT{7>kA$Z*Q1h|Rxg{~P(P z)OYXTopA5`F#r1$o>k6U%BXRX-nI4s`oX1G4Cn<)c_Idd1>MDI8)3+GIP@fdrf;t6LtO?u8e@OB|y5n#v6FGm*%0R?>`U~3IoPKwA~ zDB9z!d=mlQB*QdkB(S&U$KGu8Q&w+>6CgO>G{ql@{*dBgj=^{nKp`#qZGRT;85FW!=Qzcx zbt{A7YZ`oqLT0Kddu9-!J85A%pW9nFIIm~4V^iDp6nds6`3%ZQDmbx!96nQ%63B7= ze9qE5kJ7ZZn;11KBAnN5IZ+g7vbGs z8@pU&tFcp)IcQ$cW47PA6bDifKI0{8z2kWE$3G?BX99j`4@AQpnUUz$@>r(SkMpv2 z@X}*1k6yy#;jb}-=~5( zpocP}v+FbA%@}x4anZ5Y@kZoI?RM=_CyeB-#YsGibTvj&keRwh`FXM)Zg?kO}xJdfR!Q%AOeR7$OBqd_tc> zfqjx|z&oL`Z!Yc{ZaVh<#QxtI=;`vP^B}#|aqtY<)B%p5r~$mZIlb$+NgVL`Q{ex} z^Z%A55;u|&#jn=+o8w%)m`QL~Pmz4^u-sAgq*e!e_kZa(QC`k8`QR<;JC3D86-RqT z{;|cL2^SkCl;3F#44;M9O6|rr3vL(qJY6?pluQ?;@;X-!xlJrTew>=Re8U-E$0&}M zVrcC>e5|(U@rd{0iW!<90vv>wsN~kN#f2tfE|Fy%7^ODb42N)y(_48MC}*<$q!;S~ z3e7hIC~=yAH`A@;JsQK#z>PxBJ3}0UG(NfJqE5Cj+mI55vIZ4Rw2(xcK0clSH+lj6 z)DP!-HV=NS&Q+r{mJI0Mb_;3V@W@zKuTo(?Kz1WYs{}W4PUkVrtuJJJobnUWS1&V^mQkU%&nL zyZ{Je7Qa**71uI~cg}7QF1jj<@^lRmNk%s2zS(96>idS|-)Hug|6m}0IV8!hp1`0b zBj{VMO1O)KooMj$8Fa`Jxnv*}C~rska7Bl5rQP8kD!4h(7l3Jid`H& z`ZSBbW;9bv*mB7Z0MRwqWZB$Ys&IMnTldrsUJXhQL|wOtlE>hA0X@CIAQz++SU~Q3Ynj*rX?Onk2!HS^}bg%j?!Y8q9fBj@{Da9nSsC*Hq(GNIesc4S)P$pJ@de z_L9@1{fckvVtK;g@Pw*9ZZ@V7u>>h|G)h>0pFHx$^PwN(A?%Mw&eRXTJur8Jv8AUW z@`FVl3S&AZs(e_pikdCN;TdkonR5bTd(8Uvrp*fZp*lNaa0BNY_Q9li=x0s>g&y zisep}2MRkJUII>tb;yT-Kvq=G_zFiut_WhVzjSEb8kMTR=E2>J91doWmV_Wx$taCP zuKxmso|#(xj7Si>-TIZ*k4mbstKtXFPMONkzGu)tDBg%Y)0W34V0kryk{6+RTi|22 zrR+J?Cc(O9pWkCn!(EC+i6W1bPCWMO&8(#<)J*sOn=ThlP>EweLdqt;QoJ>nhMETt z8Ole|F&Bwt@cFy>V+W+DgG+1rKc4Tz5ZU89DvV4u+{IjHeR*!Adf)6mrg!|t?cXzs z2#k;u49-r<-xJl(#$#t}j@-^u|02wu0vCFt<~+2&**KE)seQG=GI0={kd3P;a2E~Z zm8f|PQ~n66Q`emHGWCfbvQG}$92Ja$S7gt;B&>CNjcn=xp|2jY0`+QLU_}Wmw(wuE z2W*{N=UHa-hChR}s4G8xMoI56hw(0re!xfq<5!rO9g!}pHr6f^lpyqRh?B_L+9JdJ zIDyghQnox))Q1^?kHs&`b($A4(L&xVJg4Kq(e+%C4Gl9gUnKg z&Sc)Jcvu81t2y}*{8y-N`;T4#^Ovm#i6NuMcO+w#wAh(Ezt;w{d+lKPjhnw`j6}c_ z&<VMi5|N=PJswxWJ#v<6}zmz+QpuRE+!M!jJ&HQk!IY zJGabhV|kE2((Xik_H`0>12R$V&C=ZJOu6a2;nJZd*m~9n(`aNP`W`!IdZo@WaaoJ_ z4vZyU!v_@Uac?$oLE+F zlPH@77$-~(SYIgxkEpgkDa>ifLJp%GH&&?ODJ@&%|zG~;#4p47y@v9_#}Jytb0wJneq;1@OdazY6$)s z={dxf>$cEp`nsB(F0MQl&+|AZT5cnOcDR#v*7-?!$|6Hv4Jy~dT@+uKgvC{!lw^52B?^vZS#V1h_B9yZc{=NdHQSmV5Vk*?d zBu)AHG5O_o=5o9O8afYj!>}Ob=97CY;H)0w?6eZM{UMLh6l;H_O~jsAp4twiaf;L? zRF+Coa<9nyVVWT>sO6`q6Y*c+zu2!TU_&p$ug@SoRI65s;uXc%fz2YGdZahqqUT{n zjd58kh~^4A`36=Oi>cv)&Zs$M1+fm@$S`)7a=>u93z-nWN?p3-n#ZPBFiyy}_Iib{ zX^o8=d}$C>SWG@|klZt^#01}elD_tNdPKjhjd;LIvT@;J{Tg%mbMz7s-oP~c+y;gX z+M`wV86C4uDt*UM8xQoi(e$llrAkTO!9_3q!FgHJ<=K|$Z3>D{BJr{mEvY_L%KA}? zX*DYuKdWOU%-(XLyq3;;T@W+FA0ta#Y0f$FDCB9U=z&qiwbtI}syx^DD@RM&hwk!r z+eh-(*^22?{H7~UDynmP;srCo>fnLqG47N)BDz+$`f8+@>!Wtg4UO~G9Rd>u+k8Z1 zqLrt?w%Ietf?=^XRdnw%Bf4?+HMv;c@fhr$9I%~zQ9jGka6m~mM)kc($MREm%?8cX&!7zw(X*7phjt9R#X&2uKTh|17!Jz(guIOUy5oDb z{=3&fo`gdh$QR>(8?IbB|cMYh5;rbdrKzX|yafmb&}W z!Tqe3>{eU-f}3xsIhWoVX}WXa`_^^`eFC?H~v?AuR;H&@973IQ}rvaLg8ZZw92 zIz9PUrf^*^su198orn-lIoq)7aZ*v%H?tJPaXC@BNquX%n@qGYjd@iw-UcT47Ti!} z_s zdZFvb+QK4;%tBCV&fz)gL3~w^?PQoVoPo)0pSW=2Ynma34CC5>|8-rzZWDRH)I` zon2AZV`h#pPpn_i@^C6LjvnJUpoNNR!#luvJ4D`I6Qkko4R5V4pa_r9ekgsyhw^1# zRWY*A4L_xd!6peGRC4Yb)F+R1=m>~KE-tArXEBn^4jV#}9-q$YV!RRc6I%VLGVOTe zAVQ)`nD>b^Ai<=bWI~foe4{ak++xk7eJOB$Eq2gBpz35R6R*m78*E zHM$gjnjs-6g;tr;zDvKw)nghYsy@^9DJ26gPMbDgDziXuVhEXEbXzR}%F(}vY! zu3d`s!z0dBsmK5^C@fq)_-LQC#J?tlVKJ-7cEJg=>waRTipOmeI}j58J$&z(7+-lt zY%KAT^$g~1+Fk}7_=xySX+$@^!rWJN6weUG8$k5*pZ<;>jmHiV9#i!^o)qcmOP)`_ zBm`Wiy%0kXq6r?^6-WD33wWUPHLuML_Bf6=@_LF(@L$RBxX(a`i4f$Lw4~2x2fRy7 zV23z>wbdu$x}x(IA%HrbwXCIyW2#mr*frreRnIfRAf-=R!WUvRUZ~}F0GjsD_;}2-rw|v$_+8zR8Klf^9z+Riif97i48jYvl3nTDJ+DX+Q6i z=2-*aRF$IA=y?rk+Nx^v?t$$5#KA_jqe6>83cNRl%wYl})5>>zc2!4$)Y;5eRhNMX zL|(y>7xHh_mskk!`nuqozih;xAl)WrSwr?v%uLs2w1v7}68<%27yx5tC)ZnSg>~7@ z@@KH75PSy;6K6trP^dc|$`{Wv!}K@(eHuK)CY}QgCeR3h?d`drJX77J-lZbEvcxvs zQqGL0u@1@d8D<2ZsWy$|$2E8*FyyMJ8w6DSwxUItEIQ1aVLFAGtxPsdiI0d|UO>h> z)5p9!v|nC&9WcD{cEVc5deC7xR5YSbdG|*84WWpnro0k1p5JuBbh>5O(3o0Uk=>DS zLN!%;u}nB`xq{*YsRY6Y#9v?A6wMx{hJJh?kEuLpvY=ji|I=EuO>#y<(x|Vy*i*e+ zf+ZAYzSvyi-6mS+&n4tM*!I}LtM4rlJ9RyASla9r2@^Gb{0AJ%TH)b8LmJr~m+C}4 zG?w~%38KDT730=j9@*`?qhJGI=3mjdP!BiCHIzM|!EjwT_`R=Z8BSa(g5qe{lp1Z- z28Z}Qc_VzuDNJIKTYX=DpD^+NV(Ba6+I)hop%f_EQk(#V;_e!x6bSAFf)#hyplyNT z?(Ul4?k(;PL4&&%DNrcwee=KfeSZ1&e8}!Iv$MNr=A3!y#4k!%7OFd-`cl@yaUdJd zccCCPsP*DQ$2t8)W2tz@nzX%$+a0G|!OM)rhFq?doNVv(28jBrXDLta#xv}W;;4~o zx5Y7dh;7_X2A;fo^l8ugnh@IzL5!v|15^#aj70uyZc zdhL~L@0~Rwu%2PkuKf2AZERqY%doAcUXgMjN8;|HSCB&|ANBM^-?#H}+R*=!QP%&v zoNfh1-^cxwj8;-@BF{&FT-9gv1trq$au}SzpQ#T`CIQ4bt}>WmI;|AX^nY-N*t?m_ z6}&Ob`_w1!%G;Ya%ze|3_gSgeK?iqNloXpOU)5{M&^CPn7RoI5-5rC;w`;2e?}Tv) z=m%c%ML8J0bB32t4X|4v_{%DU2YEYLemShO8FELHObr!&M6;dnM?Y;S1)ys3zO1yuqgulZ(iE<8$ z{Hboak#V3rRJC6i2$DM6(B9>ORXC#PKBtB&Md`vqQzF9PPBkSZ6P1Y7VI`o*%P{~Q znVV#l(yy;(nsSE+Jf5A5cbwwY`kD*ixcPcuoS=oCH9Lr6)6kb^OiTQNnvxpI)%G4q z%8kZ$z(0Nypn*lcJ230}U%mE!3BkYLZ7E^(Z<=d|A}-2p1tqc-v#%|xuAWOfio~*f z-hJp5Q107oFl@raQhYdf_~Br-_J$12O=#5#bf*$8OmQ>HW35#h-!{hk+7Lc(4;o|V ze@cB)hhj@^8U8-Cb?FQ*wv}6sNGutI1L||&8B|#UVrpTaKZ(24-#IH|J(zTPRmjVTx}P9y}cn%8~T8By(^$cPbSwE(0?ggqXYC+ z+q$a}7&@(wW@Ra@_bhEi6nE-J?t=LT^o$ZkVA>KBHSQNH4SwF5qIXGFQ~l2r`Y}(h z|BslXf=YZmMwJnPj`D|exI49PBJ^v_|8cx4w2qX3pd!Y&%1SP>>vbWU@HEOW12<|k z6(QV-3U2a$qxa#_ak5GTjBxnrNuEv1l&eK}NN2;UA5X5=c zJ=s1EO9G1Y(S{?6O7=Zz_;;B#Oqu{J(-ce;=ki&qHXds1=yXNK5T+d3H|U6{Qh9`>&MI z#YXu5md{EUkx~u8fMUwlc+0+oiU32LX}}RtB=+4b=HoISs$zeGAtexUZCFd(yN0UX2y6i?m?qesS zcYl$_LC54<#%c)c?2y=)F0NRag2wy8pYXJ?R&w)5;x^}VkD6)zq;O#Pdm6c%!Q8XL zP&asEpK2+674`mGj}Xrmv#xqp!T#**(#EnJY>NyHx4m1=AIh`+=)U zB~P?qhp(w8D?K%Q9?G19!$%^OYW2LXeZFxXjXa@o(8;8g}$c-8J`M zRUTF=d1<99hY*JHY?iIXe6|Wt2OYIl{Jc($hKT zcwepl-H_VIh^7{(3#o$F!?WR)hALQ71=@2UvLV494d9D*gY`9{0C8kX%>~GJ_~F~> zlh$|5f++Jz=Pd!<%vRFxlm3-MZbzVd{;W2Jpp;|SzUM}UJqJNQuZ_oP%w1MOp0&z$ zA=v^==-IY+?!qY~|1E*l;DlpNU33ZHPM% zqD9ow@^k--c#yIH$OYJg`5)tEe2#~-V0~}*PQ2BjZ>xV}ZwV&xNm{>%F|L-3-hu*} zI}D?MoDm(gyH3*{ME%~+1hic41BFOE{&atv1K@bwERtF4 zIU!N!7v<7E!nndNo`X2PGzhBJ+Z>LOSGF!~FOQOic`S8QdSIt!cvl9ChtAuM2Yig6 z3b5#LdclDyoZ7DvYA>+f0^aois{nF9lx;9AoH8f*!?|^+#o%6$uQwpe&KYGLOF2io z4aQlJ$!m{*ca)sIboaDqc=5eO0}fVAjZP39Hn-#W?*+iI%>pf=Oer!eQ|j-suYx*W zIzv*g5#T8AVEw%X{;WmbQG6?Bbj@9%#GxB+zkt-tf1C@J`d-gaB9|>3clF^aq>ID5 zpIRpbmRPH_pIeIWSSSbIm&2GQ-PgFAmtNJ6-}lKG_bs>hnkXEZ{6ukJCMf;L!+G(t z6ncQf6)q29*LMK5Joa9`XywitRc@w{&;c6a+O8Z>WYPc-dCO#$l+%QpPPnV z0a_+K3g^YK8v5D@*6SZCuOaYkeD@zb^Nm&MSr4>tW~wVDlw@>S(#`e|NwTHQ$z5Ed z@0!1hRWKx9|5TtdyIudOF~ZQ&)U;VRAFP5Bm4KUY1VlZ4EFbY6{>e1DyAdl(mfDUc zzQBh&S;D!`+Q7c^Xra?EUb*I-;PROIoqr16AjD~9GJhHoe!RpNIet7yi3Zqe z_{`(}8Aku_h6*Ew?_z16^K9Hjv#xSZ!cIINc=|7U*!`*6qpjc8(Qp^aY$lpIduG4K zANtq>FApUysjn7>%k}l!g#_`{R%e)L~LBY>5_`I=7)a zQsbERQoMb7s(T2r#3Sr?gVE*Rzq_RS!oTC$qC%gxrovvKD=d%s3Bfa|aQaJNh58jF zoTg_IR}nb^c~tsv(bzx2tf5_dokiL%9M_5r^E$FA3|@=VjhJ!N4-=TFbP#GTx#^=; zM(crsQW8(tQNf zb+IAG$|ScSP77!U{soG%Kf2Ipxfhkjy~+U?;%sGExx20hvVru^e4?>wmu|6 zd1nSZ^Bnl$46l-=)^t3oXfqI%Dj-{~cN(%xl>9v^n#(H=Lw{*e#scW+32u(=5C+|MYQeG(*Hpd)i8 zfdDelT{D9Q&K7ad*kbC8y?t2g9YgS(tD{F+)T~sxQv>Koh=K`tvT>az~0T% zuR?WWNzDLrAVp1YU09ZsqIxl9GCvC7@fo3ol^tCu^KkIPTL(>zX#JW~^Rm`1)35DTU8 zwKW$tJ2RyK~Tm$h-*=cbe(f9WCdCaELNhuhZ5gQTc5%V`IvSdY>E7IPx& zYB%}SVVw?NL1??GrBR2Ds(FeiGMwX`k&Zhg_@#+#?1E&WNUUAI6T}ZAQFACQu}RYW89K!!wmiQW7ubG^@kf)lz42&MDlfXBkvW zFNg8&=6)?l-vlr*;rX=S)!G@iDi4%uo|3M`nyIk<-V$liu;*-fXrnz>-y*lNb3A(Y zZPzv0#Mt?J(3#n0T~~wN^NEhVy!z{8vi=c~=DJ~0h2u%t9juaHHeX1YQ=XlMhamv# zWiP0S1tc+&qG;`=Sp#HZc)z^7#dL{&rfO+vXGw)dBO4_>-4zwP=;TEAG`G`F>7RHx z?Ma#a)5;`AkA|$ZsAt_TLvi?5?u%uGUm;5(Cod_E@OzyM+y0UqS=qC|EJ(5Za$TEZ z-l^rcU{9gKu}bzUAQ^oGHVW_2O`;gX9%tRS(V&@l^G!)GW6R6XQ1L@jd$p8+U>h)m z4-~j)Zy~ADXDH4jEJoQeYT6334}a!r;L=YKe-<3!D?X^=7=IT5!i}K%goaU)R=axP&3d?m$Zz-sD}OS#at0+lXu#=3xI@;F zJ=63W%$^ntDp=yCoSjY?F)pO`ji#KTfiF!kqNG7ycNxeLjA_zDWJCoPEA(5|T9CdZAb_SI5& z2Y%D2a^L%tQNL`MYKw;R{Y#84UCw|~OBtYYMOZ`s@H&i)e}gn$WqWOO_@?g1@=#3q z3`FyJLGn{{fD6i?wq4mI4HQTjS`9@XQ7C)E%}?+fTgvcXG63-;wN^~_hIX!lR(3U0rkf$h?PIm3kd5x8- zMl4GWe39~|D%IMnjJ*4CbP$Evh5H!`z$f*T6Otnhs^pqo z2dqiKPLF)8LkfWRW>(HkSUbZR<(JgT=G252tasPEKGx+w3?w!JJK@lW@|zhyUA|ZL zYvPYlG&b!IoP=3vX&#i}1K!*ic;}YhY23Kue&50#8mXxa2n`r=+TzI7^6QHpEB}6q z@sz=PGZ5Mr077tr_+=wfv}v_)ds-{Myln29CZvHAr3({YI;5i*>qANca<9`WtWzf7 z4u6nm?20X#!_&RBGTH_gbocC?Y$uFDd^ygW^{UQkac|VOnJ~V(Svj_aed2wxGm(T? zT4FdaNtaevR&otc!ow~Fj;f|{gZ z>iVW;cYe~kT#E;oJVyM<_=+I7>O$s`RG;wvX~(P1{adNJ{cU&sqvIY>n6sp^I<&=F z9nCA{&}F-%5^-TOM9U-KL-V~wC#EHy`;6^pv_b4pTc<$enhCWUc8l~|xOA%UUEwO+ zbdE7C%#1s*!SP|sW58}*9)sb!{U~ybZ#u{l_USI%61fxOeBz*S}*y;hR)81<;)n zXMrRz1+Q9l4q=ZAUJ>jF6pOWqO-Id{ChNWXI0|2TNJ^zUyrZRduN91MK-MdpxG!Z8 zWq79w)taI2p0qU3{2{6eS)MM4{OUCO{f)cQrxp9YCiQi$FbHQAdx|XvL~&~IJE0{l zp!)kxi%IQq;>S@SQAOAWYu{5w@O;5&8!|6^uIq+N+f4ASU%CRw4v70qQF7Yp6Ekoq z?eI*Q0Waj~LzM+f5Y0U$9l@G?I+j~!t4=l|Cg8cNOP$WDUzF7J4@Y{a3~~<-?Yp9V za5&J!`#eZ~HOh{;tCriCnY3sPpjmo5kwcgP<~#gxJ;t6(r6>6~TUGH2P_|E20r~#F z6Ga4LUG24;EES-FsEDgQ$h4$Odk{JR6+6nR!_prjcWkX3uH))VC7c3i5R-@Yv)ab` zu*BAS1`xE@2kuEaNaxsA&6S#3)D=1vO`~gI6fqL*#{oaqQWj4QU^EHjS3g~OYpqR;4V#+iWCoc#pZV|T zMu^<9rBg^l5mO2gx=Ms2DUQ|eRN!_ea@+~hK?}`mb?|q)Srw%3SBu*3-~?QS@bOig zxWA`j#aSJDzHXPhDK0HpKa`ZfFJ&_X6qd^8@%agJ2mX?qoazOARW=a~ zBfqcB9#{T4NQFv%il?JF?F?>gP85c1dvQ0=D$&mnIYf@$ZWBGU zYND$>AF--m5Lr+W3_QKvgl?O+ELX~eb=5?IOKTJOQb74F3B;N$(4OtrPWR;?%#iwra( zJ}{Iwl>s*^vK<;#YkLr?gt43JWUX|57Jp&a^BRHiV`ppdJtC#FI>Mj3V?B0DxJZXD z*a0`;ji+2_0|T57$zb)bL&UdH|1=tuiWVQ$;VNQ!b{9cRk78@$3nf9L<38+m$f;)_ zwgq;ziT2X^{(eu|hevIr4)a4$=PHe>HohNn;1Vq8nia7>^;g-SD$>yScceparNsLn z$MrFXp^d6?H1BhW57oKBA@3P_kLK|O4TF52XR6!Cnau?2@b_)=AY@6MtoN z_5`|xT3kD$LG4=x?u$9e9}KU(qwQwG)EP_AOMl`@zRLYoK`$cX`W?2pzkw0!TK%P+ zRggPgDmUz;lPQbKMwTv>=P)LUcRo;K=|Ax33`bkf1fK+tjnB$|Fe+<7(vFR1R<_6+-N(&;nj)Gb6KiCk zAkr$^Sv<_oM3S&7yIt;6_gBYDSl8~dWShO^vq)M{BK^eaO2L(1IIu)8{}-wr0q#0B z`9EmYu+N02U+96KTWBLKAc1|CR5R9!BOpSXoG>-8^tXm$S*LLZGoTJ5vM8$-&AVuF z7d=^(=kQX-(ld%3x&BKpZoz@~_s`|FTwnrB*`wtEJZ_z@0KK-P%%59>l^|pRKy0Dt zafS-6GoK;#DXSWXs1Ayy2hU&~>N$}pE!tK}%L{wlMj|yGPHDNM!Q$)89{V1mllRySEegrz>H96 zg{Iu!TD5_b5p652dWewJt9)^E6|BsOug27G)|x|fZkq9FR5W%Z10OH`t}d}n^!BwI>=AEV7ct}{6CkN za#Fm5hU?E~7e93y9ALW%$IXOpm*APPmlYkvL;c%J$~4ZwKDUzQmTwPJdA&))CCZn@ z-IQm2`K1H5KV@-T7i96ixvqs_^4{uLSo)wf#t*qzfN%g76<-Gf+GS%1ZO&2CBQ$i# za7Il})TF|Emn`HJ*Xm|jzdhsUW)Q{*1Xoq^Vr{C3tfPxsR5k`mGQP^N>4W)OM{Xo@ zzvrj5M&!a`vsiM#tQ#=8Ge}h{CgTO1-GuLQd*rl5Ff246Jwo&B%=^-nDMtY@-Q_Wq zXZM-}ubP`cmjLQ2_+Vw3w?ZlxuC%$gR$u8Mn|XID8x;YN9Ed3=S+{^cwWrbwkk=3l z%ztAaXCB`ehbPT;c`(e@#VT^@HXlTE7#O@jRWf0e0$}ij%JOzmY(b=Z0p7bFxFKQt zc%X)PQ%>*Mfd`CHSM4Hod@bF}+D(>x5OkUmfRJK|UL0M?(f$j^l5A*$?3yh1UJO}+ zL5=nDw6hCl&5p0HsHHfknzov6>yUZ^%)OgjBp~~>&C=m;K|ya%NN#7g?Zdem=17f7YN7Hk0YL)$<%H}A^(B3EtlSiyC^ zyF;=Hv0?Zk5~q?48mvF|P9r#XXp=xmKUPkyZ0WykeT`F|{jPMLRL&n(ic-9drv?s} z$j;yC#-&wQR26$Mp351{)(8Vh1uqhVdCr4dmbzOib&s1dcx+tLLa9yA4)H{0Hjw=W}nHQfsW;MBw8WMtJ7-Nq=SF5ekkC z$_Y4wVtl5>u#@7lsQUhOtlRkbGmcyToeRBG$4qWF&b_N0+1Vvt}q=A)JjXLzS#98ukB=K=J5lVVAqkd~` zRUGWfjnlFZbh2S10(bA1@-ANW;XG#x&gNy;XUVHjG9@h8f$&@epZ__L5_x(O>xu%+^03ih9wSzx> z>S1MGSy8*@sZXn+k^A3-J@xB52bq@^rRzyUdFCJ?TPvb=~U<|yvhovLip*6e&ZMKH^Z>j{Sizi|J05gu$~1GHt(sR%23yH}4U7Rg={AWwi|-P%=py}dpg+CL;ETrPK)q#0kM zZt*PMS%ZDgmJ4@pgh3ams=DS3!T0kbPh|gt)~5}=w49~8pcZW5{`OUaN$4U#HfLWT za6Qfa(bnB$PU6k5RRDw(DC8b~>(RyO;(o3JG~k%I;1s3-0|PXKI0l_OqpR~4CXe3M zM;w*fo&O*wN$!iIHmq>Qhzdou>i82ZK@gx^SIE_sO=J&18B4b%AoDIDCJrfxP><@X z@URRWwz)I{>i$O$D)Y6&b!Pgiyd=lHe!R^lyh`dEdiu)2k-^d+x9LAZ!U-$TXwUdJz8t{!cI%A(X(AE_=E?cdoqGX9I1T z7Bx1oXij)b{x!0VXe2q4+o|$B;=|@YPl_DD5UHWip?vK>p6X&UO!_mmnfHYFl=rZ) zU+oEEhQ|IOsfS4;KceWHOosZTyf^C}a3OME;ZHBPw}~^2nr7Q{TYQ>mW8+@zpMxQT z?j}hdxn-646;27l=N|}bDXhHs`9XPw)%^8(IzoQ~62v%FQw{p`%(ge?U?-*D5m`^i8(O`$-QNsDUpg+G^84+MUr1FW7 zTi1_Buuk=?XgkHDg8vVsSkYU-4gH<_4s^+|@TFf&7tJt-taqOlPsgLeRnFDo*VX?C z<3&;_tpgJ1PbvgtgIA{wPm813`r5(1va3)5k3eVhjve>54 zrmaVA%7|k6()x%)34D820fpj&=27`elYC(yN=Z85xG6@{HKZaH}Hqcew3dc=f^FtZkpbRurTYvD!)yX8I{1mZ z%bN*3(FRqC9T+7d==}dcJrO1^#X47oye>T~y_192z(9Vv;akx-P&v8tS`@cff+;yh z@=V|tQ!KjYdgwJS%x7oBWhhLgy22HjXeQK{J;!*Ha;DWS_BFI=*2q7VB;IG488qyr zfZwEmhgzhL0m_5T@JL<$d=80ELt}NX(Wj7p9hQWrkT9$VA=q`tw-`Sy`mRNUiRuS& zofdw&jpth>$6)(4GMvcP+PrF(^iBV&qG?NFgPK@Qe$G3B^H-kO-b*Y}trqL&)K1*0 zX|g|Tv6%lBbsNO(OAO=iu+0_Fm2sQ3Z`N0vHF0X^MY9<&2nap~ExL`dHGzf*7%aDb zM8()+(vnQ;grbn=Ao`ji#*_oR_fmGc&0tdX7i7uxqs--H@oXDV^l2qpH}L0o_32@Z zAc2Fo)1xE)=}<-J)yHk4rcvIt5v@hO3yGWyP1Uhory8WM!!_B0gz&PK#jM0lE3*bk z9(mREnYhF%vVl@4P5m72RrsV=UiXwUsGJ2_(cUqHbg;F~XMvV?UJzb_6K2?UC05I5 zO7ku8GMID%o$BW&X~JrzQ!j+xZQplB@>L&U&~3BrV(TExAx{sNA{rY>aLy^;m1mSA~UkWit1sMd@ahjS}{axQx6g$#`Ti{X;K- zOxYT&^v-dy!FD*b?4mCE?7Mb3Hxo}VWZqs<U7IW3DoG5Ik{5EF^|ZGz zUt(nUA1vvJbolta;vgK{P~TprRjz+|RMdwbiri%y|AaeIvrWM`Ksocu-{98p(6GYwDdk*%* z4Ovxy?CuCrn!;JWP&Ik_)gq!*stb5DA#%d@sdu-c3->LNw**<|E?OPFvdiCkd{r{O zkvx#++(M{(n7L;d2Ci8aBwqNjr`M#k?jY?yQIXLbb-yT}_v>J1%L82E4sd*nC17y? z_|817K(P$eqCT67K13I{9^5Zbea%^{+sP} z`6cDTzLQD_=j@SBP3RbI07h6Oco7ZxwLEMtrGeJphkV#6vVrcFPnskB?{^tlt*p+B zypkB=NmoKZf4B^zv)k^Hi>nYrBj4qvHZkL+WSQ1TRfXLl?(pmJM-VZ$a{5EjeyY&V za^IKdy52Q;Uqd?Em0A!%dYV441Ad9CdEHJN^zTEmdaIejx13Qo06|vPwF$95%58)U zv0CPH9Sh?;&Y`tu6!Y1Wa_PLMdwmk0IejJ7>o$wxT5DOXjcy^G(=|PM z?N7TrLjz|fc*7gf>4mBjTd~5Inp)%@rN}G*19j2>XT!(-$4_W9Re%N1NIow5O-^id zIlQ=4hjE76or7TRDY^}NVk}N;r@2{;AS!hEz}3tRyokO`$F}XIew06ZpPt5OBl6~R zt#$3VOQxsr^B=0C+!_Fw3ApRLF;tSHC19L=KIPb@@V2Qcd)T^bo#ug)3Xq}bS8aOK z9WE**Gv5W}3!A8}pxIPYfjrr^j#v~88UV32;7VVeFB_=VHwr7-+plFBItMuJTnOB? zlo{>luHOgWTmnc0t0RpsBqS$D=h->=A_N8s7H1pc-q#H7i}+c6kz+TciXJ(L`?ghM zo(;qlbxNbIxMyw_#A-$ZN<`z1+Gax_K213Rvf&3NAK!Ue3lc`=<=*KUtY^9!b!1wN zJNX^9@#%V9Hv|vZs{=%x2f}7*BG@)X)AEcbBGK{>bpLu?Lj4Dd5g#^k)HkjEn@&hR zgTPvE13(5q=W5FrJhl-3PeVidH#MHJXt~{en&7Yk@n;kf>8zUNO;6@-_E}t14L6d6 zM9M3whG1oGKu3pwQ9b*=fSeX@pHn_XMzuTFC1MzuvN&pdbJQ_`Key_@#iYQL7oDC= z1qzqzl}I42OwSJYGjp-WP}i(~I@uXsPwM#gL(Gccu}y%#rsy@cMP-E-2zh5LM&sU< zb=DcS8X>y$wj>r)0k82!C)^|q7!$teU}Fc2rWVShpIn}Rf4zs>P*&LeR3&p%FgsKp z`u=5O_5^umtMkML)1v;{ES znng2qS6V-VbDckXPfb=;hW4$%*(TM2Vyl*K1=uuP6o@7p9&xdDpQnF~{?XKI6Zoq8 z#vs%JR{U15qr@StEP|u0WDxL*p%PAcH`{{zZ#sKA#;v^dkxhywt5c*gs9S<`#De32 z%d{foTS$ItOHaDdV99~J2OyQOXut%OtG#w)XTrFEEM=fzH@bOw608^!kj^^mkR1egcD6PmG8+K z<(qMA+hki8r=kH7TTJT@Wo7AwmzGKpZhp6OLq94p0j2v&D`L}=p{#-OA!=iOaHLqz#jc$HrH#X9icz#1d>V|K_Fni`(j;rxT0&&>~d?$ zJlT;gXJdL%`22@$qEOj7+WJa;5CyDiOz6WHZpi?w(jfWONG*~(0J1E0iRN?9>8VOz z(k-Z9z|?lfjs(^A9Ndm-oL7rr!D_v44icK-)XdpYB^=zBh^{d{@@2kn3r)Pb2-3r{ z>G2C&f2a16_$33y)x)US@%0EiQkA0XXA1|bl?mj_VWBvDmz^20;PKY5I&2GgIUf)z z`hhM4{vILSeoMEq0eaqxT{1y;p;*uST7S%CX*JgrL0YlFyF2{XI1Xxq&|q$5?)JU{ z|BB!}|weH<2qw-NC~ zvpAr%XDtui$T}cW7^L6sgx$}zhDUoHF~8mf>0mU4$8LNF9lk)dQ2InTq@#SC>*JY5 z6h*li+0bxk;pbQ#{DUA$&0=G)C<)B23UTdNBQqmW*l-AQV`pfR~EdWxD5@_Y7=!> ztSOj8i%)-6{1*d`Qi~r)zEM5S#T{@QSVLzkeJ7tDLTW;hRHnN?k?X@S+(;yG$2>p& zQ+TXBFv3rPz%nOo2t1DhE(I@74=o+X_QR-cmOWNPe|dxQ^*Xc{8;ib%4h=K(aFm^y zO%}w~OLL_X3)^6eL=hwVspoTa>RO%m5`Z^y4?Zt{W)!Tkr)9l2yF8pei1MB2m=w>P zVHMtQ5kxhX-x(?y(==J1GIw)?16G8Krn@YaB^f5sgT`WM0!8F^O6;`}#0}B=SDiGa%R|Q~g zxw6yHTWygzr>{o*J#A#EKKnvv(1Rwzqo=nGPx)osI9rpGgwrSEMC&sS{1_vx&xM-* ze`>9~J$*%*Iu7q$?RPERUB2*RE)i)|ee0^eMZ6xLHWNN69)ErbV@F#d&Nt~UTrVHS z`ezYRJ$Mf{4CcTtj#)t!_`##{?C<9C#sgD6U3|>P^5(L_r*-i5!r#0qh}CKHK``?N zqCAw%IuVny%l8`!|M#^$p1EKrvm1s(4oL#ZRhEi3ncOu7%=u@r(ESQ zyr*T(o^`hN1YFQLTaXc()Y{birAxrmTy18xnX3P}yGLxB!D7*8K0d(WDhlOP7%rGH zFxQ2OFJpE^MGaM#Lwz=F(uoBp?Jl%XnpuY89j6(G-t9{t+^MgI7>CxQH*?4xULdFL ztNGjO!`myF-U`0^C=MBZc=ozhQk`W-nG)BfebT@mHSSyjyY`+ z|UxfYqd?Xw32BAB)Tzp z{bAQc%F*dnd)_f`Dy55i9hV3m-k^wJ8UUq3laBN$;lR$#GkA5I((pz^Nc_8okcx5O ziBmz;M{(^9rPzL+R1;|`_u~d>lFBb8De!W?b$a{u9|dN2#i8I$VKn2#HQ>z z*z1TLxtB<}R2%bZ4bmQa$tXcLf6b9!>u<<;B@6~Es!F{;7ssCDbk!`x4Ev>QwXf|M zLREP83?edyw^9>a7i%nCn)@akK{sFy<57xbAGhW!lTYiq0ulHX{=?Rjhl6AUn8As+ z74G1F{QqnT%9fQfqJgGAysN~u-%}V&Cf6-&X>7I%4%MBKZ1o{J_3B`@%N8F;Q!N zhs}9$YnAout2fNUE4^qCKR`B3L;q=QG_uu2Z!dxj5Ei!E_0of6Oty2eD0%qzMn`Xg z{}3#W$?JOE#?w{1e|s6szh|~fSo#UDu!2gP)8#PGG?a4O!P{vBLi&%Ujf_N51r`bxkrKa@j z7Bmq*w)Ofjec7J#S0SQ1L#1yjuldm&$D>>7081I#*y(x#s~qT|95j3YM0<9)UjK3Y z$Q`Mvn!Y@nBl5gQUVBN2I*tj|FU`t1=;2C6I{V=Ch;X+m&_ctM8uQ!SKkz_SO@gFE ze(7~;(op%gDGmytt}0@9`2IBm^Vp2hti_8>6%P?k{vQmX#<~JHRAOuYQvAkjoYc78 zSK!wy-!Bq8JY(Xf?>_sC=cnC@q6xDrlYK-#)4Pctr~9WPQX$x8PVMI0p`d&34bNH! zYcTTMhNTHwP#6Jxn`aQ?sBNXVHnQOYHROmX)R2QG*6Izr&k+(A)aaQ`ceA#%)Tt#VzrEUMQ`r?fL_a%Fo{lm zNZ-?qLZ%F+ZZKxBQabqKp_k^G=GyIXX7!rAqX09q`qyIOaOTIcl~j!BPMi0u1Ygxe z$Zs6r^g!;%%@`6ZJQ z>usb4w>SR3C+*$qA=Y%!5|;oCk(iO>fOYd-(EL$293saHn*KrGlLW;uSgSeEoU{n) zA8;IuLrYz@*_hguvK5iYZhZ?cT~gHeLWLw_feEt_9+J}10G}6;v>Kx2=6oXM2iwhB zK3v`;pB;6sAqKN{8pAY)-=0BG?-H;;_f5?6*buir0+O;7Ts-h4qfksiu2jg+Q*{>wYoC9N#24cS0T+ji$7$gIj8QLV+pt6tk6_Z_+b#^kE;wJ$SGSWBf3E!6X6M#MgE? zvksrR1lpX`>+&`|yya>)_f3KhOiZ&A{0m(MH#T)R)zZpPi~xoHy(U}QtUp}CRep=> zJvtWevn6U=5X?N97wg2QhXGAur|GaJK^uu$MpCkUF{jhLu{rjNqy4*l1_kYYm^ABl zSI1aRwn$rt`ed?L&smLmYPnx%t{6QU+PKJT`WKs~E!wjan)2BmsMF3X``%TkJJ0fB z1GNXPW8-_8_f>VUYIgx?TU)GHwW`5gSDnQFK~u-w$}urksVd$kKDBUpK)Dvy#4m5@OMceGsx~lOvC(dl&A`+OO>kbVmcOM4fiy)6%btG^KDhNKDpi} zGJM(?StUp{H3Jqkcw@b?Cs?+mDnRTu;aj%=UKd9_>`^}PDo(kfT^7!jCQ)`|(-^Xx zzJ;@>kBivrbz~jCS9r%mHf=E^xMY)xdELaygSn?A7JCrm*n~+(o)#FTL7JKBK=i=6 zk6@|VXl%Z;LfZW;csPf3m>tH=VHZ-E2U#mqTTz8zK+UtBoMBv3_CVeq=Lu55{MSnR zML{w=8oW>U&cBFCk0^_6)w%8LFf-coY#OpyCUK7)x(H$iqU~N1BBvai^!i}nP-_)<4417&$ zEhCo>*T^R~!Ei@3ceqz0ZVlcIaJceb70|hbbF2n_Ip67Ym`32|KG{Zrg)PuXGUEFN zDq=X?PWGWF0=O$^y7YT+Cg>c@AT0Ghc{2mll*wvqz}d+wZ{5tsnJ;yerC@}oqM&3k znNz|MBgKpO_J{5y%*D?;YORKK8F1#-{d_Vy;df{7R<|=P6>@m5-@~Vq+=1vkNHoPr zX)B>?tj-*QOvyVeKt^*r93D;3N{N;gP?m3cMzdPT!4lSAwdwyv4ae<<8`;}0HyTf7 zjI;(D71yPmS7xIsvU%2oEg#q+dITj$d&Zv3XiBsQ|=#+w&!3J&p--YokNU}sqB>!@J)M5e4_ z7`KwDVoB?|PgfJBH@%n^$m$$!{y~0&lPezo+!_nmmR?bLXdSMu%CTyr#xbqZI+)is zCyVdU1Y@G?pDEfKi4#ZO?MxE{6f_C78X-57vVC_$PVCc@*STF5+~fW(n!Rs+kDPr_ zcpt-WviJ)%dUbZ0KExv|^_y&Kq9)7C=Ttegb>?3p@*6`%JveTx6jO_phf6u8V@&pH zi3&v?C)WAyV@c?YmE(i3_sQ5ZqnrKvDM`KOVT#HYC0?t1llWw5#res(^CrHH5<&d{ zbobF)0BK*?r#SHHG+&Rgw&?tR^e?M36$t!9OZ1mry5cE>C4c+j18JASo4dAZeOPh2lL}>2F(gZHzRj82)Ko+?C^&D~a*7-Q&r*Mk zt0;vcrn%zqz1G^3CS$y<4H^ve44;`E9`A>gX5i+@@u79#FY)L3#Mg>gFLiiB1)U>` zd|vI%?>q2IPYZ+q(hJ~v^s^)TxAoe5Vp{DE`aztI*TJ_Eon0&~`^vDvK?& zwuuaXKN+~ZnP;mGwRF@f$K_esmR`!bX!Uc+%{6Jx2%KyV3A>X3G?U}juav!JzV-(dh~0CZ-`h?&VID|q>Sy>M0a=6w&e(`!8( zzv~p%dp#HW>`b?pI8Gs(N^!GA_jr}CQ@#c8#F+uk*X6RBhnXgz0B(bA*$_&14M}ZhCh3Qu+jylU(57M#) z+(OD+bb3Qp$iaJ;+;1cCG#zEqkzNn>!2W1-M1BsBwj?7Ow}h3xAXU=@O8&{)ROASh ztinFC^ium{PxT14^Rw;vDaU`d!WZpv)y(j^&b->aYk@t6xjpCoQxp{Lz_(E^nEvo& z9K!R>0$+1{>{@9#Cmfp)(1+CZLAbB1=`>jvUquwC#p(un)!-5TJULy*7|9tLLgn>E zC~3g4J4wHI&eO&W30ao@W^cqkAWraODsUZPBzaAE^E=m@o2hHp8rH0{Ax>nO`@_^? ztoS{59NNBC0Lt)AIG%PIfbHn-SYmH6VKGu$mK;xSz6@-NNQH7#r;ZVmLHWpApq4a; zS3Sl)Q9g1wK8=s+fdOfdelC~5CRj!PL!ZXkwRlHC5VMmrqdLk$3@@eH5mX!RvRD$D z4!ypogA}fTVm~udmQ;m|1RK}z%$E$ZPSL8YIaAdX=eTzYUJtaXaj-ryEUXjWgGO(?WWj$=cVw1gFV}1CXp4Ma z*GczXa=NJ4gfvM^d{Apl)fUMAvA^_ub&HIIET5gzRw&ZcE_Nx3T5;2sD?Z=NI2>Pm zavm*1LxAH0j$thmMR?X}VB-0liUz03$ev$L9+$f&aM^FwI=!fSt!+-7>Qfbkt!{C- z>9S}(m}vZ4BB$sV#;Po4Ja3P0b1+qNO!@ZQzh_TWXWW()2u-6AK;b^Bl}c^=+UFM% zN=8m|SPn@Yg~~>g(@pWr?sG1)w^1}-;a>2mq9;^!|2zTn8&dw zOU?ew)EaZL@eW##%O>F(jj5>oUP+v6rNzdhHp!>pDYH)g!(DlTW!9sLQD0HZlgU8E zxZxrpZ&+-i>$+mye^l4Tvjx8*+FQn13!l*7`8n#l#LpT%T`9rJ%!=n~? zH9Qs7E`jPU$Maie=#y~-hXdI_i6O}+!lmQ zo@~d*$FFP=4HaM8^IGQ#X*LUOR$SO&nu0lbZ6`~u*KjJ-m`wEH=Tu=9Rhfr4+hz$3 zl3(#IPmJBH-G}vj*GagXaQkYC_;#imn+rJ!cr%brHKVzeG`HtTBK5n(HW8kr@0^l2 z<7R%J)0bnVJN|e9erRi`7;MCaqGga6?z2CE`jo4^!q@6uiRc3dmx3p=XqbEfPo^{ES)J(jws$MV2wqHj;X$TGzDNDS!ukEk0Lcz$^ z0i50HtS_#l?e}#Udx{SrNXWR}ms%vdStKn8g>~y$Pn4&(R`pXA!$op?rssXlPCMVE zqY2msprH1#y;kG`;K!>)A>%lZ0h_eRBx>z(EEzTG_%kF>*_K(g_Qtbum*$;*i<>&t zeu=F)>Q84*x1DqcYO;g%Y;ws+Xo^3jp>L<#3gQ@q%}jBfyRJj*Ax^x4pWBNsAN=xa zOsw~xW7kF@dGfZX05C8*QT5gE7 z!ETq}>mj1eQtAcq1vgJB(#ovx*dg>@S3OyQB#a4$s-45mIZzk1seT(}V}6XFxIIV9 z!LeF%M$(7x-%_JT8~`lYTBg2^i;Ev^TuT6WySDW^r0>;YshPJUfVtEq zp4AcAg(G=28-%35ShU3vSV$n$NXmhwqu!18bISwz1lOMJmji2f_E5IC6)NAUAf!3D zlUIu6tr>7cKu$G3SiKgK@? zw#d~e>G_5>9oA?cTz^bUY-I{z0WkC1!3LPo zuRL>0?h&;RZn(H;7~nB@NbadE$f{9xNf?B~L8L7u(=^}syO^XRm(zk)vdJDulG`ic z8q!Y@l>dgfY5uN9Dn zWb`=}U$=zu3oW!$$eyuE9XyL~^-P~jcaNmihK`7DM8I_A)<(j#42eWyYUB!uxzm~o zPXZK))hnwRXjpd;WOkFDXzK^q7bvph)C6#56QXV*dCCjL>bEMgSS0&rO)fElFE(>vvex4YIQx<{$bzB>Sl^(#oEhJ zAetb%+}&PP<;2M9{FdQ&0Dm$NzpT@IrRL?0*o*N**mzWZ&R-#&ZDx;O(Ik5F7i`EF z#E6N${v`>fF!7!Rko0IKeJL*X=u%GGmr5b4_Y>oG*K`t&Z@{dj<8)kKl_Sd=RNroj z5j_&%YwfU`CW~_W0Qc+D)7N$X=4;s%Pj<<*!YvX};-#YF%mF`+pkY_^0-~vAr-Dk# zind0IXELB${d~zva%Qe^;_{z!_+5!A9;-dp;e}uYx_Fvqm*)?%QW0;yQ3BdH)}e3K z%%OK4Sc}D8-CXoqh5RVPqdOh_N{xjtqWLD;Yk}FRv5->0j|Y6YPf_<(6Jjc_r@oCC zV;IW6e%N*ym*J<)Z`s}jHmAB~i~I%r1q0|Yp#acOuuw3tFi?;W004jjU{PXH07aBo zjU2xC=U&Fu_9#wmUHx4KAVU6!62^QsL}s)H6PPbPSM2bvzDBW_5Q=@4MWUtG%f7Tb zjMv4a%ZPQ=?XcBt@m$YL;IF1`A2TM;RFGcsV$r^>o@wz@KHYvBP737dESyy{*YvC> ztuPv5=Z^ML;NK|H@)YXmSy3eI>j1mPEtG{46O={3#TPY;a0*gQ398Ieq1hQ}rX_yB zxeIzT64q3h|Nl4_ag zc@Z}I3$QrtI+evZd;y^HxZSnj@nBrwt={D9Vv05=+|NVi3~gGRT-ac|^y+6>97O8;dcih%{hn~V~Z zX{*c8@xZL#bnA9P^ltDPL8qOOIZ<~eMI@wK6&PZ{DhA(8MQ}whC<&dtI;sciihR>a zxz)%rfxNi|uiGVg?}(5AhNTh*5yW>?>|{38y)n%1jij)g2(!FPgx;Q`iO}-zr3I() zpo=QccT(&-1R9@p!UMN~(UC3TvIgdKPUstcif?cuDTTUjJ~$fopH1W%cQ)&K{^&*W z-zrG2`-r6c3ei^H@OymNU`<$n-6uadL_|tE;~!t^i}5fgTT~A&?ie@w;nLABj3WVb&s)=v^`yZ^|re6527Xj1~z7LkIYPn{QU^Tp`a` zSmHy4BPq5+I?|>sKMa< zl-cOe5!l&#_CK<{Jp{E_Qux#iH{=cO2tNvm3hLCsv|46vOcNQ(Ca9Mcz6j0=?@iI^ z2#Tr9TG)q7r9V}N=JzA;7@k3A4X2X(+M~+l`xpPI=>4JYc9t~Op=9w1$A2Vk$Zr#s zioQa`LD3^k_kxFy_r!5(!^oMBU;r3tLI`PVzMo9pKQTbS$nLZ8id*9X4Vj6Tt%shx zC_N3`R>)Jy;{4<{^QDSZY+N=(1set3J47GhQI76ffiT$1A%23d(&6AMMQWoLUpi91 zf9POTc3o{8A=#B*e6cw-Ag~QmG_1cdN7$;NNBRTch(Q>=#R0G|*C6^N^}hg2G=u6O znAx3~Tttg&6 zEy|{_K*app^Fiu4aynV9|yTtQPeS)uw?QyA>FY7G1NedJj_aTh-r zYV|c6BGyL`+#`w2;Yb*!TcR1;>mNT#;zh(1UNQ5>rFmgO>!P!yt*iCGg^P@Ld8}x3 zjvqSzo8$od!#a_!)?Yv$Sc3eK<}II+86sK3`a0W+cub?B1O1-CI9kTBvmru=U*Q3` zmX=~O&AJnzWHXCdvp6L@p9CiL%>;VVb-zft2!{TG`I++l%9N9<>+8WrY6nVwPEQ~_ zb-0Ewqv!RPeB3r2OhrwbvXX}SEDh>Aa&MoRJ@&;~TNbZu5EteY);s^7%CkWOyEg1o zxpm#Ts^v<8`cOxD#Psj0Qy7%Yry;Q+sS&PXf4w%Dq9G6n#oLaLD25fa zvPD#$CA+*~dAJe~6QT$XVvJHLky)-GWaJn2c@#K=OcfYuL+TeHlY9-cgL;J)GN506 z!jFbaIL*=Axpjj?$F_zEjroGgMc1zR2}-w-lBx_4wkpF7m6Tg4M5vExo6{khMY$y8 z*lFlB^$9^`k+v3VTYdEVBLq~<;>Kt`@|=jDz=!O@)wX@$i{jTZBOOj@LA8M7JH8fPk9e=>F_8Kfzg z&s+P-4IC6Q1h4|Z0|d<`Ha{b#{Y+|Y`4Er2#7Vu6$r_*d{l5~fGiy*?Vn8aRad87|AcX_)Ady?kk!;Gv9nR@r_ zhVT_vVyDHQ9GBJsU5SFTSybZC2t-JoP)F{v^b#NAQae7W!eNVZ7BkLM@tOmGJ?e`A zelZUymPq-~(!Dz2NrV~n@oBUUrbz!0hSg{3`d~3y3vp@ifvnP-pXwsN7%0XBHD%#3 zBIWbPgp7la%!HKic>|4P6zW>+OnBh%`2))#F0Zi5S6eSlO*?4*`gAYJqLF>PN6o?uQ*A(D^ zf9;1~TPzaxAodrNlGGdPe@eMw*%x{|niP%WkrXgdB+-9ETwF1FWz>47RMGuTanc89 z*hIKJFv?~81J;Dj=`lnx%w6l#Jp4HOfL2v2@6Ze1Yv&p0;_^~+8~vR zFpO`NI?i0f7DE``x*1JHPh)^+S^p~wgS~;(TWTBiCP-0+$fj#88VOO2Kmj8a&}eHg z1kRg_R)3!&Y^3~JTAj*7;r%Q4r$+s@*{k^Fkv4E@ibn9!DB~d%vOni?06$tzthj#{ z%TlQ6qZ5trCM2s)HJ`)I0Jo<02+H)3O6qn>v)_LEA5E7W_ntL6_xe+qQ6aAjOpbR_ z=FHzYlRi|A+zJapt0H1jh~j<>;PEaMUqvpZUR0WsgObqKlxLFQpQFQ zwdZ~efT4v)XH_%-pDlnX30V&0h4f@E{UNYgC6Rz^DRT4%4ob8?tPPe0wv@R^!hC$d zsZ4o=FtNop`4w6l)Gbm;K7xrE_Y*^HqPz&8)4}wrmgDw=j-OG{T9~c%e zL&5Y7?>kj~b4;$|-Wz-Ahts^Vp7m|iIY+51LC=$?Lo*nv(8xuT@x3C_i zT&1A~*H#e|p1NV8HiRp9xm8&lA{z*`RRWr$}~n zWduGqx!^Qrl)wcwfH{Rl7Gkh;{3ik@kd^g}l2W%fvHY0*Yf{p!1@xShPax)UWZI9& zWa%$3AJ+4Jz%~kPz&g0iwOtS9G)fSy#C*TaBZ{5;Z?r+&rri#9muw|?$cI8h@`X9c z28hE?88lYlFF9#dDj7Hz!DUM(`J@Dgi?1IP1V_&JAk#E;fuqW_~KXr{t#RDaQ~B2!4JHby{;;&IFc4q)l$_{lf6 zbPN@FNH064PfF5-V8Hz;@`-Xqqbql6a)2+=;-sC+K)q6N?y>yhcrF`6Od6fV(e@V* zf2;r@Qd&wP>9?wt`8yLtPk4RyNC$2#n4NWGE$ac5!U*CdG0+!9O>QZByJ$)@2rvJU zi0Enpb8nl#A=>O_r!n*gMy9l>g>X@B})&cSUa7#oQF(*;b?>u5ChZon7&zp-*rLGfI{I2MvG6Vj1%ou=h%g@lUg z#b5MYOQyDDbiIb@C%HP^8()!7euXEX_1KW2yh_bC6u+v=k@DE^is6fKfOrnVVp~o0 zox-_U03vTwPoF~^uR;a(2tMEV2ZJdWVUulNYu7$8F_YYy=?7w@pmW`E=y`Tq<9(Bh z-C*LVl#CIzxyx-+?m^`o%Vr}O3|d$KrNk28DZ}Z1G9YG=RSm9i{wy$vul8hsl&Mz; zVqiYKLEv1aL}aaXTqPS7=u6djk4L-eyS&S9zd&HT-;5rtV=Snu$dG5esE?A$6yFC% zI$IoibL}%}=9biIZ1_Od@#t@_n%gL$#^&$;cF6xJ^_0qyl+wEY`}3~D&uiOPpL~~t zgNy&Wl!y`O{RnAyTUc7L<*flqDmgxkT5m&<1zxW_tH|`!Ds&02f2%aQYxHL$y+tyf zIrxCVlK%-Yu}ouE0~(SEi(W~|N0btio!=V{B3?ZaWAnm|Vg81uDeNvZ1$&)pG^_^0 zYW$qMb>vAsQt6iSbMI!D=}Uy#Jt{>$lZo^HqXUY5HUtNCZ|VnO_{HMC@7put6Ec0? z&gC^6&0zZr5Z}07dXL>_Sqr*=_X82+EwhoWiDfE7$MKojnpaVq4u4$@j^+QV;i`M# zRdWoC!TOH{+zeoawaYb6zBVlL>)*d@b>9na8vX)ePwpI8&J`3wt;I~xPALicRLmwo z-OvEr{rEAr{%qhnBf1qX!A$1?i`JFY!1_D^MGux%UB2d+dih`?T{r=c(bYd`sUJo8 z^5m1#OO)<&vc&GceeI^a>oFTiyMNPj=FpS1ry$3K>|KZ(&2Qo7J&vBF#TyYiixaZs zaBub@g>cF>9|2bTiOhGj`nDpif;a<{T0?~)+LfY$?ZrD-yvc*_1>57?PV??*HWeyu~;3^o=%j zT$jVlWqONmGKE<`8nPssEe|dG=I#*reyXehbRS!d_L=;=62cnD+qaM9*~z6{#5y4})_?etPSb z(>aQ<^N$N?#raV8fZRgTR-|a0>QD__{wd!`{@QC9&pDs=t!1}cj(?;dU@Jas=e8#p z{IgnC&~eXs$mi`Zk9%uSAvt*H#{#pc{<%d(zJaSVFt_yh`Ps;++f9+DuKJp(Vj3jC z>S%8=xadFJdo%lkb=NlgH6&?-Y;2V$1yM&N%s_h6QI`xkD-ogn$$t>@k=kbqEzI&- z1Ri0?qadkKEey;X{ucn^-&)5b6+3m*Wf4#M^^m`>$^j{nY*}~9$lc#W?)yVR_b2Yu z4E4Q4B7au(ks3Trk%fBg1q?v*hxnLB&n##cKNZ%WC1FN61<5=PAYgJ-*H_-SMrD`K zSV3Gs(D1Ug=lkgk#jo!dJWATFMhGRml+*h}{aQj~lnf|{xEH|5CJfC<>MrU4^e;o} z!6c%X%TE$JsQWv+e*y3_h2a_{{wMqT)MkuuN?)tO;b_1av zvhG8=0#F<|z(|{EA4K>GPV9FP7;rjjsAA2YK^%TQfeUcDJXX7C>9Q&U;pTqlq0Ld`o>NiG$x;P_;cc{bmM+*P zW}BKMIKi(kr(b?p>q~x)5uNn-QuQ-N{%uk4Wl(cVU|fE7>xzVCAvyIogFIA-A`wfn z(&BQMcn=8OIdc3(*!|2Y5;5+wf*rP+V5;j1c1<7bT29aBa=g7A8k63z|?ZUs#8Q zB*OjqDT>2b*hfy1$w^tx;Bo0o83F#qJkQXlawsYES&Tf-55IdT_d6V4^nw&HVm?|UPzC4 z?QT51avUBge3Ih8KEAq~DGL!=rwX|-4N&^}n-mDmWYrd}a=*J8@~mn{e!*_%9mw_#Y;$(9d! zG1QOv7;=GtUtcuj%&Y*F>}>>ZIjB8bOiAbQ4gDE&|C}HNcD6JezkHH#f5gnB=Fd-GS*TV~(!y?=-S~VR)H(7g8C~|82QHlP#Z#-f2q8KtA52#5l z8Z2r?&$id%mZ3SQa0k%VPxFwc+etA3A@!L&q z=ffD#@k%LK?ZXEqLbDXY?P%DGeW=pQSez6pjL;J1tnDiVyvmM*fbpC5e-nC^U%s#W zal_~(x0xasBYBN22jXyWB7CP3Jkg9`g0;Ip)-0_Ko2+yU;Jzkl_!c0t#7$ zx)>la_BFk~VtRs+?Z{jfvlW;(T$QhW;bvj_idBepRisA0Sicz%rMArq<;Cb7$#>NG z(GBxY>$F~p1J2~K`x9@AhFlw?@-U;Ub6OVpely1)f4&Ih#EKn)Xf|) z3#Zx%T?Tc(X2!T(+$X;M1zfA#{RIrg@x9#<6%WOV(dVQ*fhrS>@mDAa49qKnDBBDH={{A5zS#kbi5QU(Q+c z5ouE=QF@5w<44?x5~xIy8oGPF!*E9{OT&J}rD(i2>OqJf3)ynKzB)n-aQ3{6w_H-R z?^0q$bwd_q!3Ew4kFBlp-mk8hdA&e&sP}k4b+42`lZgFS=bQ1b%-K zQnjl`66+}Zu9_VCv1a_}OTtBP;-aGm=Zu(nsZ8swyLGWmL#EbPQdnYxH^TSqEQ&M{ z;=G0Q22jzcg3Q1TD~K+%T4VkU0wGksa5#sV_l81Ize9{*GiWm9p=* zS_;V&I?6$d+Nl(p6D*S`l?D*y=Cg6wSS^}h?q2{&^abz4GS*~Bf%W(nn!?wlMmAje zKUjS`k|=Ns`v5aUzX?BJ%$rfK2(tU8 zU99wc_Kwt_Dj9679QV%T)IPy_VPkT#?-(6JWUOVKK{$@ik_324YbtV?Ft`D3e#JB9 zh;;d09QY1wJnviaTxBg&dSFZ}6?u19ZE4SoJ+tsAfcu_Oa(EpvE4(O2kyjjg<2~Vo zeMaKAE}TmL#R;rBP@+1)C1-)|Aeal0U}mh8qkoiu zlcBI)((~|0rpZA2U1}&{#ry@#PJ+J_|MJzOTt$NT4Dr-jRl-!OdT%lkq^k|MH~$xR(Mw_RnDwS+ zg^3GK^QLCr^Y01-8^cVCP|!t%!PeZ-33}xl$`!Nx1wisw-K@SRY36W`Z1)W?jo1;o z-s)=wc-6gP7`~xdVpvoOLTaFPVJwQ%(Z$9aVzVkL{!(i`>cA}|uQgkJ$g2Hsn$b-x zerMiRrc}8|4pZwtC`%992xkp3hrkjURWSu%QP?f&Zz5A&!LtPd^a~dnBp9~5uOB}K zcxUfGp%aKY-DFL+r@WgcHb8=TdkukT=2IWanl_Ua{{k3aIq^itrLKFZfa|JVAx3~{ z!c_JL(LUHP_&24La%^p+u_Y=^xF!}FSg|VqK}7Vlc1}o9c41i8$ao;X*JM zjI*rpo!5l*JWsxP3sP`zt4rHZ52*QJX6rS=N_$C=A;KSc?;)Eq=_s8t)EdSu?sQQ^ zImt9GSDGO!x*2O5W2gE2Ywg8=NH`|cQp}`rc2P`a$_*!vE`-_Hxw5hR5WAh@aAMO8 zX^T9uPEANN+npxVgZL3iSNc&gVd7@Riuk~q{Sagzc{W5IyNHS!eT|twnHl}au+2%N%pIf}W z>*j-FV0j1MWRr42(E1R``XdqQXixqAM0CLKW9>d*2^z_N&@%dMJ?Q{<-5ZE2%T^a! z2NjKu`JBX1tszddE{9bF2!J(N2xBWui_Iy$PhuT}Mq1Tm9DL25ew>-OCW@V!S{2jZ z!jRd!z|TrE0eUe=*?iaebCHA0hwwq0Qk5I?&5dO@f;z`l#K2>Np-peHt z=L!y>$i?|Xak0iKz0y5-N%EjJ)sDb~{q_oZ$CFHqP+5FVlvfIC*w z8DV681aS}?W-h-bp{Jk-jcvYwd`ZogBlZ!jEyZVgR(X9qR{dhq1WZS*>&S7R%VZAf z=3My4z#)z+yl_V9vk7w{MB5CRp3nSW$r^l8rK7wXq3V38N2VbN;JPhNx9=P`ub=`B zmw{s#{y$yIdomGNW^rY#bN}! z(zXe{uh!3dwWyZXB%)6@U7FdMJpA8HA1?j^EcLQAzba#Z8p8 zd+H;J{sOG|so)_9%P{*GOlQ=)1GMq{x6tC{CAB7CEKnaav~pk~u04H@su430YhXS( zV|`@rL~k&LK6XAitpgp_{MOz0#L|CUXH8)?$PrT~Ipu28``IwIl0*Q0uFA_VNQv2A z)H;=>0#?@gGpmpmzEdByU=}|o2Cv2JM*m8NxUn#ofAW0-h_x(*ud~ zxUTZ84(c=}vpQsE9(+0Ll~s*88>tAyRCH2W=7NmI#C=BiUDuK-<#ZwM(Ozu#kH zE0H2@xhc0up~iXL7rn>^g15td^7glopgpW}^g*G!y==|Di-m(D zskY0HSRhsei_b`Q`Bic3>=fu_u@!U4H=?XyzzDD3!s}QljPyb2P<$Il%DZ-{_Tz^h zWB}nq#Cmy3YFMRf?+IJpZA?RoytY+pK*y6QI!tU}zc@i~eCZ3kl07i2$4w*bi#=wG zR9NEEWfJJa;V>?F$D^2n{U;(gpAykRwU;#+RT+0eZwLYrD<*IDyQ50hq{uc=zQ1?u zEcBJmuH7vraq(tGU3Ho?TIjYQYvoft_FG1165XOGsXgfkANVQ211Db`{31?_rAVPb zJ(`!JF~+RhI{KNUCpneaB}Bv-nq`$YEe%zuX7%W~i->Xv;@=(Gaq(d;dIn6R!RJb( zZLJ=k`Z)6O+liruVLgfAa9;~6U0hFR4xqZx{RN!boAiZwBFuz|Zq&%*7cbDVi9<%Mf?{ObYkf3eBbrJAL!2zw_mAst*03hbFjPU0^FnpR|u-z8A+b#e~*W z_j`W$_PZoxYpxz0#yc#Xt=65H)y81GGT6eSRUtKg8(k&nlgs}HTGeM1v#Ba z{MAzN03#<@B+)EiEju2n2<|p!iH~``g8Q*5pFU!IdY}RI8wWI~R$oS=NC%z~7eoC8 zguDn7amPfV>AABbNji=+#i4-)Fqb{M1tan5Baf1lmIs~4MV2qdp^5I*fN$~i!Np;x*bc5h6(Qn*?WMo2Z;B-@fJvjO@a`Z(hqrfogqvHTEHzi-M$z zfZ<0UPrf=rN{(Yh%6eS`Vo75fQXh$g&(9SGBZJY@E(;a(AOA!TvV z<3p)BKw|Ha`%Zzz0<7`RI+88KA?Qh)Z zJOP1Vr>nAZnm4$YQ}-+uPCU2{5tY!HU(pElvV_(o62lVef&(KAptQ_p=C>I3+>b)= zxuctqqLtUIh@~quI~`h{309F}E~%s?G*DHb%$;6E8#^HgTL}F(bqiWm^=!Cc=&RMz z<-pj1>xhu1gnJ5JSs-(1Kt1EMKo62&G^t(Y0AJaYNdW$i4OWDa=&{aW3hsiMQ=kQ) zR^d8y+r~R;yvGkXC`w(<>JGAQB9BYW_s$wI%ox66CTA;8zJvSh0-M{13me0BH6VHJ zP%{npBM27FBE0aS)gCHQ{%nn56yYnqGFC3<6~j{(H8CVRkhsYkuoDQx(vWk7|5!09 zwq%-(kE|JA;X%*K%+#p-+Wkb@z0J?M^G=CSzfDvVgH;4XkH4PPBAq6BT>Qc5ENJ1y z7bbenix{40G%Tet<>Dq3Dxj8w=*W13#fNl;eM}M|?IZo?$s`xACirq7R1yC>C$bJh zw_>pB&7W<2B6r}G#RzO;GFQYy;#dst&$lh<7aID~=1xR49dUR){@;@pE2##O`J17Y zV|ju0smc?dYF3!Dv0xh2_DJ+i96_+p$WN)e39oBnj-Ql8}nbC_Ju)h>z#p zLp%7&GWVDb+0>2DD*J>i_=H(gy?;>tzN2jYFCo<>LM?M_24cE0W=&$cBJ@otZ@G0B z29o13rw&EyVwSa&uWs$`VUs{dBU|&-e;*Oo)cJ#x{I0pU8|WCmJrdIlcW4wDE-%i` zZ8%Wd?L0DRXALRT5r}h2*eux_K4(_T^~zJm-t!<-p7P|$h%*eYtE&!M)jC7&-TBpA zo_cryt>>nK{3~mpYnk<1*-rFrczw-v4N-u2{VrjD31VaFh#S3E9M(&(dDOKy5uW8t zl1Ux(Hn*7*0TXYFS2Q_YLNdP{0|g+Q{Be4^62JN0qzo$J6CR-*hnej^pYl0GTP%C` zSik36kV#>LHE(t}2=l*U3;Vk@+bzR2>Z0$0vOxZrqT_QP{6m!Y!k06S5{A`^FG-h! zV_7+tQ~(9<*9e$C>=A|{SlD9fw@^YcD>H-H>k1?YR`;pg<9InL*fyz2j zbo8M%s;C*AuA*uK_U3JvPmep2yKXy?U=g7SRL{upNZV{*(010x896-^O-F`GW9KBL zecD`HR`jcB#LRkYea#LyNwO<)#t~fneUQpL>=e2awn))uV{5PTViIdlfy60?qqv#E=*Lqo1MExK zTAxfO*5{n?LdgtIdCm~Y?JhHr9*Dy~*Y|uDAZ{@+xX+k&ktGsb zN{Xf2#}Vsf=6$e}Lq=e1>Faft!0Aj_G;0pFHWQd|L}iBGXeaQyRQa!d&yNh9&YMdP zY9iIi)I&FawTp@PI$6f@UX;Cvk%&HVXtkoiaMn0I2{tl%`29jfWKh(?kWNaWSE2h5 z5==Rn1TG_|82F|QLoBO3I2e{v~27d3=NG&i_`=_ea?T8|rjNOnBivhQP$ zt=`&?Z#Vs&0sh&6I(kHCFRw~Zo6{;}QA_jT5ro%V?-%hi(d#2i@O5pX^=CL;uYIov z)a}qQE}uOZWjT*e3@1%`x>(AgMoiDnu zb`-a)nt&o2Gm$QFHnO==vu@K&Lu+aTddl+8woxg_7>xSMcKKZCGn+Bd=_dBR^d5T8 z<0r3ztd!Bh^C(;4dtLvZy!=v^BB~=12=`x{_RDVINL{1rT5`;>x_)EoNo9LxVI9AdBR(I9ha~2DOYKJXGvWLZWy-b8vbT(CvunaegF6Hd?(Xic#oZl(l~P;_MT1*QAW$^8ySr;~ zTC~MoipVI zz=ARAVrfNqwTo|aSqLeoNxW5t!Kq#BR{00ESq2>4 z4ZhFV_TenkZXda>0l^W2dvo-|#&0;HQGzIJ1x4#+S;9V`!9?3-6v@Zl2AI_T`Z)Yv zfLHg94x3hY3UMeZrA-pt`yGwk_{?urr*+TF_@Vzts@;#W7OrydtnunKbkHwF%5asD zk9;g9;&l!2HYFzX z@REP3xY90Do@W$xPwf5;ViU1Y%FZlS8VwB^z@;2aqJfk|tmZHacMToGrfIfVIqz7= zi_6?yb?OPzxRhwjF7ZVrDMd55t9S0u_Q+O-!-`q=J*E|0Mf~K(vVK`>E|r6F6vBJtHa_F6O_Ez z(OEt+H0#H6%iz=?*jY{CV+P$rg2KFtRKsyNvnqXX-x6>)>A{yNNKH&pg$#z-8Y@~* zs|E#>hoTdF_P3@cDUs_8_UQM{^%K%zwF=z}-@P_n(eky~-w{P@-EuiL%#M=B7QCmW zaMx2K^xzp|>~%&4zt<$`f76CY5`MYzujrt>;{S|w8_55g)uV?=X_vNDwYddux&N^!4EZ1M+v zBekYDl?gwM1R=s>r~;q~^pe=^>%lWmVc7vf;D-vE$=}$C4kc|5la~U$;89}98Fp_Q&yTxyREg?VmKbgv3D|>fv2W}egk+fYQ>0tPe8%~eV;_W43KV|B zQ25G?c)}NjiHNNV%swV{>$%8%PS|+wH%@*PX{L6i*yc+zSkCuJ{e@I^L7d&|oo+C@ z*X##mtoF(2nNUsApTnF5aGStfp^35NajS4t`%?)pe=8BnlH^s8-+?1dFn4}^{-6n# zcw~&Q=(cn57hmt)#aTc;QrS!@6fW*o1Z9Z*%^$BbWnpbPgENz9aNdW)^NX(4}_jb(L5==R;sKdWOrapwJ{EkEfQp3VibIH_gH#*u16Dx zb7$~h3nJ591=7EaK6372{{T#6ZlAzvblq&?VK=iNS$;m;U9b1-I4!({9pDdFK#s&Q zCCmNqdg5aTEDK+Ms1mpc*4LBggo?itah};I(a)T)b%bezW2zybX^#LlB-iUUekfCN zGRy3Ql3K+#tSx{{ahjXKw?h#Z56f)gI_p%I-DA1Us*W|I(wVqapM zjf*fzP>l5`+XsLcfC^F%`8Tvym=>(ySInvU+J1`4iJs`tcb2$z4BNegd*>0dU~N5q zr^Areb*|$!sjLu1cqKgQ*YhnMZgwAdOcIIPFz;)yr_;3zzii@yUVsh->RYH6o;(a~V>ThLZAEY2f zmxh6nHcqS0}drd z3kfsK`Cd=vg0+2qXU#!i^KR&^MDrG#55}xwWRy`jzZY^8|Mti(&F@=-Ge_-cy(PGX zGJH@exE}MUwz7vDSEn2@qMK6k_~v(GB*>U@we+np4g9b4Z=LemN&!4=0-gU(bzR{I zyD@q9va(uU!w>nxfe=?aL)hCJ@}^ zh3)RJUsQ7cp5H0Es-(grc+Lbk+H(p#sE-n|VnoYKrWbd{Irz1#yO6mwMfv4y9dnT1 zph|Kdldn0>`A<=nc{Ae0yfMbRQI=I|_h%GCr)Kbya?o4%TOh~`&1Tijx3T#zQtX5+z5Y7e~-1rh`~Qidi&$hAWU z2#JErYpC#so-YqXDd}#^6crc@w9ydta-dva94`qeBnTS6s2W#WOQ$a z2c{j7090Ld*YqD+;vHnIi_F{$)GHmJ{ve_<4QPehk;JFBzsqSykL*ir{)WB0&nzJ1 z$p=unzBbFME?8n6@ydxRlmgjM^7&t2rP?i@EELGB5i|Av0~nsCl$8HV>{ivd@DCu~ z`GZODP^|H2>FW28Zv$I{MnRBfzYLqtG$2w~BiL$(Fpg+fI|$s%?oDm$T5osFemRCG<%c z+jEwI?MTSAdj$pA8~Gj*kqyE}G}c{|F3iJj3E3Cwk@v!T?_AwIL?j*%q|2(x zM&z78Fcs+>{B0Occ1@ip_<{jG5$oNG!h6P@U<(WaNHK-<(@Havu_~uXYkZY;8K?iu z&0_&B@0###Gj?QDkTcnbi7e7c^N zPGeg>vc>!40-$;6AK_xo*Pv2|Oqp~$P}C~$Y+iXcmPS5Z6&H=R*XW6CL=A%c)eW}< zg?|CEhqdI8yv>0gP!uA4qNG_34)J+|zex9uAM#kVvaqu7f&#vjQL}4?W0e?UX{*{y zoFF*AeV#TWO9mR8+hlg&=lF|=UXpQ)sYqR*xs{3sF7vn~0q zs;lOhko;eo{bE$;H@#(ahdjUF@(nZ2v zoM77l>X@r`VQ0nJ^>Tk(MZgL|rzyvTKzkvO666BAvQz%_5tkn`uk%s(Dsbt$@+fmD zbFDg+G_xPX>P}vGBVJP~dI%UZGmUQ|AfcCCp?r&7Uf`L>*w~vrLetKfZcmEQ`2r~j zKOc;lCwZVaV4XiTnn#(C*Rk6BL#-4l6CSS^c~Y8nw=!eDXPMqt58=K8VUe!Wox;Be zUG#LE^b^d_y{@BjkQ9SG%c_4;r;T?Yia@X&{*j*#N@Fa)EA*0rLS`BD#ymatd zIf~|+naX}4=*t(}e~YIYwUcQ52d8x!HbKRdQInY2Q87(4V>}NON6PEy^tW$apwG;@ ztfmPwxTmr%ha{=Y{M!F>;WJaTv#=ZWSKLlSSPYTFG3#7u7DZus^n^$@@nS%G;r{)U zL$V21um)&ltkKa zJrCO8l|+e&qkQ10hcIpZ2p4gQIOFQOXWOG9P+nL;m|J~_=Rj=$OM>2_B&=i%*)5dM z)Hz_QFT3hAR3O7;n~oqA#+1>bx}$22nnMCa^QbWBq5_!Xt#tU~;pK9XdclqLL6ZCM!{887vz!-LV;FYWdxG zW$E!7VzLUMmiQZNcn|Sw>)5-q_OVIwqXGXOKFGkA_=v9e=vdQABT`0RJsjr7d8=MDMATb{~JGK_;yA&~DD=`mnJ&ZZ{lvZHJv*?H-KSCR6 zehVX2l!EcItWT2IFmyebe=qa7@1AvSjwiO+0_5+?8Y8E?)%uP74mb}L2>(coiY{1M zR}w&YUf_+I(?m6u-@KD@q=czUQyz0nwBU-_)|q5A9u&h(7(zpKj5`u-U%YSsk$oUh z-fr{P%GXMFSJ#s;bbDUg8lOjmg(@D`pPI8Q**;P7I!Rkqb>pES0DSIquT~ilh&HsN z30u)47bxcPTGr8#DG&H*LTOqy&wo!Q|1rJ(xF@0vMM)`mMa5EzF=EvJV$;INB5PUW zQ}DIE$|LV_0i1tMrX-2Qv++z~C1a;h+M}fsSIB}9Z;_Wa{>y_{LDk8Yc}V)YsSvQ; z>&N~ZkK(9d4vqzJKhf@tt&@-JFS>I4Y>n+y3$$Vp;9t%cTZMM6c|L|TuK|0e!;-{)*M)G@7@J5-X zcGT)kTerhgUSfosB{8R|FN!g>(MhM$q^wibn@I#qZFoLz-EU8nj%K%>*{8LpD8Z32 zD$Hznk^9Hw<(_mxwh-!%BJ|4UZn4V3T0#Jcp7)S_VZ>G4N1yLg^o>uRCIQfv z3s-aP!oi9Z)RsO}+UjmIbB_QCbcIAc;hF$XkFsavgv5E`s%E$%)5BRwR@EZU4gL_x z5~pBTZVZ`ce-Py-< zUcoV{t6ZwY^Ii0zrO$X$am8xdBo@4uP3Y%I#btj81d2G5bi~8+#GjH0$KDK7LYgu; zydN0f$B1AEZ4jBg%P||bykE;wK8eLG6OZ2NYbf#*K*Ep?Yx>ch`HmZ?tFpS7FYhb_ zna5C~3E>{wB#+0lHIz}=jb=jOFC}h%3V$aBfj~yYxJ5HodV?KE|Ju${U$;7CY>jv(8DV!#Re33~-irt@3QgUmBAt96d^-0;qdiuu+UaL8WB#w5y8kVh_ zDFn*%F=68NRx}B%2#W&*xvMQrxItb$yy{G`iZIyidnat9D1XC!+A(DSp)ETpI!Kj!a%a84Bii93aQ5FRC`l1Iq*xfo#)5n7Bc zBdhL|cfHAjlBfcFuM=JH#hIF>8=-Zl!vYl1)v#>z{rl0oveyQ1jS4ZYuOBG6ln^Ty zUs!>b$=5@^b6uiC&0$4^Q3#)k5DVS>G`$5HmxACEBXP>?rh=Ca9mu+)r{(22jv2?A z5_N9)Q6h0lUr3UM(5)shb+*&WN$*jm{u;S8$%;}6DG%=_@D<`a(oJCzv~j%{D6~p zw4meAnT-l+DE0@Ai0jqHx#~w%s4XUm>^xCgQTALbX-2~GCbwS8+t4piT^p(y7M_I` zq04TPy(pI02Pk>Vpy==F7`Fl|tJGbU47~E>+`{`@&rUQ1_bD=5(92`&s~S}T=uh@6 z2S-MmFbD5AORm-Gux{GhR!#*7__97w)SJC6-xwC=UPN1c0+#^M4~;Q~ZW@yu0~N}E7(s}DUV z@A4TokIa&6_Nu?ArPb=(%@_rS#V{)Bk349}erp-;Bv@>wlrt)T7Z8Q^CX=Srt#FTo z>2QpL&l$Ibzh%JOPh4i>dkCCpR|0pGk%3F&+v`igNoH25tv<6DqJ_78(4tKKnr2BJ zohjW;i}0HyFZ?-Hnipynp{<|ET-9+@e2ybs0pHGM>2;lg{rx3mJ!Ouz{Dp<BjtWPszY!PUzFV;c~Yf zr@k-Jb7_TT$BwR~k^gnhCvg#cUK40p2>Iq$OwHh>dl44P!##1#G$0cF48O_`m*Wk` z=z_^{4dnFzG7$C$dlD9JI!gNEz$)+{0Kk=)+1pcZ^Q6fA3_(&V_si@xXBDvWt~x>G zPqxNe!S+tT2yMbxOP$y13T*+s;~xwmM;b&p8lnwa?~wl*bfWWMQ-bEE6UNik$q@B3 z@#HWTRnnK~+1K7o=Eb!mLKoA7*G^z(PH|)&=;4>P%Jj&gK*WWk`TgaAl`TPtW1yh{ zs(o<7C8)?v0uzK@a6HS7t74h~AUjim)t?-M|>D%x-53Cyd28~CW< zVtP#R8ws3d!*y}>SN3`7HY4=`IUG$FRMkOojxI4zNdT&}t8gvg! z%NVeqycI#)vxZ5@kxcOjQHUo+;AjOgW|O~&ZmaFF45I>?j<}$Z2O3?CC!@-A7LA8Z zh#R9iuiQ;%=50wy*@>&MGiMF1bw>#S^Fhd>lT&Ib*Cwu#L&S`rgBeJpd~!Wv7MIyJ zF=#_Yeq?@}xo37lt;p@O9I>Gz9%mpon#DK>*B>u@@>?toxl>;Ljm86>gF%6aaL@`b zp&@8lo#rO*dh9200#=%SuJjioJf-+x{)loQ?Igh!HZxQ2%af^caP7#s@lZaI(L_8! z6y9l`rlVEyuX4#ACuU30KDbN%KLAw8Nwp6ElRV9Zg`2%ybd!2(#DNw2T$v8P9=1u6 zG1@6u`HDg;UM!k`QMvAp&N+$vQN zK+0PUC=v2(rZ=A0S=ldrD(Q~TN5PC(gV4IcrJCqDuid3XgsZR*N`RVp^q!bt4=bYc zL3zPWD>6MYd(Ux3hd+~=5{-*T?_G?(AGC$A-(8SRtAVr9W+wyBozf=K( zC-xpjey^3Vm6a9I&eJ1I-Gv;i-xUNsU1(rY}Oki6i=eH0&dRWy`Ka@G7DNcI@CJCLF`?lngxKbn4Hmb z%ieUjkL!3)G}IY%tgTM}+E?tXwpr#{=&1Dnv75Z?RRf?A%-$GE%d%p(|(Fs`1LrZ_ivFBN^{?g}7?8|;=+EV#f>FQr z*D0z00g$SR(0#CveT4PuCUbt@_e%L{SW`LTUOVzrgzzH@af<@$70WUV_T9$LMbAuH z0m^U6%nlrDgnrBJL3XisjN6P2QPRQvJ+aUyVTG2bo-kLzd}oNElu>2e$!o*w6}>7^ zcdhqz&oYYy2p&aS*NfJk-N>7YSBnD5FuEB;nPuiv_Cv1_$H2p1n%Tq$A3qY!)$znR z3PoP?4CLUr+X`mh&KkT_W~+PDzH2@_sXZt+iNqK~N2ReE<;*D<;W-ezLd1lBAf~-# z;eKNKz=qs!^;(*tFgWMP9*4qPsZ^Hc!$!N==n(Hf<=D|CVsZ}!`fT)|8p-(c!!s!} zO<`kNJRZgsfpC{Z`=}pH6#Ho9RBpv^t2zl;#(_^^r}EU($&SP+RbVwXXU5x3tu{sb z+&KthHv}=kBpE8PLU5U8JEnm;IAEhm3}Q*jPj3~H{{eVWY>}v$&_XZ$It6Bp`Q&2e zXiOvzWbO?MDO2au3M$>l2^=#zvo2Q{$(1E%do$D zsVOmISMio?Y@BR6fc!0Em#FUL@`(dIRor64PLSoImqjYFRb31pC>5-qtOkdC$uyr z79?j!QXu8O;zTueh_1!-4xuFgaaT1-K0902r!K1k3uETzVnl5sT{uwJO-3B_ z57I0R{sCaJjGAjZDy^7E`O(irZ;b~M9uv}_9tjR^xx0C7C}<|TnDWJR%~u$utHdv3 zNH@&_pA#&9FLtqHYGejwYOsV(FXz}VBr!N5HXu*nFEcE6Ou!JQk+ZYCuWYOaluIF^ zi4ZDlF^Px|Mq2bU?#VqE9CFAa7Yt?onlnw&B0F@IsBB*t6hR8vN(Ix2eX^&q!wrsv zJj0INi`=~JEA|AcWi1di*6p_j2P0?R6GfwklqzZ&bI@X#6E8X7LnT{a@fmuSX7n^y z6ld?uhaGH8(i5AG)`e_6yInHMLGemS+GyN6JmF_=GVjKXSL)uRS>WdW8S;JI_KpEr zhHs2w(@Z!KXs9gb2IVZDK0n8c`vhf894f2G=Wbc^TqNbr)?#4RxP{6(u15$7ec!aK z9(Q0+EN#0+fWO?|^eVdu7>e6;lTmPctSqcT@(OW(*GD7rG`J)vep!cc!M(>JyE|Io z)Q7SYvsru}2khfMZN4Q6pTSNS!r-Pgr(1$z(K=%-ttdtNpu86~!#ndJrsgt@#nfW6 zA6%P!KJs9V*k@<~CKT-*>gUeq#5)42RQ1C~>yn=^Jy+S%XbUKp#il{4{}pqklW}F5 z5E|>|f_@L|JMbVi86z5|BJ6?&PjliVdr%_U3E$NQ&@*em5EPjw`(8xkD7ftt=b4Q}Jl8wxvS@4u}H zB*Y~(pmx(^c~fQ3VFD=>cmUuElq6oydT2SAWY-9O1G!n?JM?(X$c({ptBeKrp0ES) zh2r{9n9#4E?IN^ih5c`uw2JlhYNKnEG0ZQU{ST?O#i+Rc!ng zH~QW#_I2>ul+9+S7fYR`Yp@i6-(}D$KMLS06QE1vu?|YRzt18c{Z}EZ`}01U)mcUi z=2btlipi}*u?PZ)S;Ka-`AbGH&VyLYU~fbuVv;$Vbc|uk{L;C;Y*cjy#pgE14kNhg zx~f>CU7;j}xP8A|$5F^LaJ^fE+k!wOUdJ@Be*hL%5{!}FLja_YmWzl1%2taYJ^oA|C>LL%r*n=vJt|r_hkzZl zE||l-h_xM8jZH6FDf}vD?QThZ8~!`NTffb4~g|OG{H)4J=rEMggYVFz)zoD+xo%Q#=|?j17w~_BMDh zs^t$*SYO7SArM%>V;<#S`FTaIjIM!sv(xj+`#lP6l9$B{4l7&ewQrtAqQmYlP^Vo{ z48y7IB5iS{5$D$^W48||RwF+b7-9g&gOT7;HGKf*pf|Sobht&+V}yP8WH*!WKpu9o zuty6|_PhBebkouh^wbetu_LxkIio()BU(7)T^5aE!F~$)tf&sHX!R}19HUu&_v$*e z4i}jtYDxAisHQ2!IBS@gE;i@1_zm?aAw4R!l3VApj0SkC+&3xdZL6>h(`p}HMcFN9 z*XIXH497igq4pglWsNFLTqTmnc#b~q;SWpYUq7vUWnmMz7L7lNdwxGcDzq&Or_wdf zAEt7rI^r*8$I^R2S;494w==cJOwJY29y>{oy76$pvT~4TGUr?C4>i72;0bO8&>EK^GKcV!-I@e>~xlti$6<#OcYhZ>fm14N%Gga^U?{smtPgEgSYMwLV` z|D2@1%tvWmg3#o{A30N*fI0felR8pP)P`p^QN`)*rk{22C43ldkdB{l4JXqq2>QpP z4)QxO`66~i={*&uvndEQcOb|;#QDzm{%cp*t_Jp43DfQfr-ma6Ari?9HL6wVF7<2; zbTG2J4a;cj`sVmIr{MuF}@Is>8sU77E6pzZJhQDErN#y$kk1d)_(+0f9t_rB09jhTgAlvx5! zL$6^iF?y#muGm058o*biX(@Jhyg=deRE?xUm>CYGHkR0{aGLX3={Iq*lEIqYo78o4+(@^7K$UoVgSmOjH;ic+Y~a>G!Wu*!j`fWL!0eC(v-vEg5!Ns&)6lGikLIX7E*K ztglgqbs7lsyFvLS^#06fyc1g0z{tvg+Oo%}Db!^l5yqiwc56T-quE~^Pk$Eb=J3wJ zs&D*=iooCx)wWIgIo1y5=2jP?R;5f)5VS;39^li0{1Y<^^waSAJ`K1nzd=*A2R>$7 z{!kVs6N0h8fO8EKrZ>9cl1jd0(Kv+d&of0>@r{LoI^?*-i47LVL6M!NyiE9#^ers(AT_33I{L68e|D&BE7-9i&G~CmO!KXOw_i8gTRL#RCu@Ri8iUf_IQw$NaFuA!o zxsr`*&>7gjqeZodVZI@Z7g+SCPEH1PrKYKWa}VPv(^$)|m5j{%`*sMu(hJpBrdZNl zh+on?D`PKIO;^{W=FLmF5VN!Zun!+v)!c^>rU5-QT{3AXZ>ykgj`L=7()!42Zd98$ zNE=fcG9H|1I`iOozRkBRf~9B2*Xm$p(C2LEP@&4$16H&-0VhRlLI{(EOF{3B zKhSZrteQY-5s~!VPk7_|{@l{5uYp?<==?OKcyC9s8K8DGr}o`qOIvmB2>so@^56P| z*zj)~HozO|15A!>m>!hq3&z>RJ4hzgfN5H@l;A9dy|80k#y37ic8v7>)nG-b@w#%% zdKy(kkDb!ybT5BFtCBUrcze52?#=7(&(2Op&aGAH&brfo!}0bnam6jl)f*Iq7BWTf zrzh9P``r&&*5Rwc zzCRJJ-5JG(WI^nCC>}!DEqfJXAh81zia~GmcnW}2j4Waj-t0AUH*5YsR8j~L3pEJF zkT)yQJg0~{Ne`uVQ$q~O!vmN5ivKK^VB=rh@=9}8i7@yAeJu#4;=1@JjKVVh^ARB> zmSQdD&PfU98Pzv+^q=&XA~Gn3_NSj}RIPnS6-7C?b%(X8%S``rl~aZ=oRmphf+BsD zduuwAkAD^)DEBok5k{NH0Ffco8gVQC?u{BNt1KC6-fWZ<79;tiG1aSRs8+pJ_$|ze zi{hw$gS&#&;t;eWblHS=f$=r9C6f7g{Q3ca0+D}jtK?R7O4;gqQUo^A1Y}S>Q3w?N zM9R?p3l3g?ggVPMAl)qZD%ek zM#qQOCHt>h{NWw;$YuW?5dn8gOcJWaHvBnTBHk*Mh5ozU5IO@&3gVDlWl++NnD})X zU&>yqpNM4(5NmFKxu%>^a)6E*8AbXjdqvd?5z)m^m`BaBD4N8vMo{4fUC~<8=n!FE z$HCu-$Y|bca~jj0dPkc>A!)yv{H>*9$nN83f8uQ&Fgy{_oF&GScwAX^&FW#-DmFNx zM+}a3UUhcUW+3j$$-xafuPJHXzX#M~IVRXCbk1-;$C8&+o`WiUo)z|Zg=K+*!8?#5 zO}onUo>UrKQ8m(+QK1v66y0)xuc*WvV{1xke-VW!8W!#Dt6o{OYeo{?V|ED+d3$oV zQ#j_<_M-MTO7m+1cJ5yrE(y2Hz5;U;=HwpxVPdbb4vLY88eSsf0%P0%uE83 z#AI@6b$9+5*Pjz3IAn^2SHsyxZ0}^;Jzo;4on1DAsGPA>^HV-PB%Ocpp6@RT&{I_k zKUk?wK^gPc+u5vBP`|@Wr1yeWlR*JyCVnrIDpu&Vno`&diwlD9W|LiVCWU!H#r|7| z!?sKEMW1~-7ii=PHH@0LZCtI4PovD{$Zhq?+EU3s6aKKz{tcm{!y`(DOR9~#A!+b1 z-%3J)#AJygVn#^A6zK5v4DY?24*J{5Z@4v?4vn;tWp7KX$oWWS{QPAw7QrjW%q5v1 z6zdo<0i_#yxb{c=p~;6`2s~sua%3K1xEQuQ0Cwcx6y~6Z4ox8&^c@1OIS)gB;WHH_ zl|`D_Oks3smNm2vxH7dxHD#+BYCEvmFKmn#No01gTxn+G=_)?imiatAmHNQ&OPp~%#EK=}$kcAf?gb?=s_T7UTXGvcdsOuV*!(?AH3Y&AqY$^)Bl^UCC{#6QO#QW@1iVa=7 zTeiDnwdt>idfTN>YqLQ6qAVL{?z$){`aG2hQa%l^RD;4j0+8qGVwn?^7I7y@{cczY z-<<$3P3@-j2uqy)w#s;}wP%As3|b-{D@#Yt*0aBdf>J{l@YlIu#kA5@Reo80^*d%5b~(%GhasUOv(m6N_jWw3{M?5I3*tVh)I=tAcz2B| z&D@0Aq9|}>b!C|^3G*GhJPr?lF$t0owMXy4gr_UNu!bPLy+>3Fk|hKnp#o6Q&{5G) zk&#f){;d{-j6#UYAbE%jvu6@E%nIqT`>%o! zG7^#;;AS^4BwNR_jH>=8c2LQ5V48{_?EFm-64~Y}Yu#E}8YtM@#Q5Kru+>6;m#rGv zv*|YX)f$sJi#B)S4B99$7aL3&l9bv%)@crL7Xp<2p)cqK(cQ!f)7pCSu_I zM&v`6z;Ee&@9il>>K_A(u*F<<40r*avK4N2n`tAGY-dPjz0xrAZJdb<9&+N3c&#Dm zx$Mpu0=u3GOYlA2ni|mo@*Rr_A#zZW^yLl3?XID?Qi;!wSN-G&@Da#Pgx!9lhpd>Gi@!&F;?!s! zs`qGwq4IuMtdi6FAHZ^Sn5iw@E#lK<1_6SlU)VTu_^V2gJFw|i)eWZi7-s?E$AjK1 z7Na2Jx-RNje}@8=m$ET$FvJwg|9-vdMx?7x`UkM@@DHHxf0v>)mQ%S(AJlM8_k9*N zk{JI^+x0>!_Bi0@e~Xa*AHew7KY-Bxe!!$^ok(p5BNc_szRl%N^dsoqK-fNq?hgrFS>hiXX=P^>D2-f43iyum|5t+_PG(nz z^D)2MORE39_dSgfB5|}yp1Nn>W5eJkV`DAisQ#a%{r{7c;dnUQ($vOr|G_M;@w6+> zrx0xmV9w>fr<~EwusHaiSW{%N{S)bTJG}|rw2r;Lw4ODjKT*!QpVw*~OTF=g%b7c* zKmXToQmVP|z=zgF94+EKu^Vo!?^4};mC4z^9iT3HQL7W={b2phW1|%9^AuU9pHu{k zm(+T|+niWQ;^{2na|6gw^^`6D((n&}NVT@Gk;+UpbRZ{;36EFn1`*oz77t}Z> zXB(cX#yY(3pfmouu<)poELRqwZJl%Sqr{n|r1P<``cfd}3t7*J>6moz%{85}K;uKx z16F4|O=%>C$a);gj+6+qX)a^)jsGec*(dv7tdsa^jCq6C)vrI_3|RlbvDXq^2+ZVc zQQ2YB&|sZ&U#g=&Bo2U075^#YkHs z9Q8#1UxAWOirys22dUIaM(B?WUplypv*Smk729GS{bUQW&f@7ekM1wF;eSnReb4bj zI=INox+Y{zQI&3`mInWvYRlCkbYA5f3s3{_u$}vvKMNW;GT=Hl%k41JT~`gkzd3IwKLLwbdstqISepeb-xIFs#0e6$&?nu zF;H?ol}KKW;hjoqsiQRw?v`fa8ZYHtf&bXGth2dTK)v7MM!IS=lj(?ZGW$(}o+nb) zmebzEurT5Dkeq0a&qAO4o%c8=Wt4?m6oG{lOu;qh58RI*ALnA zhLV)_b8QTs$A+-~H2=F&GXqt;^t3>uQ%S}*=)`cs&UoYU|FHECL$hW6P; zq>q-|BpK1wg&$Nf42a5QDvYD;yqS^Io8nAjMX@E&BAP&k_$4ecqq1xr(y8iFX)$f4 z^oX_AfI<3`&j0J;_!&n-W5ZaR`xB{rt!3_#yhL%%ywO^#LJ^~nuIP&voN&6%tb5yS zZkH_YihDR^hmPJ$@6wz;W_)seShxwk{yj-F3!Q$g%nqNDrzAC-N_efJ@JtFG-~B1f zU!|yoSU*;hQAmj;0+DYP<+Dvv!>VQEq64GHC0xi*)girO-Q%YceD=7r+9-~P)2Jr< ze^Px=(4SNwgWUwuQCIZDrUo_|477%o%O3-8;q}CpsR@63?kY+pMLIExXEv^wy*S%y<16<~NAA<-ebdIz{ayE4EIvLt8epRk$q z8VwVQ=V!(IEtT%_?=5-0I*v=j8YU5oH=}M3^V}vfjs6UFV<8>7oeG_Oi=$K3-KIRq zL<-L-A~JPdtoAFIJThd)TXiTAawel>LgJG+)NKC;uu<^qM-_K0mNzx81ii1R-3ET> zvx4`GvUqd~Gc|#UgjTLIMQJrn&;G0fR;Pf{ z0~V3GVuX(p@PlQDZ(wePBhn1}+bYD4G_W`PuCO`s4@qhAN!uYL%$#Z#k;5F64{a{b zsVJasGY(sFLLRu`lDE5Bf#k{B z&P_TUHAd9jP*iWTX86eN)}^7>vo}gr(Lse5u}l$zltaqWRFTea{pL>$PMzu48$q4z zvF&)xQvwt$z%i;t2D2rzAfqUes(ulC`-USabckD2N%}I}&%sb(0a> z!djg$r-6A$M)~YN^)n_^YuJob%ClX+Z20NW>~XICp8$p}dD0%M4L4-v1|_m0_8zOb z^DB$p10TA!e9Mk6nQ_JQE;znr#}~}F;`x!1FP$~M=dV{0^YDC&J199z{f;Iw$SsdyQZbBn0%jg4^3sTkIaYm;9f%s8mA^27^V z@`vwZ?^#%(D`0cUA;60EqVaIYA z2hb@th8>3FY>oPb1};2KQGfCiUNkAC&9c`}U7){mxbLFk1n8L1LU?HCgPKYpaFa`n zf}NXhb9kC9rjxkNt|$!E1qpLbM1|Tv<|~c=05M!n_bIM-x&_Coc_8Gh`>Q_c&$_ej zi9YH()jZpko@O^Z({dD!i0XYK9zjfaaIMwhPY-I^8mSmq?jLQW!qygrwRS`p)|kZZZgwcGm9xgqgvMkqKIIY!r&4qmesr0OU6vtlU;QOin05qYSsX+@2V#4er zI)v;bM?`Q@r(l2twK=bi>8*W&*&Agy0g9Qn2tP$89}y3l*MHr2k$ZyeP?ZT+ZV{T% zb*8q{qUsiHLo`JdK;%eW>w&b6;5SW&?K1&Q1DT-FL5jpcL2HPl{iz)B zhDggk;TN-@Mn;Z_&j+U?A`T0%9_!)Hy6lg-ER<<W9c#A_#@1*th*=<@N&aS9>5c<8UuMik96j- z+JrFJXSfMX0bqW{MfPMtgv6c0nCasB6e6j=ux>Q!qWH zO2WrdidRNPX_(O9EeV6Vg~UE!gW1)=I#`EPaZrSDv5gsOY)sG6LeRL0)TXh{&=lyN zGc78L0S5q{{MFhJlbBtRU5QN4UNx7 z)V0)^AS&;`p9&-#eN*D$IfO_FvVB(_`=@ac-LwS0#R#T3(hyF1CgCM^shA!rwX?8T zc;U{8A!2Y4Vk0ro1!FLe!@7fVU67zri8+O( zJggn%De25n-2tZ*a|!x-wm5>LeW9N{8`U|CcB}~DBPd|v2w|fg5QZ`OP>qB1pwKsG z?uoHOC4|K~2edfYzNwP3U>?nVmMaL%NG))pu~<1U(zsDASDr|;IX)55Ix;j(bAh6p zB_k$Qq>#8(Akw20-gXVeKVCo+M-FM{i1WKG(V8fEQ}p#=2auzaEqxJftS%||bD6NB z#EGNh2Q`R_JXCZ*4ht8Bb{Xd*M|G+NIvXg*z!QtKqJv53qi4FR%blB~buD=U&?B!q z_X2EEk3gU4LOj)I8cdeyUHU9OAj0YzDCJ|oa5=0*BNEfZu~=uo>S)Own9R;^mKYSr$;%;=x4 zNwPLpg43dw2=Nh+M|om!QsLZeWPt~Lb>C|Diz$(m89{YVp`!QYXzEj)XTSkaSy;&i zfD`oeHREv*a#6oaJ_+!1P+}bc9YTs`%s88po*^>}Ua^=rVclV-j^b-nN~K(^XSi7e zPD=AB&gRjo@0N-?hU&5q(LYZ_d{SvO$+B7o`HzVXA@Mu`qK;Nfzy_*F1nn$%(PJ=g zh3AB1qhyY742-{vC5XUcFij4cGf&g_=5C=k%elhBc3i_yoN}Z&0JBJn8{4^wsrqmx-JgGV14w*z`02{biWEsco9kX*tUYXPxf!nLFn8XMhi zK~Qd2Xc7)f@m9zZ4~v18Ms7gyW`=q4wnqipg56Qf^D`h(vUvt(lLZXZsEm__Wes;# z=$Z{GPR$TUgB$qTHy&V)@y*88W>mPFx>#w8wL-Z9WVMk%gP7z#4PI&pC&V~125M^7 z%-9h^L-AvY>5#HEfYyKpl(XM-r-hTi_@DZM+j}+G3`^)#WaN%SR)@p_%6E4zSledT zUC;9rH#bx_$Z4e|`~Lv&*K9048-Z2}O^sqv7A zE!UQox$eF}nseICN|O+5hNEW5DbkDKZQ6?sB)O=tvB#ZefUbC?ss(hudfkV^%ZZRj z6A3>37R&rR$Vh%D0_4cq7~zee0IKyWxyZ0AV{)C5JT7>@R`(T^lY4qVdW z13?2+=^pILbGUOWhDpsvu-GunsyK&qmrl zz0N7`4C-tn zhWO;@S4-vV{45?N*h!lBjSCjAc&1|DWQ^(sg?W&#eR2VoW|1ISCogrh_WW2-SqFLk z;WHfETe#fg#8Z3M{2|nii)q2zVVv+Y3aa^-JGP0l%FQ{>O8Afpl_!hvB6kx8;kvm3 z#A2Gu3TeyENzS2V8Jy$89;*+6FFbQ-nG{jv)t4~c+B9lH!?+pXa3d#$_>yxr(E{>h zG5-MaHxxM|mW>s6pEu#%rsyRw$Z~!`48~L;8 zs(aZJc%&;6k87>5=&z2;osxX4X{P3*f_zJ}1TjH_iV8Zr!u!(3?3wXX2^)@kN3dV` znWEu;#z;sMogtC2aZL9)tqnFcuL3!1B7p}!UNaG48iKYS(PlFY*xc^>01B_W?aNl` z3ux_ZJ^_vez{}7rp|x=s*$!rquu7El-GH3MJ4Mj6#|O2p9^1CQ6w4oO(VJD5X5mMW zC+p13Ij)nla&MGxJD;yU9sDH&d+c;pb*#PCBO4qb@SAePVx*YaIUwK%l?OgUz{cII zCd|5gfp$%efvgosiZ|icu_!sfw>*KmS<{ERiSP(fzLQPwv}Is6b6YcN3?3GEDN~hDiIV8gBOo zW*?^t*^~D8aC(lLqygfOmb6<#XO_FPi$l>9M}+SQ*`8);%_Ehj8*e2kHRp&D;D40e z@=X*ivavf!&$dKpBKs$Z*(jUIVeoTe2-G!U@KHboi+Uy1O;l?%_GFwZ(pW^-RNPMr zb}bxR-IG(KnDtyvJx~OlSK$4!&`!*i+5Uo2$XUoNX4t^sMbC&DUkEE`emAn_;2`^~ zPTR)gAH_V*AHYyzVwQva$k-qaHz{-5d zfsJSk8FCc%TB`9)E+*3AYBEuvjHHFetrc5>JF3(ZI}Ix&VW%~~g0Vk}Hl(cVyLBv> ziCkSgg~X~VlU>=6;i`iY9sqI_MUC!lr#CXAe`g~d>{b?GJS;xLdz*O`w6${bt9J{%~O4qDpY_MXx-S!Vdv4V zSAJZ^_plV^9LQT65yalas;rPsdqJlZ;cP7ik%Y44U(#P?*2+gSw^5==!j(!%Wa$D5FAS~3e=>gPEn;!0iS|(Af@Y!KJxqR?^vmi{lEO(nI-MruVz2GZ4zu zhR=f*7D=ltmKOrZbEFLp5CQ_X+P-Vv_F54Vy96-dIu?MBP@Xg82A2}DtgUra6$M;{ zS1ofD4CT2wHR0fJ71KR;Y`M!Hz;r7vEVpe~1d;ZY-c2rz;lP^(U@@Xr2Fg)kb752`s z8i3_+?iBHvP70M*jC^X&(z0A<4 zrw$ZK!OCKpv}hGzhL-55PY{wfHk9l!Oy-f2t;AX*aMcq{MEcMzHGq9r@TmZ)S0PxC z1Dd4pEfTNOw7I6jj(;wBg@BYvh6e1Qv_Hby_;T0wm6st1?k>yLwVvn(gj01@;9?te zQ}a8maVsj-t3IylA*ovz9of6GkmQ4}G;S_JmFj-$Mz>8)BEpcf#(279Rh z5FQM`kw7VJhec=hCcVvf6HOJfHn(^~JFI-gG0k}Hn+S^>CqlNQU4;5~cewj{e~ZKa z0F|rbaQ^`03*)f;9c$y@_h0!8Ke}c*DILPV;+oznCqw`mZW`{cYgVmV#5uwjmTIEL zK53sDx_-%gG#TYvJ8BrnidSXPMu1!AQ=^SHyDw*he(s zny*WS+3~{AT-?>rri3_+mnz;jpAzVTwzDbGzubgBV6;lLpT8y!e!@`X`MXIAz4s7_ zH|ePkLAdy(Z3y_7)5}?)H&~>74Xaiagn7>P`GRhN1VSU!S0(uPhKI!A>^TAf4`gyg z`20(WTE2SSVGu$uX!9Cftab+y?8#^-L7}t-AXTSmQ8b2rjBXy0`LVfjnzMBGoVk$%5I7{iCw8&Pq6MS76TS1hy$v$5D21(^n-Bp zhc$?8Oje}EUsI3nW79hq{cI z93*MbtSsVqT5m8F@;g;y(T`1y7Zt7|xQ~b3AE`Qcqs_+C@$roUc0BYc_}QK1D9J0e zJgjYtLrU?;u&_9j6Pm-JDW$F!5IHN)aSF5aW73@#FY-Rfbw|ULn>qDQC*3_U9*AY^1YG^hv&RcKh-<$8c@SE{{Iy;8kW zy+Vu0D-l?ZNL2n;jzpu9&G?7y`U{ZmE*FdSm;pJjAD2ZL9QY(7P{Q>}#$CELT1EJX zl-g98vsAmVQhW3i{#^x|@ekYd6S@j6o5DNjtTtxUVR>wsPO`Pa3sdYZ8#Ow@go2=i6e&3**yJjLwRft6qkRh{`zx#pe7aS-%kdzd<~Y&fmJTh@{W9Q>a`>MXIWf{WUQz$tqUr z6lH}90;B+Rj~}3$&Q=Mi-@2wElRnwFr}HhEatV;usgzoc)Z-*6JEFJI8!~usnp4UtJ|#fbXEA9 zo^aCHJJf#_^vMysU0m!QG)^rgv;FXOa_Rvy^fGS|b^qqe)bp9!wcTfwNS8$`N9xOiYua zrBcgG0_Fl!c%2|HF`zCdSJwDyy*EHGi%8sbw7y*=z)m?vL&#}_A9Sg^PFI49*y(R% z4JLdLIVBRMV+$Km0m;OXbo#K`VTs>Ao^TH;oEwl%SzS(2A8RROB@3HT57! zofbNj-X(=F%LA8;gk4ZZs5qff!8P&(r?fe!h&>fAmq_6)TV)8SAX*$ZZxvXDN=z_6e_JKT*pC8Acaw+8IFpV%cXNA z5g7+Pq8hPwyj)eK^jTHDql&ZCW9=@$;zk?$gyW!3RcX247MLMWY{;tFKr{^$&QMfh z(Nty^UEC^L1zT>4m&+@Ts$_Hz0IWBR=P^tZsZwy1T?IAMa6uJlvHIi^Rhr0XIJlj} zD7gHXofv=!fKdTT&@nK+vyD1t3e~W~@*CxDnySJ?s)gd9XfP3Tg+R$n5CX5aMN8#* zQk}XR4upW54 zB}BL=IHc^Q8?-HgnA1jH&zz$N-T99BK~ECZXk|fA7L64aRegL!cU~23v%yeQ6$L_t z2Q4p`@p)3WC~eS`M4}^~OX6-R(*_l4wP{d!rX;IZ5VrpSfR2@hK*Zb1Q=Xe*Gq}hdnj?{Q)`BSeK=|GdTym@;w`Kl`J|OX*Gkeq zvScB-7n2AZj$w0yJEn?F)NYBAsy0G%3cy0b<%Fy*SX`mX9HGk#lsRE?!sUU>({jM& zfU0dE&E+`+Ix+!H8lG!H8ViYz%0bc;2!(0j_FGHEQ%$(RnN(@|G=njT14&k!IJHo9 zI-0cjL+Gvu9&1#h=Q-wgL+P#qXZIR3!5{9d_6{0p`zcd!9uRdKAePd?KlN&V8L?A7 z;P8Lytk&9g&%!bH3ES?qjRdSz`@2*%2wV{hSwVM3AwzsDBgNBn1p~r?;Sq396a@i5 zP!UbrJFWiQUg{M*0=P#EZw;Vnx~X~cQ2_4HQ>f5>^cb5-l>Yz-2K|C_Dw8;ZaIPDL zt_ikkxUoIqFyRnX&B1nE(9+|w*-ANyxMn^O+aPO*m{?DQL~e;vf*mOm6NGZYVs?qn zGO?A73aD0sgPiSLG){9`3z<$;PB~zuQ`4;1G2gg=s9J2+mdz6?6ev)LP@^QM?{GyF zGaJTJvTm+M_KifQ24Dz=D$UaHhfYSkqN!}1vODE#lVi4u(O|OLnnhY|J?1r5eiZv7 z{Ynptf9g<`u4%eO(|Nq*Jc5A9Kutia2#C6%#1Y(!f*m;$oZLF{shH6_XifwhrywWF zuIok&R)3RqR(>q%wS7BX7Y7dGWF8#^4HWX>1qw5gwnI1>EUd)o@T+QurV-E-@eemQ zsUlN^a#~O_h#MzU?xN^ePlPFz>7Vw5$`o4ZG{cI*2FdShVq5}i+U*)a$q3{Z1a?!% zJA~Zb##0WM&4Y7y>dR5&G{R{GXhbXl5Yzx#DQYeY5_LiWD~ekyy3ktb z038*Q-)XZ{6&T_~s};7Lt)g5dL=$w}R2zlevK)ru5E)&vZbs^1QV_3#%&NOOBGOTvmwnEYj ziB>ypJ6$Hc5g=-}`0Axfl?d*DP`hL~4dW^BfQ!PS-+CJa6Zg5|T2LP1o4+u05h=r> z8;>iBaOPWSmVp&~t4Ob6t?5+avR1| zx)+6J67+7VbVw=U9-F^P5#$!aJr@<>RCtXi28gT%>f2(kV5(`>X(P(8aT>fjpsPsx zWJ=+DR*w?1we+3?`-FRW=937SK@6o0vIS&rjyDwXiLkIaV049DpWM|qepGVjl66I~ z(E|bk;+!s@5TNFU{{V0e3bolPSSq@WMx77vtQP9_3rlO!f3|gRWy1Ki4j{(65XG?r z%09WC;$?zPMVULz0t{x(as?j^jeYtFu0!! zp>L+<76DQ|O5I?qV617qhYyuwwpXy#6>RS#T~`R>6m9eyE*`IWM@W?yLX3qHi9rN2 z9ZpcJkK7Y+Lh7dr2~Q=}3TEhX&EoUVBctM+GKUqS>Or__fx5TYEAZ;Br1qR6y0Kep zSgNwEBkcxATpNv0;&eqf7@H}!R3n~LskriC zLX6RI2( zg`gQ8F$h)ZmN=~lyz+Y{_sUS->IeI52n(w}4JRp^hUvGQz^w|5kfQj>C|m-CsxXbv zjpd;c%NnY5i=>dL(P)VX2+&;_C0ZGclifxgAxImnZBsmx;Q^44iMmyd*n}R)ZFRZP z4GTbYyc8}ujHaBjrun`u3kg9&E&&w^FN@sW6mnY9?Ugzax&f`(NkiS7csnaaFg?Lm zcf7C^9OX&!az<0S84gPmp~N8oZWNCy*#7`hqz>5v2IHI*9|&qLH%b`=(11ZiBKSvM zQEEBc5&=x6+#uv@pvNMs4N7ld+_b`DYEmzwSMet17$_MR45fENA;`x$hC=?Lq|BB5 zMNcT1GEvAbJb;6cD3ndjH^sq10#SAqB<7susx#T@c5%wbX|3ZV!5XeDTERxML8?7> zY!s8J-s(=BGMkDST!$=Na}^2-f`NogsJc)pP`RNP2)n}HbqW+IQl&!k`w2{_9wZL& zmJ^$FC{cSHT2(S0BxD8(ZlOj=^P;s{0ArZnmtwfp9wlbtt+ra6=P){2M!{IEBGYD} zR5&=fpqNC$qU==m`t~WlQrr9dJq`X5nLVq%~Sm|4=@1tm7)M!@> zuseo2ttT0$KF_iM!36^ehCoDKZy8Q@>Yd{8$vNUvShfgii-6G+H=N_|3y5%AMY6c6 z%X8W%vi|_WR5%*zbzDt@p;YTt^ciL~p5V_n48$TbgAN5#s2l)WWNW2B8kJJe)-!N^<&c17T zu;{9Bwrs|gQ;S+(@lUl|Dr<=s)jv0sS_v3jSJT`;G2V?s`w3DNTV0-rhmc&W@pl46 zCH-Zk&c{*3P_zobUKGMZcxH_ytpp+MoDo)|+ijUs@#=l69&{UYdZrg#E6CN};6Yy}Pu^Ja*AhxJowa zjwHCR>k9s`rtt?;f)$5}Hn0tO-C=2NCX_A(2O=aC;f2$85weSAlC_>bO;uS^&uM)# zA=F)>`giI~abmVQDr_8ksg?o`iJk5@lv9wr1O@KMISwTWC^13;H%@pPCpeWC8{%#U zIXeVeVnGScYjzNQ7V?6%iypbja7NY+Dyf;Ll-qMU`$fXGzq zbV>t}60m@PM?~k!lDl4S7XpFJrX_E;+G*Mz#y$W}wp!o4LW`@rSJaj4{J@p%{HyMR zOOS3903k+5DcUDJO!8(EL1D%mxOWsX+I0*8jv{&*|zk z5#@0{2-;!Bn_=IC@SE9tMP3ozKYgT1cNk4s;xEAj!Zz@U~=Wvt|k1usgyGaXN+R1Sy0VB}i_~M9*XlEMK;2yvUSw5wfw{ zs@a^@&VgC2EVM8X;fmw7soUK;rZ_u8s8#5)(AQJ01F4Y!FQ|T;b&73NT3t)POk>>U zhDmuk0k~gIP_@vpH~O~{2=;=ZMa2Ms&O!sH40EJM)j3LS6+=o2WCecLK*4cJ^v4HhDaC|m}LqT^bYzrQLM@`;6rFH|Q~ zosrjmc~*M$Eaw$BLa^}$S{l}q?u}E#p}ZS`f)Iib5Frf;8W}*}-9Q~{Sm$gNIxqx{ zP-umqQi+?z^&~DdG;Vnay`#D{1ZY>NQG2CgaZ=?72<6Y`D;dwK>g2;3H5%^$~fLUge3(XR2eK z#|N>{La}jCTnbgavEJ^*Q*<1oWO}*n36#lH=`;Z?)eR9+RGv*ummiTys}b_IQFJKG zd9pb`#-Uhvh!D!AP%U@`hjkcLGa&(R2wqUQ^cYWtgrL$^2P_2&ZY5K*jR{yn^09~Eh>qP(IEnYIcK5vtrne>CbCmn z)`𝔑=~(e#?)4h(GQ6DV@gZ!)|pF1wyG;6^L_IAmA=(%6cdZZpp1LO{SnCiBfsq z7aVNZ>VD4ToWrHvVRvPL=d!Wdon~-paaKD+DuDzjhZGRVZ#@GUA)0Wm-}G!BaBUf7KKa%24N* zLMHiAr;#dDsmOH-*xXiH!~Xz6kH~_7nYu|Zn@>q427z_ zw*_((K|!SUOr`*naZh@g={8a>k>vnR!c#2uo?(>SKZQ$z+uy4{nN)t9bD-CJ6=&d< zYFmWMC6b<=n!v_qhx(^unXAyVKLx5J;HJ(Vs2Nw8}wJTAvhJ*l*)FbHVT0@JWiGCNd6Bak7G z^T?c$l2qL{!i5Sil`2;pvw>@C`#E3@BwS1F?3+fT{wyU@ z;Wnzf(Q{QVrs_Hz`ihqTv$j1$AyVPCIzNX`{{XdylXUdNsCVTcFL&nF_)wujjD<>+ zbxs0rgL8JsR9sXjzBv!yI7acy;*7;YP-xasXjPjJM>$^OvTJHPK}@Dt?G*?DnN)Zc zrmu1pAEv1=%}T_oJRZkLdsrX$OtaFb@t^`~H=Xhf$2*&O_}n>0^PTy^H;z%+TmJyY v{u8$-Zml0aK~y(ZMz`DT3X@v{+7nSh4Uk6jzCoDhI~&i&;D;pMbASKYajfr= literal 0 HcmV?d00001 diff --git a/docs/source/api/index.rst b/docs/source/api/index.rst index cea73de6802d..f296c74310c6 100644 --- a/docs/source/api/index.rst +++ b/docs/source/api/index.rst @@ -82,6 +82,7 @@ The following modules are available in the ``isaaclab_contrib`` extension: actuators assets + controllers mdp rl sensors diff --git a/docs/source/api/lab_contrib/isaaclab_contrib.controllers.rst b/docs/source/api/lab_contrib/isaaclab_contrib.controllers.rst new file mode 100644 index 000000000000..c76804d4b463 --- /dev/null +++ b/docs/source/api/lab_contrib/isaaclab_contrib.controllers.rst @@ -0,0 +1,88 @@ +isaaclab_contrib.controllers +============================ + +.. automodule:: isaaclab_contrib.controllers + + .. rubric:: Classes + + .. autosummary:: + + LeeControllerBase + LeeControllerBaseCfg + LeeAccController + LeeAccControllerCfg + LeeAttController + LeeAttControllerCfg + LeePosController + LeePosControllerCfg + LeeVelController + LeeVelControllerCfg + +Lee Base Controller +-------------------- + +.. autoclass:: LeeControllerBase + :members: + :inherited-members: + :show-inheritance: + +.. autoclass:: LeeControllerBaseCfg + :members: + :inherited-members: + :show-inheritance: + :exclude-members: __init__, class_type + +Lee Acceleration Controller +---------------------------- + +.. autoclass:: LeeAccController + :members: + :inherited-members: + :show-inheritance: + +.. autoclass:: LeeAccControllerCfg + :members: + :inherited-members: + :show-inheritance: + :exclude-members: __init__, class_type + +Lee Attitude Controller +------------------------- +.. autoclass:: LeeAttController + :members: + :inherited-members: + :show-inheritance: + +.. autoclass:: LeeAttControllerCfg + :members: + :inherited-members: + :show-inheritance: + :exclude-members: __init__, class_type + +Lee Position Controller +----------------------- + +.. autoclass:: LeePosController + :members: + :inherited-members: + :show-inheritance: + +.. autoclass:: LeePosControllerCfg + :members: + :inherited-members: + :show-inheritance: + :exclude-members: __init__, class_type + +Lee Velocity Controller +----------------------- + +.. autoclass:: LeeVelController + :members: + :inherited-members: + :show-inheritance: + +.. autoclass:: LeeVelControllerCfg + :members: + :inherited-members: + :show-inheritance: + :exclude-members: __init__, class_type diff --git a/docs/source/overview/environments.rst b/docs/source/overview/environments.rst index c1bce52597e4..6a13f8c087d7 100644 --- a/docs/source/overview/environments.rst +++ b/docs/source/overview/environments.rst @@ -531,14 +531,20 @@ Multirotor .. |arl_robot_track_position_state_based| image:: ../_static/tasks/drone_arl/arl_robot_1_track_position_state_based.jpg +.. |arl_robot_navigation-link| replace:: `Isaac-Navigation-3DObstacles-ARL-Robot-1-v0 `__ + +.. |arl_robot_navigation| image:: ../_static/tasks/drone_arl/arl_robot_1_navigation.jpg + .. table:: :widths: 25 30 25 20 - +----------------------------------------+---------------------------------------------+----------------------------------------------------------------------------------------+------------------------------+ - | World | Environment ID | Description | Presets | - +========================================+=============================================+========================================================================================+==============================+ - | |arl_robot_track_position_state_based| | |arl_robot_track_position_state_based-link| | Setpoint position control for the ARL robot using the track_position_state_based task. | | - +----------------------------------------+---------------------------------------------+----------------------------------------------------------------------------------------+------------------------------+ + +----------------------------------------+---------------------------------------------+----------------------------------------------------------------------------------------+-----------------------+ + | World | Environment ID | Description | Presets | + +========================================+=============================================+========================================================================================+=======================+ + | |arl_robot_track_position_state_based| | |arl_robot_track_position_state_based-link| | Setpoint position control for the ARL robot using the track_position_state_based task. | | + +----------------------------------------+---------------------------------------------+----------------------------------------------------------------------------------------+-----------------------+ + | |arl_robot_navigation| | |arl_robot_navigation-link| | Navigate through 3D obstacles with the ARL robot using depth camera sensing. | | + +----------------------------------------+---------------------------------------------+----------------------------------------------------------------------------------------+-----------------------+ Others @@ -1013,6 +1019,16 @@ inferencing, including reading from an already trained checkpoint and disabling - Manager Based - **rsl_rl** (PPO), **skrl** (PPO) - ``newton_mjwarp``, ``physx`` + * - Isaac-TrackPositionNoObstacles-ARL-Robot-1-v0 + - Isaac-TrackPositionNoObstacles-ARL-Robot-1-Play-v0 + - Manager Based + - **rl_games** (PPO), **rsl_rl** (PPO), **skrl** (PPO) + - ``physx`` + * - Isaac-Navigation-3DObstacles-ARL-Robot-1-v0 + - Isaac-Navigation-3DObstacles-ARL-Robot-1-Play-v0 + - Manager Based + - **rl_games** (PPO), **rsl_rl** (PPO), **skrl** (PPO) + - ``physx`` * - Isaac-Open-Drawer-Franka-IK-Abs-v0 - - Manager Based diff --git a/scripts/demos/arl_robot_1.py b/scripts/demos/arl_robot_1.py new file mode 100644 index 000000000000..987e6be6b2ec --- /dev/null +++ b/scripts/demos/arl_robot_1.py @@ -0,0 +1,114 @@ +# Copyright (c) 2022-2026, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md). +# All rights reserved. +# +# SPDX-License-Identifier: BSD-3-Clause + +""" +Script to view ARL Robot 1. + +Launch Isaac Sim Simulator first. +""" + +# Create argparser +import argparse + +from isaaclab.app import AppLauncher + +parser = argparse.ArgumentParser(description="View ARL Robot 1 with Lee Position Controller.") +# append AppLauncher cli args +AppLauncher.add_app_launcher_args(parser) +args_cli = parser.parse_args() + +# launch omniverse app +app_launcher = AppLauncher(args_cli) +simulation_app = app_launcher.app + +"""Rest everything follows.""" + +import torch + +import omni.usd +from pxr import Gf, UsdLux + +import isaaclab.sim as sim_utils +from isaaclab.sim import SimulationContext + +from isaaclab_contrib.assets import Multirotor +from isaaclab_contrib.controllers.lee_position_control import LeePosController +from isaaclab_contrib.controllers.lee_position_control_cfg import LeePosControllerCfg + +from isaaclab_assets.robots.arl_robot_1 import ARL_ROBOT_1_CFG + + +def main(): + """Main function to spawn arl_robot_1.""" + + # Create simulation context + sim_cfg = sim_utils.SimulationCfg(dt=0.01) + sim = SimulationContext(sim_cfg) + + # Create a dome light with light blue color + stage = omni.usd.get_context().get_stage() + dome_light = UsdLux.DomeLight.Define(stage, "/World/DomeLight") + dome_light.CreateColorAttr(Gf.Vec3f(0.53, 0.81, 0.92)) # Light blue + dome_light.CreateIntensityAttr(1000.0) + + # Spawn ground plane + cfg = sim_utils.GroundPlaneCfg() + cfg.func("/World/defaultGroundPlane", cfg) + + # Spawn robot + robot_cfg = ARL_ROBOT_1_CFG.replace(prim_path="/World/Robot") + robot_cfg.actuators["thrusters"].dt = sim_cfg.dt + robot = Multirotor(robot_cfg) + + # Play the simulator + sim.reset() + + # Create Lee position controller + controller_cfg = LeePosControllerCfg( + K_pos_range=((2.5, 2.5, 1.5), (3.5, 3.5, 2.0)), + K_vel_range=((2.5, 2.5, 1.5), (3.5, 3.5, 2.0)), + K_rot_range=((1.6, 1.6, 0.25), (1.85, 1.85, 0.4)), + K_angvel_range=((0.4, 0.4, 0.075), (0.5, 0.5, 0.09)), + max_inclination_angle_rad=1.0471975511965976, + max_yaw_rate=1.0471975511965976, + ) + controller = LeePosController(controller_cfg, robot, num_envs=1, device=str(sim.device)) + + # Get allocation matrix and compute pseudoinverse + allocation_matrix = torch.tensor(robot_cfg.allocation_matrix, device=sim.device, dtype=torch.float32) + # allocation_matrix is (6, num_thrusters), we need pseudoinverse for wrench -> thrust + alloc_pinv = torch.linalg.pinv(allocation_matrix) # Shape: (num_thrusters, 6) + + # Position command: hover in place (zero position, zero yaw) + pos_command = torch.zeros((1, 4), device=sim.device) # [x, y, z, yaw] + pos_command[0, 2] = 1.0 # Hover at 1 meter height + + # Simulation loop + print("[INFO] Starting demo with Lee Position Controller. Press Ctrl+C to stop.") + + while simulation_app.is_running(): + # Compute wrench from velocity controller + wrench = controller.compute(pos_command) # Shape: (1, 6) + + # Allocate wrench to thrusters: thrust = pinv(A) @ wrench + thrust_cmd = torch.matmul(wrench, alloc_pinv.T) # Shape: (1, num_thrusters) + thrust_cmd = thrust_cmd.clamp(min=0.0) # Ensure non-negative thrust + + # Apply thrust + robot.set_thrust_target(thrust_cmd) + + # Step simulation + robot.write_data_to_sim() + sim.step() + + # Update robot + robot.update(sim_cfg.dt) + + # Cleanup + simulation_app.close() + + +if __name__ == "__main__": + main() diff --git a/source/isaaclab_assets/isaaclab_assets/robots/arl_robot_1.py b/source/isaaclab_assets/isaaclab_assets/robots/arl_robot_1.py index 32e01adc93b4..4f81f8a0645c 100644 --- a/source/isaaclab_assets/isaaclab_assets/robots/arl_robot_1.py +++ b/source/isaaclab_assets/isaaclab_assets/robots/arl_robot_1.py @@ -7,7 +7,7 @@ The following configuration parameters are available: -* :obj:`ARL_ROBOT_1_CFG`: The ARL_Robot_1 with (TODO add motor propeller combination) +* :obj:`ARL_ROBOT_1_CFG`: The ARL_Robot_1 """ import isaaclab.sim as sim_utils diff --git a/source/isaaclab_contrib/docs/README.md b/source/isaaclab_contrib/docs/README.md index 346b47e5522c..ea09129849f5 100644 --- a/source/isaaclab_contrib/docs/README.md +++ b/source/isaaclab_contrib/docs/README.md @@ -208,11 +208,11 @@ The `ThrustAction` term provides flexible preprocessing to support all modes thr ### Demo Script -A complete demonstration of quadcopter simulation is available: +A complete demonstration of multirotor simulation is available: ```bash -# Run quadcopter demo -./isaaclab.sh -p scripts/demos/quadcopter.py +# Run multirotor demo +./isaaclab.sh -p scripts/demos/arl_robot_1.py ``` ## TacSL Tactile Sensor (Detailed) @@ -478,7 +478,7 @@ The extension includes comprehensive unit tests for all contributed components: # Test multirotor components python -m pytest source/isaaclab_contrib/test/assets/test_multirotor.py python -m pytest source/isaaclab_contrib/test/actuators/test_thruster.py - +python -m pytest source/isaaclab_contrib/test/assets/test_drone_geometric_controllers.py # Run all contrib tests python -m pytest source/isaaclab_contrib/test/ ``` diff --git a/source/isaaclab_contrib/isaaclab_contrib/actuators/thruster.py b/source/isaaclab_contrib/isaaclab_contrib/actuators/thruster.py index 036a817fbfbd..da9053107b78 100644 --- a/source/isaaclab_contrib/isaaclab_contrib/actuators/thruster.py +++ b/source/isaaclab_contrib/isaaclab_contrib/actuators/thruster.py @@ -188,9 +188,9 @@ def motor_model_rate(self, error: torch.Tensor, mixing_factor: torch.Tensor): def rk4_integration(self, error: torch.Tensor, mixing_factor: torch.Tensor): k1 = self.motor_model_rate(error, mixing_factor) - k2 = self.motor_model_rate(error + 0.5 * self.cfg.dt * k1, mixing_factor) - k3 = self.motor_model_rate(error + 0.5 * self.cfg.dt * k2, mixing_factor) - k4 = self.motor_model_rate(error + self.cfg.dt * k3, mixing_factor) + k2 = self.motor_model_rate(error - 0.5 * self.cfg.dt * k1, mixing_factor) + k3 = self.motor_model_rate(error - 0.5 * self.cfg.dt * k2, mixing_factor) + k4 = self.motor_model_rate(error - self.cfg.dt * k3, mixing_factor) return (self.cfg.dt / 6.0) * (k1 + 2.0 * k2 + 2.0 * k3 + k4) def discrete_mixing_factor(self, time_constant: torch.Tensor): diff --git a/source/isaaclab_contrib/isaaclab_contrib/controllers/__init__.py b/source/isaaclab_contrib/isaaclab_contrib/controllers/__init__.py new file mode 100644 index 000000000000..15ad731d8b9d --- /dev/null +++ b/source/isaaclab_contrib/isaaclab_contrib/controllers/__init__.py @@ -0,0 +1,16 @@ +# Copyright (c) 2022-2026, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md). +# All rights reserved. +# +# SPDX-License-Identifier: BSD-3-Clause + +"""Sub-package for different controllers and motion-generators. + +Controllers or motion generators are responsible for closed-loop tracking of a given command. The +controller can be a simple PID controller or a more complex controller such as impedance control +or inverse kinematics control. The controller is responsible for generating the desired joint-level +commands to be sent to the robot. +""" + + +from isaaclab.utils.module import lazy_export +lazy_export() diff --git a/source/isaaclab_contrib/isaaclab_contrib/controllers/__init__.pyi b/source/isaaclab_contrib/isaaclab_contrib/controllers/__init__.pyi new file mode 100644 index 000000000000..648fa27731de --- /dev/null +++ b/source/isaaclab_contrib/isaaclab_contrib/controllers/__init__.pyi @@ -0,0 +1,32 @@ +# Copyright (c) 2022-2026, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md). +# All rights reserved. +# +# SPDX-License-Identifier: BSD-3-Clause + +__all__ = [ + "compute_desired_orientation", + "compute_body_torque", + "yaw_rate_to_body_angvel", + "LeeControllerBase", + "LeeControllerBaseCfg", + "LeeAttController", + "LeeAttControllerCfg", + "LeeAccController", + "LeeAccControllerCfg", + "LeePosController", + "LeePosControllerCfg", + "LeeVelController", + "LeeVelControllerCfg", +] + +from .lee_controller_utils import compute_body_torque, compute_desired_orientation, yaw_rate_to_body_angvel +from .lee_controller_base import LeeControllerBase +from .lee_controller_base_cfg import LeeControllerBaseCfg +from .lee_attitude_control import LeeAttController +from .lee_attitude_control_cfg import LeeAttControllerCfg +from .lee_acceleration_control import LeeAccController +from .lee_acceleration_control_cfg import LeeAccControllerCfg +from .lee_position_control import LeePosController +from .lee_position_control_cfg import LeePosControllerCfg +from .lee_velocity_control import LeeVelController +from .lee_velocity_control_cfg import LeeVelControllerCfg diff --git a/source/isaaclab_contrib/isaaclab_contrib/controllers/lee_acceleration_control.py b/source/isaaclab_contrib/isaaclab_contrib/controllers/lee_acceleration_control.py new file mode 100644 index 000000000000..908f05745a8e --- /dev/null +++ b/source/isaaclab_contrib/isaaclab_contrib/controllers/lee_acceleration_control.py @@ -0,0 +1,102 @@ +# Copyright (c) 2022-2026, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md). +# All rights reserved. +# +# SPDX-License-Identifier: BSD-3-Clause + +from __future__ import annotations + +from typing import TYPE_CHECKING + +import torch + +import isaaclab.utils.math as math_utils + +from .lee_controller_base import LeeControllerBase +from .lee_controller_utils import compute_body_torque, compute_desired_orientation, yaw_rate_to_body_angvel + +if TYPE_CHECKING: + from isaaclab.assets import Multirotor + + from .lee_acceleration_control_cfg import LeeAccControllerCfg + + +class LeeAccController(LeeControllerBase): + """Lee acceleration controller for multirotor tracking acceleration setpoints. + + Computes a body-frame wrench command ``[Fx, Fy, Fz, Tx, Ty, Tz]`` from an acceleration setpoint + in the world frame. Gains may be randomized per environment if enabled in the configuration. + """ + + cfg: LeeAccControllerCfg + + def __init__(self, cfg: LeeAccControllerCfg, asset: Multirotor, num_envs: int, device: str): + """Initialize controller. + + Args: + cfg: Controller configuration. + asset: Multirotor asset to control. + num_envs: Number of environments. + device: Device to run computations on. + """ + super().__init__(cfg, asset, num_envs, device) + + # Gain ranges + self.K_rot_range = torch.tensor(self.cfg.K_rot_range, device=device).repeat(num_envs, 1, 1) + self.K_angvel_range = torch.tensor(self.cfg.K_angvel_range, device=device).repeat(num_envs, 1, 1) + + # Current gains + self.K_rot_current = self.K_rot_range.mean(dim=1) + self.K_angvel_current = self.K_angvel_range.mean(dim=1) + + def compute(self, command: torch.Tensor) -> torch.Tensor: + """Compute wrench command from acceleration setpoint. + + Args: + command: (num_envs, 4) acceleration command command [ax, ay, az, yaw_rate] in body frame. + + Returns: + (num_envs, 6) wrench command [fx, fy, fz, tx, ty, tz] in body frame. + """ + self.wrench_command_b.zero_() + + root_quat_w, root_ang_vel_b, _ = self._root_state_tensors() + + # Use command directly as acceleration setpoint + forces_w = (command[:, :3] - self.gravity) * self.mass.view(-1, 1) + + # Project forces to body z-axis for thrust command + body_z_w = math_utils.matrix_from_quat(root_quat_w)[:, :, 2] + self.wrench_command_b[:, 2] = torch.sum(forces_w * body_z_w, dim=1) + + # Get current yaw and compute desired orientation + roll, pitch, yaw = math_utils.euler_xyz_from_quat(root_quat_w) + desired_quat = compute_desired_orientation(forces_w, yaw, self.rotation_matrix_buffer) + + # Compute desired angular velocity in body frame from yaw rate command + desired_angvel_b = yaw_rate_to_body_angvel(command[:, 3], roll, pitch, self.device) + + # Compute torque command + self.wrench_command_b[:, 3:6] = compute_body_torque( + desired_quat, + desired_angvel_b, + root_quat_w, + root_ang_vel_b, + self.robot_inertia, + self.K_rot_current, + self.K_angvel_current, + self.cfg.max_yaw_rate, + ) + + return self.wrench_command_b + + def _randomize_params(self, env_ids: slice | torch.Tensor): + """Randomize controller gains for the given environments if enabled.""" + self.K_rot_current[env_ids] = math_utils.sample_uniform( + self.K_rot_range[env_ids, 0], self.K_rot_range[env_ids, 1], self.K_rot_range[env_ids, 0].shape, self.device + ) + self.K_angvel_current[env_ids] = math_utils.sample_uniform( + self.K_angvel_range[env_ids, 0], + self.K_angvel_range[env_ids, 1], + self.K_angvel_range[env_ids, 0].shape, + self.device, + ) diff --git a/source/isaaclab_contrib/isaaclab_contrib/controllers/lee_acceleration_control_cfg.py b/source/isaaclab_contrib/isaaclab_contrib/controllers/lee_acceleration_control_cfg.py new file mode 100644 index 000000000000..6a1f6c7db7e2 --- /dev/null +++ b/source/isaaclab_contrib/isaaclab_contrib/controllers/lee_acceleration_control_cfg.py @@ -0,0 +1,23 @@ +# Copyright (c) 2022-2026, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md). +# All rights reserved. +# +# SPDX-License-Identifier: BSD-3-Clause + + +from isaaclab.utils import configclass + +from .lee_acceleration_control import LeeAccController +from .lee_controller_base_cfg import LeeControllerBaseCfg + + +@configclass +class LeeAccControllerCfg(LeeControllerBaseCfg): + """Configuration for a Lee-style geometric quadrotor acceleration controller. + + Unless otherwise noted, vectors are ordered as (x, y, z) in the simulation world/body frames. + The acceleration controller gains are sampled uniformly per environment between + their corresponding ``*_min`` and ``*_max`` bounds at reset. + """ + + class_type: type = LeeAccController + """The class type for the acceleration controller.""" diff --git a/source/isaaclab_contrib/isaaclab_contrib/controllers/lee_attitude_control.py b/source/isaaclab_contrib/isaaclab_contrib/controllers/lee_attitude_control.py new file mode 100644 index 000000000000..2ea176bde295 --- /dev/null +++ b/source/isaaclab_contrib/isaaclab_contrib/controllers/lee_attitude_control.py @@ -0,0 +1,98 @@ +# Copyright (c) 2022-2026, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md). +# All rights reserved. +# +# SPDX-License-Identifier: BSD-3-Clause + +from __future__ import annotations + +from typing import TYPE_CHECKING + +import torch + +import isaaclab.utils.math as math_utils + +from .lee_controller_base import LeeControllerBase +from .lee_controller_utils import compute_body_torque, yaw_rate_to_body_angvel + +if TYPE_CHECKING: + from isaaclab.assets import Multirotor + + from .lee_attitude_control_cfg import LeeAttControllerCfg + + +class LeeAttController(LeeControllerBase): + """Lee attitude controller for multirotor tracking attitude setpoints. + + Computes a body-frame wrench command ``[Fx, Fy, Fz, Tx, Ty, Tz]`` from an attitude setpoint + in the world frame. Gains may be randomized per environment if enabled in the configuration. + """ + + cfg: LeeAttControllerCfg + + def __init__(self, cfg: LeeAttControllerCfg, asset: Multirotor, num_envs: int, device: str): + """Initialize controller. + + Args: + cfg: Controller configuration. + asset: Multirotor asset to control. + num_envs: Number of environments. + device: Device to run computations on. + """ + super().__init__(cfg, asset, num_envs, device) + + # Gain ranges + self.K_rot_range = torch.tensor(self.cfg.K_rot_range, device=device).repeat(num_envs, 1, 1) + self.K_angvel_range = torch.tensor(self.cfg.K_angvel_range, device=device).repeat(num_envs, 1, 1) + + # Current gains + self.K_rot_current = self.K_rot_range.mean(dim=1) + self.K_angvel_current = self.K_angvel_range.mean(dim=1) + + def compute(self, command: torch.Tensor) -> torch.Tensor: + """Compute wrench command from attitude setpoint. + + Args: + command: (num_envs, 4) attitude command command [thrust, roll, pitch, yaw_rate] in body frame. + + Returns: + (num_envs, 6) wrench command [fx, fy, fz, tx, ty, tz] in body frame. + """ + self.wrench_command_b.zero_() + + root_quat_w, root_ang_vel_b, _ = self._root_state_tensors() + + # Use command directly as attitude setpoint + self.wrench_command_b[:, 2] = (command[:, 0] + 1.0) * self.mass * torch.norm(self.gravity, dim=1) + + # Get current yaw and compute desired orientation + roll, pitch, yaw = math_utils.euler_xyz_from_quat(root_quat_w) + desired_quat = math_utils.quat_from_euler_xyz(command[:, 1], command[:, 2], yaw) + + # Compute desired angular velocity in body frame from yaw rate command + desired_angvel_b = yaw_rate_to_body_angvel(command[:, 3], roll, pitch, self.device) + + # Compute torque command + self.wrench_command_b[:, 3:6] = compute_body_torque( + desired_quat, + desired_angvel_b, + root_quat_w, + root_ang_vel_b, + self.robot_inertia, + self.K_rot_current, + self.K_angvel_current, + self.cfg.max_yaw_rate, + ) + + return self.wrench_command_b + + def _randomize_params(self, env_ids: slice | torch.Tensor): + """Randomize controller gains for the given environments if enabled.""" + self.K_rot_current[env_ids] = math_utils.sample_uniform( + self.K_rot_range[env_ids, 0], self.K_rot_range[env_ids, 1], self.K_rot_range[env_ids, 0].shape, self.device + ) + self.K_angvel_current[env_ids] = math_utils.sample_uniform( + self.K_angvel_range[env_ids, 0], + self.K_angvel_range[env_ids, 1], + self.K_angvel_range[env_ids, 0].shape, + self.device, + ) diff --git a/source/isaaclab_contrib/isaaclab_contrib/controllers/lee_attitude_control_cfg.py b/source/isaaclab_contrib/isaaclab_contrib/controllers/lee_attitude_control_cfg.py new file mode 100644 index 000000000000..bcf0f9f3ca13 --- /dev/null +++ b/source/isaaclab_contrib/isaaclab_contrib/controllers/lee_attitude_control_cfg.py @@ -0,0 +1,23 @@ +# Copyright (c) 2022-2026, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md). +# All rights reserved. +# +# SPDX-License-Identifier: BSD-3-Clause + + +from isaaclab.utils import configclass + +from .lee_attitude_control import LeeAttController +from .lee_controller_base_cfg import LeeControllerBaseCfg + + +@configclass +class LeeAttControllerCfg(LeeControllerBaseCfg): + """Configuration for a Lee-style geometric quadrotor attitude controller. + + Unless otherwise noted, vectors are ordered as (x, y, z) in the simulation world/body frames. + The attitude controller gains are sampled uniformly per environment between + their corresponding ``*_min`` and ``*_max`` bounds at reset. + """ + + class_type: type = LeeAttController + """The class type for the attitude controller.""" diff --git a/source/isaaclab_contrib/isaaclab_contrib/controllers/lee_controller_base.py b/source/isaaclab_contrib/isaaclab_contrib/controllers/lee_controller_base.py new file mode 100644 index 000000000000..231c15710716 --- /dev/null +++ b/source/isaaclab_contrib/isaaclab_contrib/controllers/lee_controller_base.py @@ -0,0 +1,120 @@ +# Copyright (c) 2022-2026, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md). +# All rights reserved. +# +# SPDX-License-Identifier: BSD-3-Clause + +"""Base class for Lee-style geometric controllers.""" + +from __future__ import annotations + +from typing import TYPE_CHECKING + +import torch +import warp as wp + +import isaaclab.sim as sim_utils +import isaaclab.utils.math as math_utils + +from isaaclab_contrib.utils.math import aggregate_inertia_about_robot_com + +if TYPE_CHECKING: + from isaaclab.assets import Multirotor + + from .lee_controller_base_cfg import LeeControllerBaseCfg + + +class LeeControllerBase: + """Base class for Lee-style geometric controllers.""" + + cfg: LeeControllerBaseCfg + device: str + robot: Multirotor + + def __init__(self, cfg: LeeControllerBaseCfg, asset: Multirotor, num_envs: int, device: str): + """Initialize controller buffers and pre-compute aggregate inertias. + + Args: + cfg: Controller configuration. + asset: Multirotor asset to control. + num_envs: Number of environments. + device: Device to run computations on. + """ + self.cfg = cfg + self.robot = asset + self.device = device + self.num_envs = num_envs + + root_quat_w = self._to_torch(self.robot.data.root_link_quat_w) + body_link_pos_w = self._to_torch(self.robot.data.body_link_pos_w) + root_pos_w = self._to_torch(self.robot.data.root_pos_w) + body_com_pos_b = self._to_torch(self.robot.data.body_com_pos_b) + body_com_quat_b = self._to_torch(self.robot.data.body_com_quat_b) + body_link_quat_w = self._to_torch(self.robot.data.body_link_quat_w) + + # Aggregate mass and inertia about the robot COM for all bodies + root_quat_exp = root_quat_w.unsqueeze(1).expand(num_envs, self.robot.num_bodies, 4) + body_link_pos_delta = body_link_pos_w - root_pos_w.unsqueeze(1) + + body_masses = self._to_torch(self.robot.root_view.get_masses()) + body_inv_mass_local = torch.where(body_masses > 0, 1.0 / body_masses, torch.zeros_like(body_masses)) + self.mass, self.robot_inertia, _ = aggregate_inertia_about_robot_com( + self._to_torch(self.robot.root_view.get_inertias()), + body_inv_mass_local, + body_com_pos_b, + body_com_quat_b, + math_utils.quat_apply_inverse(root_quat_exp, body_link_pos_delta), + math_utils.quat_mul(math_utils.quat_inv(root_quat_exp), body_link_quat_w), + ) + # Get gravity from simulation context + sim = sim_utils.SimulationContext.instance() + gravity_vec = sim.cfg.gravity + self.gravity = torch.tensor(gravity_vec, device=device, dtype=torch.float32).expand(num_envs, -1) + + # Buffers + self.wrench_command_b = torch.zeros((num_envs, 6), device=device) # [fx, fy, fz, tx, ty, tz] + self.rotation_matrix_buffer = torch.zeros((num_envs, 3, 3), device=device) + + def _to_torch(self, x): + """Convert warp array to torch tensor on controller device; no-op for torch tensors.""" + if torch.is_tensor(x): + return x.to(self.device) + return wp.to_torch(x).to(self.device) + + def _root_state_tensors(self) -> tuple[torch.Tensor, torch.Tensor, torch.Tensor]: + """Fetch root state once per control step.""" + root_quat_w = self._to_torch(self.robot.data.root_quat_w) + root_ang_vel_b = self._to_torch(self.robot.data.root_ang_vel_b) + root_lin_vel_w = self._to_torch(self.robot.data.root_lin_vel_w) + return root_quat_w, root_ang_vel_b, root_lin_vel_w + + def reset(self): + """Reset controller state for all environments.""" + self.reset_idx(env_ids=None) + + def reset_idx(self, env_ids: torch.Tensor | None): + """Reset controller state (and optionally randomize gains) for selected environments. + + Args: + env_ids: Tensor of environment indices, or ``None`` for all. + """ + if env_ids is None: + env_ids = slice(None) + self._randomize_params(env_ids) + + def _randomize_params(self, env_ids: slice | torch.Tensor): + """Randomize controller gains for the given environments if enabled. + + Override in subclass to implement parameter randomization. + """ + pass + + def compute(self, command: torch.Tensor) -> torch.Tensor: + """Compute wrench command from input command. + + Args: + command: Input command (shape depends on controller type). + + Returns: + (num_envs, 6) wrench command [fx, fy, fz, tx, ty, tz] in body frame. + """ + raise NotImplementedError("Subclasses must implement compute()") diff --git a/source/isaaclab_contrib/isaaclab_contrib/controllers/lee_controller_base_cfg.py b/source/isaaclab_contrib/isaaclab_contrib/controllers/lee_controller_base_cfg.py new file mode 100644 index 000000000000..3a279f7ddb81 --- /dev/null +++ b/source/isaaclab_contrib/isaaclab_contrib/controllers/lee_controller_base_cfg.py @@ -0,0 +1,73 @@ +# Copyright (c) 2022-2026, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md). +# All rights reserved. +# +# SPDX-License-Identifier: BSD-3-Clause + +import math +from dataclasses import MISSING + +from isaaclab.utils import configclass + + +@configclass +class LeeControllerBaseCfg: + """Base configuration for Lee-style geometric quadrotor controllers. + + Unless otherwise noted, vectors are ordered as (x, y, z) in the simulation world/body frames. + The controller gains are sampled uniformly per environment between + their corresponding ``*_min`` and ``*_max`` bounds at reset. + + Note: + To disable randomization, set the min and max values to be identical. + For example: K_rot_range = ((1.85, 1.85, 0.4), (1.85, 1.85, 0.4)) + """ + + K_rot_range: tuple[tuple[float, float, float], tuple[float, float, float]] = MISSING + """Orientation (rotation) error proportional gain range about body axes [unitless]. + + This is a tuple of two tuples containing the minimum and maximum gains for roll, pitch, and yaw. + Format: ((min_roll, min_pitch, min_yaw), (max_roll, max_pitch, max_yaw)) + + To disable randomization, set both tuples to the same values. + + Example (with randomization): + ((1.6, 1.6, 0.25), (1.85, 1.85, 0.4)) for ARL Robot 1 + + Example (without randomization): + ((1.85, 1.85, 0.4), (1.85, 1.85, 0.4)) for fixed gains + """ + + K_angvel_range: tuple[tuple[float, float, float], tuple[float, float, float]] = MISSING + """Body angular-velocity error proportional gain range [unitless]. + + This is a tuple of two tuples containing the minimum and maximum gains for roll, pitch, and yaw rates. + Format: ((min_roll_rate, min_pitch_rate, min_yaw_rate), (max_roll_rate, max_pitch_rate, max_yaw_rate)) + + To disable randomization, set both tuples to the same values. + + Example (with randomization): + ((0.4, 0.4, 0.075), (0.5, 0.5, 0.09)) for ARL Robot 1 + + Example (without randomization): + ((0.5, 0.5, 0.09), (0.5, 0.5, 0.09)) for fixed gains + """ + + max_inclination_angle_rad: float = math.pi / 3 + """Maximum allowed roll/pitch magnitude (inclination) in radians. + + This limits the maximum tilt angle of the quadrotor during control. + Typical range: 0.5 to 1.57 radians (30° to 90°) + + Example: + 1.0471975511965976 (60° in radians) for ARL Robot 1 + """ + + max_yaw_rate: float = MISSING + """Maximum allowed yaw rate command [rad/s]. + + This limits the maximum rotational velocity about the z-axis. + Typical range: 0.5 to 2.0 rad/s + + Example: + 1.0471975511965976 (60°/s in radians) for ARL Robot 1 + """ diff --git a/source/isaaclab_contrib/isaaclab_contrib/controllers/lee_controller_utils.py b/source/isaaclab_contrib/isaaclab_contrib/controllers/lee_controller_utils.py new file mode 100644 index 000000000000..6a89ec0bdde4 --- /dev/null +++ b/source/isaaclab_contrib/isaaclab_contrib/controllers/lee_controller_utils.py @@ -0,0 +1,127 @@ +# Copyright (c) 2022-2026, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md). +# All rights reserved. +# +# SPDX-License-Identifier: BSD-3-Clause + +"""Shared utilities for Lee-style geometric controllers.""" + +import torch + +import isaaclab.utils.math as math_utils + + +def compute_desired_orientation( + forces_w: torch.Tensor, yaw_setpoint: torch.Tensor, rotation_matrix_buffer: torch.Tensor +) -> torch.Tensor: + """Compute desired orientation from force direction and yaw setpoint. + + Args: + forces_w: (num_envs, 3) desired force vector in world frame. + yaw_setpoint: (num_envs,) desired yaw angle [rad]. + rotation_matrix_buffer: (num_envs, 3, 3) pre-allocated buffer for rotation matrix. + + Returns: + (num_envs, 4) desired orientation quaternion (wxyz). + """ + # Desired z-axis (thrust direction) + b3_c = forces_w / (torch.norm(forces_w, dim=1, keepdim=True) + 1e-12) + + # Intermediate direction for yaw + temp_dir = torch.zeros_like(forces_w) + temp_dir[:, 0] = torch.cos(yaw_setpoint) + temp_dir[:, 1] = torch.sin(yaw_setpoint) + + # Desired y-axis (orthogonal to thrust and yaw direction) + b2_c = torch.cross(b3_c, temp_dir, dim=1) + b2_c = b2_c / (torch.norm(b2_c, dim=1, keepdim=True) + 1e-12) + + # Desired x-axis (complete right-handed frame) + b1_c = torch.cross(b2_c, b3_c, dim=1) + + # Build rotation matrix + rotation_matrix_buffer[:, :, 0] = b1_c + rotation_matrix_buffer[:, :, 1] = b2_c + rotation_matrix_buffer[:, :, 2] = b3_c + + # Convert to quaternion + return math_utils.quat_from_matrix(rotation_matrix_buffer) + + +def compute_body_torque( + setpoint_orientation: torch.Tensor, + setpoint_angvel_b: torch.Tensor, + current_quat: torch.Tensor, + current_angvel_b: torch.Tensor, + robot_inertia: torch.Tensor, + K_rot: torch.Tensor, + K_angvel: torch.Tensor, + max_yaw_rate: float, +) -> torch.Tensor: + """PD attitude control in body frame with feedforward Coriolis term. + + Args: + setpoint_orientation: (num_envs, 4) desired orientation quaternion (wxyz) in world frame. + setpoint_angvel_b: (num_envs, 3) desired angular velocity in body frame [rad/s]. + current_quat: (num_envs, 4) current orientation quaternion (wxyz). + current_angvel_b: (num_envs, 3) current angular velocity in body frame [rad/s]. + robot_inertia: (num_envs, 3, 3) robot inertia matrix. + K_rot: (num_envs, 3) rotation gain. + K_angvel: (num_envs, 3) angular velocity gain. + max_yaw_rate: Maximum yaw rate [rad/s]. + + Returns: + (num_envs, 3) body torque command [N·m]. + """ + # Clamp yaw rate + setpoint_angvel_b[:, 2] = torch.clamp(setpoint_angvel_b[:, 2], -max_yaw_rate, max_yaw_rate) + + # Compute orientation error (R^T @ R_d) + RT_Rd_quat = math_utils.quat_mul(math_utils.quat_inv(current_quat), setpoint_orientation) + R_err = math_utils.matrix_from_quat(RT_Rd_quat) + + # Extract rotation error vector from skew-symmetric part + skew_matrix = R_err.transpose(-1, -2) - R_err + rotation_error = 0.5 * torch.stack([-skew_matrix[:, 1, 2], skew_matrix[:, 0, 2], -skew_matrix[:, 0, 1]], dim=1) + + # Angular velocity error + angvel_error = current_angvel_b - setpoint_angvel_b + + # Coriolis feedforward term: ω × (I·ω) + inertia_angvel = torch.bmm(robot_inertia, current_angvel_b.unsqueeze(2)).squeeze(2) + coriolis_term = torch.cross(current_angvel_b, inertia_angvel, dim=1) + + # PD + feedforward + torque = -K_rot * rotation_error - K_angvel * angvel_error + coriolis_term + return torque + + +def yaw_rate_to_body_angvel( + yaw_rate: torch.Tensor, roll: torch.Tensor, pitch: torch.Tensor, device: torch.device +) -> torch.Tensor: + """Convert yaw rate command to body angular velocity. + + Transformation: ω_body = T(roll, pitch) @ [0, 0, yaw_rate]^T + where T is the euler-to-body rate transformation matrix. + + Args: + yaw_rate: (num_envs,) desired yaw rate [rad/s]. + roll: (num_envs,) current roll angle [rad]. + pitch: (num_envs,) current pitch angle [rad]. + device: Device to allocate tensors on. + + Returns: + (num_envs, 3) desired angular velocity in body frame [rad/s]. + """ + s_pitch = torch.sin(pitch) + c_pitch = torch.cos(pitch) + s_roll = torch.sin(roll) + c_roll = torch.cos(roll) + + # Only yaw rate is non-zero, so only the third column matters + # ω_body = [−sin(pitch), sin(roll)*cos(pitch), cos(roll)*cos(pitch)]^T * yaw_rate + angvel_b = torch.zeros((yaw_rate.shape[0], 3), device=device) + angvel_b[:, 0] = -s_pitch * yaw_rate + angvel_b[:, 1] = s_roll * c_pitch * yaw_rate + angvel_b[:, 2] = c_roll * c_pitch * yaw_rate + + return angvel_b diff --git a/source/isaaclab_contrib/isaaclab_contrib/controllers/lee_position_control.py b/source/isaaclab_contrib/isaaclab_contrib/controllers/lee_position_control.py new file mode 100644 index 000000000000..82fff709042a --- /dev/null +++ b/source/isaaclab_contrib/isaaclab_contrib/controllers/lee_position_control.py @@ -0,0 +1,134 @@ +# Copyright (c) 2022-2026, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md). +# All rights reserved. +# +# SPDX-License-Identifier: BSD-3-Clause + +from __future__ import annotations + +from typing import TYPE_CHECKING + +import torch + +import isaaclab.utils.math as math_utils + +from .lee_controller_base import LeeControllerBase +from .lee_controller_utils import compute_body_torque, compute_desired_orientation + +if TYPE_CHECKING: + from isaaclab.assets import Multirotor + + from .lee_position_control_cfg import LeePosControllerCfg + + +class LeePosController(LeeControllerBase): + """Lee position controller for multirotor tracking position setpoints. + + Computes a body-frame wrench command ``[Fx, Fy, Fz, Tx, Ty, Tz]`` from a position setpoint + in the world frame. Gains may be randomized per environment if enabled in the configuration. + """ + + cfg: LeePosControllerCfg + + def __init__(self, cfg: LeePosControllerCfg, asset: Multirotor, num_envs: int, device: str): + """Initialize controller. + + Args: + cfg: Controller configuration. + asset: Multirotor asset to control. + num_envs: Number of environments. + device: Device to run computations on. + """ + super().__init__(cfg, asset, num_envs, device) + + # Gain ranges + self.K_pos_range = torch.tensor(self.cfg.K_pos_range, device=device).repeat(num_envs, 1, 1) + self.K_vel_range = torch.tensor(self.cfg.K_vel_range, device=device).repeat(num_envs, 1, 1) + self.K_rot_range = torch.tensor(self.cfg.K_rot_range, device=device).repeat(num_envs, 1, 1) + self.K_angvel_range = torch.tensor(self.cfg.K_angvel_range, device=device).repeat(num_envs, 1, 1) + + # Current gains + self.K_pos_current = self.K_pos_range.mean(dim=1) + self.K_vel_current = self.K_vel_range.mean(dim=1) + self.K_rot_current = self.K_rot_range.mean(dim=1) + self.K_angvel_current = self.K_angvel_range.mean(dim=1) + + def compute(self, command: torch.Tensor) -> torch.Tensor: + """Compute wrench command from position setpoint. + + Args: + command: (num_envs, 4) [x, y, z, yaw] in body frame. + + Returns: + (num_envs, 6) wrench command [fx, fy, fz, tx, ty, tz] in body frame. + """ + self.wrench_command_b.zero_() + + root_quat_w, root_ang_vel_b, root_lin_vel_w = self._root_state_tensors() + root_pos_w = self._to_torch(self.robot.data.root_pos_w) + + # Compute acceleration from position error + acc = self._compute_acceleration( + setpoint_position=command[:, :3], + root_pos_w=root_pos_w, + root_lin_vel_w=root_lin_vel_w, + ) + forces_w = (acc - self.gravity) * self.mass.view(-1, 1) + + # Project forces to body z-axis for thrust command + body_z_w = math_utils.matrix_from_quat(root_quat_w)[:, :, 2] + self.wrench_command_b[:, 2] = torch.sum(forces_w * body_z_w, dim=1) + + # Get current yaw and compute desired orientation + desired_quat = compute_desired_orientation(forces_w, command[:, 3], self.rotation_matrix_buffer) + + # Zero angular velocity setpoint (hover) + desired_angvel_b = torch.zeros((self.num_envs, 3), device=self.device) + + # Compute torque command + self.wrench_command_b[:, 3:6] = compute_body_torque( + desired_quat, + desired_angvel_b, + root_quat_w, + root_ang_vel_b, + self.robot_inertia, + self.K_rot_current, + self.K_angvel_current, + self.cfg.max_yaw_rate, + ) + + return self.wrench_command_b + + def _randomize_params(self, env_ids: slice | torch.Tensor): + """Randomize controller gains for the given environments if enabled.""" + self.K_pos_current[env_ids] = math_utils.sample_uniform( + self.K_pos_range[env_ids, 0], self.K_pos_range[env_ids, 1], self.K_pos_range[env_ids, 0].shape, self.device + ) + self.K_vel_current[env_ids] = math_utils.sample_uniform( + self.K_vel_range[env_ids, 0], self.K_vel_range[env_ids, 1], self.K_vel_range[env_ids, 0].shape, self.device + ) + self.K_rot_current[env_ids] = math_utils.sample_uniform( + self.K_rot_range[env_ids, 0], self.K_rot_range[env_ids, 1], self.K_rot_range[env_ids, 0].shape, self.device + ) + self.K_angvel_current[env_ids] = math_utils.sample_uniform( + self.K_angvel_range[env_ids, 0], + self.K_angvel_range[env_ids, 1], + self.K_angvel_range[env_ids, 0].shape, + self.device, + ) + + def _compute_acceleration( + self, setpoint_position: torch.Tensor, root_pos_w: torch.Tensor, root_lin_vel_w: torch.Tensor + ) -> torch.Tensor: + """Compute desired acceleration from position error. + + Args: + setpoint_position: (num_envs, 3) desired position in world frame. + + Returns: + (num_envs, 3) desired acceleration in body frame. + """ + position_error = setpoint_position - root_pos_w + # Compute velocity error for position controller + velocity_error = -root_lin_vel_w + + return self.K_vel_current * velocity_error + self.K_pos_current * position_error diff --git a/source/isaaclab_contrib/isaaclab_contrib/controllers/lee_position_control_cfg.py b/source/isaaclab_contrib/isaaclab_contrib/controllers/lee_position_control_cfg.py new file mode 100644 index 000000000000..e2df30f8aa70 --- /dev/null +++ b/source/isaaclab_contrib/isaaclab_contrib/controllers/lee_position_control_cfg.py @@ -0,0 +1,44 @@ +# Copyright (c) 2022-2026, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md). +# All rights reserved. +# +# SPDX-License-Identifier: BSD-3-Clause + +from dataclasses import MISSING + +from isaaclab.utils import configclass + +from .lee_controller_base_cfg import LeeControllerBaseCfg +from .lee_position_control import LeePosController + + +@configclass +class LeePosControllerCfg(LeeControllerBaseCfg): + """Configuration for a Lee-style geometric quadrotor position controller. + + Unless otherwise noted, vectors are ordered as (x, y, z) in the simulation world/body frames. + The position controller gains are sampled uniformly per environment between + their corresponding ``*_min`` and ``*_max`` bounds at reset. + """ + + class_type: type = LeePosController + """The class type for the position controller.""" + + K_pos_range: tuple[tuple[float, float, float], tuple[float, float, float]] = MISSING + """Position error proportional gain range about body axes [unitless]. + + This is a tuple of two tuples containing the minimum and maximum gains for each axis (x, y, z). + Format: ((min_x, min_y, min_z), (max_x, max_y, max_z)) + + Example: + ((3.0, 3.0, 2.0), (4.0, 4.0, 2.5)) for ARL Robot 1 + """ + + K_vel_range: tuple[tuple[float, float, float], tuple[float, float, float]] = MISSING + """Velocity error proportional gain range about body axes [unitless]. + + This is a tuple of two tuples containing the minimum and maximum gains for each axis (x, y, z). + Format: ((min_x, min_y, min_z), (max_x, max_y, max_z)) + + Example: + ((2.5, 2.5, 1.5), (3.5, 3.5, 2.0)) for ARL Robot 1 + """ diff --git a/source/isaaclab_contrib/isaaclab_contrib/controllers/lee_velocity_control.py b/source/isaaclab_contrib/isaaclab_contrib/controllers/lee_velocity_control.py new file mode 100644 index 000000000000..14dc1ff970c3 --- /dev/null +++ b/source/isaaclab_contrib/isaaclab_contrib/controllers/lee_velocity_control.py @@ -0,0 +1,133 @@ +# Copyright (c) 2022-2026, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md). +# All rights reserved. +# +# SPDX-License-Identifier: BSD-3-Clause + +from __future__ import annotations + +from typing import TYPE_CHECKING + +import torch + +import isaaclab.utils.math as math_utils + +from .lee_controller_base import LeeControllerBase +from .lee_controller_utils import compute_body_torque, compute_desired_orientation, yaw_rate_to_body_angvel + +if TYPE_CHECKING: + from isaaclab.assets import Multirotor + + from .lee_velocity_control_cfg import LeeVelControllerCfg + + +class LeeVelController(LeeControllerBase): + """Lee velocity controller for multirotor tracking velocity setpoints. + + Computes a body-frame wrench command ``[Fx, Fy, Fz, Tx, Ty, Tz]`` from a velocity setpoint: + [vx, vy, vz, yaw_rate]. Gains may be randomized per environment if enabled in the configuration. + """ + + cfg: LeeVelControllerCfg + + def __init__(self, cfg: LeeVelControllerCfg, asset: Multirotor, num_envs: int, device: str): + """Initialize controller. + + Args: + cfg: Controller configuration. + asset: Multirotor asset to control. + num_envs: Number of environments. + device: Device to run computations on. + """ + super().__init__(cfg, asset, num_envs, device) + + # Gain ranges + self.K_vel_range = torch.tensor(self.cfg.K_vel_range, device=device).repeat(num_envs, 1, 1) + self.K_rot_range = torch.tensor(self.cfg.K_rot_range, device=device).repeat(num_envs, 1, 1) + self.K_angvel_range = torch.tensor(self.cfg.K_angvel_range, device=device).repeat(num_envs, 1, 1) + + # Current gains + self.K_vel_current = self.K_vel_range.mean(dim=1) + self.K_rot_current = self.K_rot_range.mean(dim=1) + self.K_angvel_current = self.K_angvel_range.mean(dim=1) + + def compute(self, command: torch.Tensor) -> torch.Tensor: + """Compute wrench command from velocity setpoint. + + Args: + command: (num_envs, 4) velocity command [vx, vy, vz, yaw_rate] in body frame. + + Returns: + (num_envs, 6) wrench command [fx, fy, fz, tx, ty, tz] in body frame. + """ + self.wrench_command_b.zero_() + + root_quat_w, root_ang_vel_b, root_lin_vel_w = self._root_state_tensors() + + # Compute acceleration from velocity tracking + acc = self._compute_acceleration( + setpoint_velocity=command[:, :3], root_quat_w=root_quat_w, root_lin_vel_w=root_lin_vel_w + ) + + forces_w = (acc - self.gravity) * self.mass.view(-1, 1) + + # Project forces to body z-axis for thrust command + body_z_w = math_utils.matrix_from_quat(root_quat_w)[:, :, 2] + self.wrench_command_b[:, 2] = torch.sum(forces_w * body_z_w, dim=1) + + # Compute desired orientation from force direction and yaw setpoint + roll, pitch, yaw = math_utils.euler_xyz_from_quat(root_quat_w) + desired_quat = compute_desired_orientation(forces_w, yaw, self.rotation_matrix_buffer) + + # Compute desired angular velocity in body frame from yaw rate command + desired_angvel_b = yaw_rate_to_body_angvel(command[:, 3], roll, pitch, self.device) + + # Compute torque command + self.wrench_command_b[:, 3:6] = compute_body_torque( + desired_quat, + desired_angvel_b, + root_quat_w, + root_ang_vel_b, + self.robot_inertia, + self.K_rot_current, + self.K_angvel_current, + self.cfg.max_yaw_rate, + ) + + return self.wrench_command_b + + def _randomize_params(self, env_ids: slice | torch.Tensor): + """Randomize controller gains for the given environments if enabled.""" + self.K_vel_current[env_ids] = math_utils.sample_uniform( + self.K_vel_range[env_ids, 0], self.K_vel_range[env_ids, 1], self.K_vel_range[env_ids, 0].shape, self.device + ) + self.K_rot_current[env_ids] = math_utils.sample_uniform( + self.K_rot_range[env_ids, 0], self.K_rot_range[env_ids, 1], self.K_rot_range[env_ids, 0].shape, self.device + ) + self.K_angvel_current[env_ids] = math_utils.sample_uniform( + self.K_angvel_range[env_ids, 0], + self.K_angvel_range[env_ids, 1], + self.K_angvel_range[env_ids, 0].shape, + self.device, + ) + + def _compute_acceleration( + self, setpoint_velocity: torch.Tensor, root_quat_w: torch.Tensor, root_lin_vel_w: torch.Tensor + ) -> torch.Tensor: + """Compute desired acceleration from velocity tracking error. + + Args: + setpoint_velocity: (num_envs, 3) desired velocity in body frame. + + Returns: + (num_envs, 3) desired acceleration in body frame. + """ + # Get yaw-only orientation (vehicle frame) + _, _, yaw = math_utils.euler_xyz_from_quat(root_quat_w) + vehicle_quat = math_utils.quat_from_euler_xyz(torch.zeros_like(yaw), torch.zeros_like(yaw), yaw) + + # Transform setpoint from body to world frame + setpoint_velocity_w = math_utils.quat_apply(vehicle_quat, setpoint_velocity) + + # Compute velocity error and acceleration command + velocity_error = setpoint_velocity_w - root_lin_vel_w + return self.K_vel_current * velocity_error diff --git a/source/isaaclab_contrib/isaaclab_contrib/controllers/lee_velocity_control_cfg.py b/source/isaaclab_contrib/isaaclab_contrib/controllers/lee_velocity_control_cfg.py new file mode 100644 index 000000000000..13ef9814d268 --- /dev/null +++ b/source/isaaclab_contrib/isaaclab_contrib/controllers/lee_velocity_control_cfg.py @@ -0,0 +1,34 @@ +# Copyright (c) 2022-2026, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md). +# All rights reserved. +# +# SPDX-License-Identifier: BSD-3-Clause + +from dataclasses import MISSING + +from isaaclab.utils import configclass + +from .lee_controller_base_cfg import LeeControllerBaseCfg +from .lee_velocity_control import LeeVelController + + +@configclass +class LeeVelControllerCfg(LeeControllerBaseCfg): + """Configuration for a Lee-style geometric quadrotor velocity controller. + + Unless otherwise noted, vectors are ordered as (x, y, z) in the simulation world/body frames. + The velocity controller gains are sampled uniformly per environment between + their corresponding ``*_min`` and ``*_max`` bounds at reset. + """ + + class_type: type = LeeVelController + """The class type for the velocity controller.""" + + K_vel_range: tuple[tuple[float, float, float], tuple[float, float, float]] = MISSING + """Velocity error proportional gain range about body axes [unitless]. + + This is a tuple of two tuples containing the minimum and maximum gains for each axis (x, y, z). + Format: ((min_x, min_y, min_z), (max_x, max_y, max_z)) + + Example: + ((2.5, 2.5, 1.5), (3.5, 3.5, 2.0)) for ARL Robot 1 + """ diff --git a/source/isaaclab_contrib/isaaclab_contrib/mdp/__init__.pyi b/source/isaaclab_contrib/isaaclab_contrib/mdp/__init__.pyi index 412db0ce4d8f..497bd981d0dd 100644 --- a/source/isaaclab_contrib/isaaclab_contrib/mdp/__init__.pyi +++ b/source/isaaclab_contrib/isaaclab_contrib/mdp/__init__.pyi @@ -5,7 +5,9 @@ __all__ = [ "ThrustAction", + "NavigationAction", "ThrustActionCfg", + "NavigationActionCfg", ] -from .actions import ThrustAction, ThrustActionCfg +from .actions import NavigationAction, NavigationActionCfg, ThrustAction, ThrustActionCfg diff --git a/source/isaaclab_contrib/isaaclab_contrib/mdp/actions/__init__.pyi b/source/isaaclab_contrib/isaaclab_contrib/mdp/actions/__init__.pyi index 8203016432d4..ede3ae69e2d0 100644 --- a/source/isaaclab_contrib/isaaclab_contrib/mdp/actions/__init__.pyi +++ b/source/isaaclab_contrib/isaaclab_contrib/mdp/actions/__init__.pyi @@ -5,8 +5,10 @@ __all__ = [ "ThrustAction", + "NavigationAction", "ThrustActionCfg", + "NavigationActionCfg", ] -from .thrust_actions import ThrustAction -from .thrust_actions_cfg import ThrustActionCfg +from .thrust_actions import NavigationAction, ThrustAction +from .thrust_actions_cfg import NavigationActionCfg, ThrustActionCfg diff --git a/source/isaaclab_contrib/isaaclab_contrib/mdp/actions/thrust_actions.py b/source/isaaclab_contrib/isaaclab_contrib/mdp/actions/thrust_actions.py index 5ed60f190c4f..d529692a8485 100644 --- a/source/isaaclab_contrib/isaaclab_contrib/mdp/actions/thrust_actions.py +++ b/source/isaaclab_contrib/isaaclab_contrib/mdp/actions/thrust_actions.py @@ -244,3 +244,171 @@ def apply_actions(self): """ # Set thrust targets using thruster IDs self._asset.set_thrust_target(self.processed_actions, thruster_ids=self._thruster_ids) + + +class NavigationAction(ThrustAction): + """Navigation action term that converts high-level navigation commands to thrust commands + using a geometric tracking controller. + + This action term extends `ThrustAction` by adding a controller layer that computes wrench + (force and torque) commands from navigation setpoints, then allocates those wrenches to + individual thruster commands using the multirotor's allocation matrix. + + The controller type is automatically determined based on the `controller_cfg` type: + - LeeVelControllerCfg: Velocity tracking controller + - LeePosControllerCfg: Position tracking controller + - LeeAccControllerCfg: Acceleration tracking controller + + The control pipeline: + 1. Process raw actions (scale, offset, clip) using parent `ThrustAction` + 2. Transform processed actions into setpoints constrained within camera FOV + 3. Compute 6-DOF wrench command using the selected Lee controller + 4. Solve thrust allocation: thrust_cmd = pinv(allocation_matrix) @ wrench_cmd + 5. Apply thrust commands to thrusters + + Attributes: + cfg: Configuration for the navigation action term, including controller config. + _lc: Lee controller instance (LeeVelController, LeePosController, or LeeAccController). + + Action Space: + The action dimension is always 3D: (forward_magnitude, pitch_angle, yaw_rate) + + Actions are clipped in range [-1, 1] and are transformed to controller commands: + - Forward position/velocity/acceleration: + [0, max_magnitude] via (action[0] + 1) * cos(pitch) * max_magnitude / 2 + - Lateral position/velocity/acceleration: + Always 0.0 (constrained to camera FOV) + - Vertical position/velocity/acceleration: + [0, max_magnitude] via (action[0] + 1) * sin(pitch) * max_magnitude / 2 + - Yaw command: [-max_yaw_command, max_yaw_command] via action[2] * max_yaw_command (yaw command is yawrate + [rad/s] for velocity and acceleration control and relative yaw change [rad] for position control) + + Where: + - pitch angle is computed as: action[1] * max_inclination_angle + + Parameters (from cfg): + max_magnitude: Maximum translational magnitude for position/velocity/acceleration commands. + max_yaw_command: Maximum yaw command in rad/s for velocity and acceleration + control and relative yaw change [rad] for position control. + max_inclination_angle: Maximum pitch angle in rad. + + Notes: + - The controller's internal states (e.g., integral terms) are reset when `reset()` is called. + - Lateral term is constrained to 0.0 to keep commands within camera FOV. + - The x and z components are derived from magnitude and inclination angle. + - Requires the multirotor asset to have a valid `allocation_matrix` attribute. + + Example: + ```python + cfg = NavigationActionCfg( + controller_cfg=LeeVelControllerCfg(...), + asset_name="robot", + max_magnitude=2.0, + max_yaw_command=1.047, + max_inclination_angle=0.785, # pi/4 + ) + nav_action = NavigationAction(cfg, env) + ``` + """ + + cfg: thrust_actions_cfg.NavigationActionCfg + """The configuration of the action term.""" + + def __init__(self, cfg: thrust_actions_cfg.NavigationActionCfg, env: ManagerBasedEnv) -> None: + # Initialize parent class (this handles all the thruster setup) + super().__init__(cfg, env) + + # Initialize controller using class_type from config + self._lc = self.cfg.controller_cfg.class_type( + cfg=self.cfg.controller_cfg, asset=self._asset, num_envs=self.num_envs, device=self.device + ) + + # Log warning if not using velocity controller + from isaaclab_contrib.controllers import LeeVelControllerCfg + + if not isinstance(self.cfg.controller_cfg, LeeVelControllerCfg): + logger.warning( + "Navigation task tuned for velocity control. " + "Consider using velocity controller for better performance or retune reward function." + ) + + # Cache allocation matrix and its pseudo-inverse (static for this asset/config) + self._allocation_matrix = self._asset.allocation_matrix + self._allocation_pinv = torch.linalg.pinv(self._allocation_matrix) + + # Add buffer to store velocity commands for observations) + self._commands = torch.zeros(self.num_envs, 4, device=self.device) + self._prev_commands = torch.zeros(self.num_envs, 4, device=self.device) + + @property + def action_dim(self) -> int: + return 3 + + @property + def prev_commands(self) -> torch.Tensor: + return self._prev_commands + + @property + def IO_descriptor(self) -> GenericActionIODescriptor: + """The IO descriptor of the action term.""" + # Get parent IO descriptor + descriptor = super().IO_descriptor + # Override action type for navigation + descriptor.action_type = "NavigationAction" + return descriptor + + def process_actions(self, actions: torch.Tensor): + """Process actions by applying scaling, offset, and clipping.""" + # Call parent to handle basic processing + super().process_actions(actions) + + self._has_actions_updated = False + + def apply_actions(self): + """Apply the processed actions as velocity commands.""" + # process the actions to be in the correct range + clamped_action = torch.clamp(self.processed_actions, min=-1.0, max=1.0) + processed_actions = torch.zeros(self.num_envs, 4, device=self.device) + + clamped_action[:, 0] += 1.0 # only allow positive thrust commands [0, 2] + processed_actions[:, 0] = ( + clamped_action[:, 0] + * torch.cos(self.cfg.max_inclination_angle * clamped_action[:, 1]) + * self.cfg.max_magnitude + / 2.0 + ) + processed_actions[:, 1] = 0.0 # set lateral thrust command to 0 + processed_actions[:, 2] = ( + clamped_action[:, 0] + * torch.sin(self.cfg.max_inclination_angle * clamped_action[:, 1]) + * self.cfg.max_magnitude + / 2.0 + ) + processed_actions[:, 3] = clamped_action[:, 2] * self.cfg.max_yaw_command + + # Store velocity commands for observations + if not self._has_actions_updated: + self._prev_commands[:] = self._commands + self._commands[:] = processed_actions + self._has_actions_updated = True + + # Compute wrench command using controller + wrench_command = self._lc.compute(processed_actions) + + # Convert wrench to thrust commands using allocation matrix + thrust_commands = wrench_command @ self._allocation_pinv.T + + # Apply thrust commands using thruster IDs + self._asset.set_thrust_target(thrust_commands, thruster_ids=self._thruster_ids) + + def reset(self, env_ids: Sequence[int] | None = None) -> None: + # Call parent reset + super().reset(env_ids) + # Reset controller internal states + self._lc.reset_idx(env_ids) + + if env_ids is None: + env_ids = slice(None) + + self._commands[env_ids] = 0.0 + self._prev_commands[env_ids] = 0.0 diff --git a/source/isaaclab_contrib/isaaclab_contrib/mdp/actions/thrust_actions_cfg.py b/source/isaaclab_contrib/isaaclab_contrib/mdp/actions/thrust_actions_cfg.py index 3a464b8fce84..d06242f80ab0 100644 --- a/source/isaaclab_contrib/isaaclab_contrib/mdp/actions/thrust_actions_cfg.py +++ b/source/isaaclab_contrib/isaaclab_contrib/mdp/actions/thrust_actions_cfg.py @@ -2,6 +2,7 @@ # All rights reserved. # # SPDX-License-Identifier: BSD-3-Clause +from __future__ import annotations from dataclasses import MISSING from typing import TYPE_CHECKING @@ -10,7 +11,9 @@ from isaaclab.utils import configclass if TYPE_CHECKING: - from .thrust_actions import ThrustAction + from isaaclab_contrib.controllers import LeeAccControllerCfg, LeePosControllerCfg, LeeVelControllerCfg + + from .thrust_actions import NavigationAction, ThrustAction @configclass @@ -72,7 +75,7 @@ class ThrustActionCfg(ActionTermCfg): - :class:`~isaaclab.managers.ActionTermCfg`: Base action term configuration """ - class_type: type["ThrustAction"] | str = "{DIR}.thrust_actions:ThrustAction" + class_type: type[ThrustAction] | str = "{DIR}.thrust_actions:ThrustAction" asset_name: str = MISSING """Name or regex expression of the asset that the action will be mapped to. @@ -168,3 +171,37 @@ class ThrustActionCfg(ActionTermCfg): If ``False``, the manually specified :attr:`offset` value is used. """ + + +@configclass +class NavigationActionCfg(ThrustActionCfg): + """Configuration for the navigation action term. + + This action term constrains the controller action to be within the field of view (FOV) + of the camera sensor. Specifically: + + - **y-component**: Always 0, as the camera FOV constraint restricts lateral movement + - **x and z components**: Derived from the action max_magnitude and max_inclination_angle, + ensuring the desired acceleration/velocity/position vector remains aligned with the camera's + viewing direction + + This constraint ensures that navigation commands respect the sensor's field of view + limitations, preventing commands that would be out of the camera's visual range. + + See :class:`NavigationAction` for more details. + """ + + class_type: type[NavigationAction] | str = "{DIR}.thrust_actions:NavigationAction" + + controller_cfg: LeeVelControllerCfg | LeePosControllerCfg | LeeAccControllerCfg = MISSING + """The configuration for the Lee velocity controller.""" + + max_magnitude: float = MISSING + """Maximum magnitude for position [m], velocity [m/s], or acceleration [m/s²] commands.""" + + max_yaw_command: float = MISSING + """Maximum yaw command. Yaw rate [rad/s] for velocity and acceleration lee geometric controller and relative + yaw change [rad] for position lee geometric controller.""" + + max_inclination_angle: float = MISSING + """Maximum inclination angle [rad] for position, velocity and acceleration lee geometric controller.""" diff --git a/source/isaaclab_contrib/isaaclab_contrib/utils/math.py b/source/isaaclab_contrib/isaaclab_contrib/utils/math.py new file mode 100644 index 000000000000..840cc62440b5 --- /dev/null +++ b/source/isaaclab_contrib/isaaclab_contrib/utils/math.py @@ -0,0 +1,93 @@ +# Copyright (c) 2022-2026, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md). +# All rights reserved. +# +# SPDX-License-Identifier: BSD-3-Clause + +"""Sub-module containing utilities for various math operations.""" + +# needed to import for allowing type-hinting: torch.Tensor | np.ndarray +from __future__ import annotations + +import logging + +import torch +import torch.nn.functional + +from isaaclab.utils.math import matrix_from_quat + +# import logger +logger = logging.getLogger(__name__) + + +def aggregate_inertia_about_robot_com( + body_inertias_local: torch.Tensor, + body_inv_mass_local: torch.Tensor, + body_com_pos_b: torch.Tensor, + body_com_quat_b: torch.Tensor, + body_pos_b: torch.Tensor, + body_quat_b: torch.Tensor, + eps=1e-12, +) -> tuple[torch.Tensor, torch.Tensor, torch.Tensor]: + """ + Aggregate per-link inertias into a single inertia about the robot COM, + expressed in the base (root link) frame. + + Shapes: + num_envs=N, num_bodies=B + + Args: + body_inertias_local (N,B,9|3,3): Link inertias in the mass/COM frame. + body_inv_mass_local (N,B): Inverse link masses (<=0 treated as padding). + body_com_pos_b (N,B,3): Link COM position relative to the link frame + (massLocalPose translation); used as body_pos_b + R_link_base @ body_com_pos_b. + body_com_quat_b (N,B,4 xyzw): Mass→link rotation (massLocalPose rotation). + body_pos_b (N,B,3): Link origins in base frame. + body_quat_b (N,B,4 xyzw): Link→base orientation. + eps (float): Small value to guard division by zero. + + Returns: + total_mass (N,): Sum of link masses. + I_total (N,3,3): Inertia about robot COM in base frame (symmetrized). + com_robot_b (N,3): Robot COM in base frame. + + Method (base frame throughout): + 1) COM of each link: com_link_b = body_pos_b + R_link_base @ body_com_pos_b + 2) Robot COM: mass-weighted average of com_link_b + 3) Transform each link inertia via R: I_b = R I_local R^T + 4) Parallel-axis: I_pa = m (‖r‖² I - r rᵀ), r = com_link_b - com_robot_b + 5) Sum over links and symmetrize + """ + # Inertia in mass frame (local to COM) + num_envs, num_bodies, _ = body_inertias_local.shape + I_local = body_inertias_local.view(num_envs, num_bodies, 3, 3) + + # Masses + m = torch.where(body_inv_mass_local > 0, 1.0 / body_inv_mass_local, torch.zeros_like(body_inv_mass_local)) + m_sum = m.sum(dim=1, keepdim=True) + valid = (m > 0).float().unsqueeze(-1) + + # Link COM positions in base frame + R_link_base = matrix_from_quat(body_quat_b) + com_link_b = body_pos_b + (R_link_base @ body_com_pos_b[..., :, None]).squeeze(-1) + + # Robot COM base frame (mass-weighted) + com_robot_b = (m.unsqueeze(-1) * com_link_b).sum(dim=1) / (m_sum + eps) + + # Rotate inertia from mass frame to world: R = R_link_base * R_mass + R_mass = matrix_from_quat(body_com_quat_b) + R = R_link_base @ R_mass + I_world = R @ I_local @ R.transpose(-1, -2) + + # Parallel-axis to robot COM + r = com_link_b - com_robot_b[:, None, :] + rrT = r[..., :, None] @ r[..., None, :] + r2 = (r * r).sum(dim=-1, keepdim=True) + I3 = torch.eye(3, device=body_pos_b.device).reshape(1, 1, 3, 3).expand(num_envs, num_bodies, 3, 3) + I_pa = m[..., None, None] * (r2[..., None] * I3 - rrT) + + # Sum over links (ignore zero-mass pads) + I_total = ((I_world + I_pa) * valid[..., None]).sum(dim=1) + I_total = 0.5 * (I_total + I_total.transpose(-1, -2)) + total_mass = m.sum(dim=1) + + return total_mass, I_total, com_robot_b diff --git a/source/isaaclab_contrib/test/controllers/test_drone_geometric_controllers.py b/source/isaaclab_contrib/test/controllers/test_drone_geometric_controllers.py new file mode 100644 index 000000000000..c24c8e5dc870 --- /dev/null +++ b/source/isaaclab_contrib/test/controllers/test_drone_geometric_controllers.py @@ -0,0 +1,345 @@ +# Copyright (c) 2022-2026, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md). +# All rights reserved. +# +# SPDX-License-Identifier: BSD-3-Clause + +"""Launch Isaac Sim Simulator first.""" + +from isaaclab.app import AppLauncher + +# launch omniverse app +simulation_app = AppLauncher(headless=True).app + +"""Rest everything follows.""" + +import types + +import pytest +import torch + +from isaaclab_contrib.controllers import ( + lee_acceleration_control as acc_mod, +) +from isaaclab_contrib.controllers import ( + lee_attitude_control as att_mod, +) +from isaaclab_contrib.controllers import lee_controller_base as base_mod +from isaaclab_contrib.controllers import ( + lee_position_control as pos_mod, +) +from isaaclab_contrib.controllers import ( + lee_velocity_control as vel_mod, +) +from isaaclab_contrib.controllers.lee_acceleration_control_cfg import LeeAccControllerCfg +from isaaclab_contrib.controllers.lee_attitude_control_cfg import LeeAttControllerCfg +from isaaclab_contrib.controllers.lee_position_control_cfg import LeePosControllerCfg +from isaaclab_contrib.controllers.lee_velocity_control_cfg import LeeVelControllerCfg + + +class _DummyRootView: + """Stub articulation view with ``get_masses`` and ``get_inertias`` for controller tests.""" + + def __init__(self, num_envs: int, num_bodies: int, device: torch.device): + inertia_flat = torch.eye(3, device=device).reshape(9) + self._inertias = inertia_flat.unsqueeze(0).unsqueeze(0).expand(num_envs, num_bodies, 9).clone() + self._masses = torch.ones((num_envs, num_bodies), device=device) + + def get_inertias(self) -> torch.Tensor: + return self._inertias + + def get_masses(self) -> torch.Tensor: + return self._masses + + +class _DummyRobot: + """Minimal multirotor stub exposing the attributes used by the controllers.""" + + def __init__(self, num_envs: int, num_bodies: int, device: torch.device): + self.num_bodies = num_bodies + quat_id = torch.tensor([0.0, 0.0, 0.0, 1.0], device=device) + self.data = types.SimpleNamespace( + root_link_quat_w=quat_id.repeat(num_envs, 1), + root_quat_w=quat_id.repeat(num_envs, 1), + root_pos_w=torch.zeros((num_envs, 3), device=device), + root_lin_vel_w=torch.zeros((num_envs, 3), device=device), + root_ang_vel_b=torch.zeros((num_envs, 3), device=device), + body_link_pos_w=torch.zeros((num_envs, num_bodies, 3), device=device), + body_link_quat_w=quat_id.repeat(num_envs, num_bodies, 1), + body_com_pos_b=torch.zeros((num_envs, num_bodies, 3), device=device), + body_com_quat_b=quat_id.repeat(num_envs, num_bodies, 1), + ) + self.root_view = _DummyRootView(num_envs, num_bodies, device) + + +class _DummySimCfg: + """Mock simulation config.""" + + def __init__(self): + self.gravity = (0.0, 0.0, -9.81) + + +class _DummySimContext: + """Mock simulation context.""" + + def __init__(self): + self.cfg = _DummySimCfg() + + +def _patch_aggregate(monkeypatch, _module, num_envs, device): + def _agg(*_args, **_kwargs): + return ( + torch.ones(num_envs, device=device), + torch.eye(3, device=device).repeat(num_envs, 1, 1), + torch.zeros((num_envs, 3, 3), device=device), + ) + + monkeypatch.setattr(base_mod, "aggregate_inertia_about_robot_com", _agg) + + +def _patch_sim_context(monkeypatch: pytest.MonkeyPatch, module) -> None: + """Monkeypatch SimulationContext.instance() to return a mock.""" + import isaaclab.sim as sim_utils + + def _mock_instance(): + return _DummySimContext() + + monkeypatch.setattr(sim_utils.SimulationContext, "instance", _mock_instance) + + +def _device_param(device_str: str) -> torch.device: + """Return the torch.device or skip when CUDA is unavailable.""" + if device_str == "cuda" and not torch.cuda.is_available(): + pytest.skip("CUDA not available on this system") + return torch.device(device_str) + + +def _create_vel_cfg() -> LeeVelControllerCfg: + """Create velocity controller config with required parameters.""" + cfg = LeeVelControllerCfg() + cfg.K_vel_range = ((2.7, 2.7, 1.3), (3.3, 3.3, 1.7)) + cfg.K_rot_range = ((1.6, 1.6, 0.25), (1.85, 1.85, 0.4)) + cfg.K_angvel_range = ((0.4, 0.4, 0.075), (0.5, 0.5, 0.09)) + cfg.max_inclination_angle_rad = 1.0471975511965976 + cfg.max_yaw_rate = 1.0471975511965976 + return cfg + + +def _create_pos_cfg() -> LeePosControllerCfg: + """Create position controller config with required parameters.""" + cfg = LeePosControllerCfg() + cfg.K_pos_range = ((3.0, 3.0, 2.0), (4.0, 4.0, 2.5)) + cfg.K_vel_range = ((2.5, 2.5, 1.5), (3.5, 3.5, 2.0)) + cfg.K_rot_range = ((1.6, 1.6, 0.25), (1.85, 1.85, 0.4)) + cfg.K_angvel_range = ((0.4, 0.4, 0.075), (0.5, 0.5, 0.09)) + cfg.max_inclination_angle_rad = 1.0471975511965976 + cfg.max_yaw_rate = 1.0471975511965976 + return cfg + + +def _create_acc_cfg() -> LeeAccControllerCfg: + """Create acceleration controller config with required parameters.""" + cfg = LeeAccControllerCfg() + cfg.K_rot_range = ((1.6, 1.6, 0.25), (1.85, 1.85, 0.4)) + cfg.K_angvel_range = ((0.4, 0.4, 0.075), (0.5, 0.5, 0.09)) + cfg.max_inclination_angle_rad = 1.0471975511965976 + cfg.max_yaw_rate = 1.0471975511965976 + return cfg + + +def _create_att_cfg() -> LeeAttControllerCfg: + """Create attitude controller config with required parameters.""" + cfg = LeeAttControllerCfg() + cfg.K_rot_range = ((1.6, 1.6, 0.25), (1.85, 1.85, 0.4)) + cfg.K_angvel_range = ((0.4, 0.4, 0.075), (0.5, 0.5, 0.09)) + cfg.max_yaw_rate = 1.0471975511965976 + return cfg + + +@pytest.mark.parametrize("device_str", ["cpu", "cuda"]) +@pytest.mark.parametrize("num_envs", [1, 2, 8]) +@pytest.mark.parametrize("num_bodies", [1, 4]) +@pytest.mark.parametrize( + "controller_cls,cfg_factory,mod_name", + [ + ("LeeVelController", _create_vel_cfg, vel_mod), + ("LeePosController", _create_pos_cfg, pos_mod), + ("LeeAccController", _create_acc_cfg, acc_mod), + ("LeeAttController", _create_att_cfg, att_mod), + ], +) +def test_lee_controllers_basic( + monkeypatch: pytest.MonkeyPatch, + device_str: str, + num_envs: int, + num_bodies: int, + controller_cls: str, + cfg_factory, + mod_name, +): + """Controllers return finite (N, 6) wrench on zero state and counter gravity on +Z. + + Tests various configurations of number of environments and bodies to catch edge cases. + """ + device = _device_param(device_str) + _patch_aggregate(monkeypatch, mod_name, num_envs, device) + _patch_sim_context(monkeypatch, mod_name) + robot = _DummyRobot(num_envs, num_bodies, device) + + cfg = cfg_factory() + controller = getattr(mod_name, controller_cls)(cfg, robot, num_envs=num_envs, device=str(device)) + + command = torch.zeros((num_envs, 4), device=device) + + wrench = controller.compute(command) + + assert wrench.shape == (num_envs, 6), f"Expected shape ({num_envs}, 6), got {wrench.shape}" + assert torch.isfinite(wrench).all(), "Wrench contains non-finite values" + assert torch.all(wrench[:, 2] > 0.0), "Body-z force should oppose gravity" + + +@pytest.mark.parametrize("device_str", ["cpu", "cuda"]) +@pytest.mark.parametrize("num_envs", [1, 2, 8]) +@pytest.mark.parametrize("num_bodies", [1, 4]) +def test_lee_vel_randomize_params_within_bounds( + monkeypatch: pytest.MonkeyPatch, device_str: str, num_envs: int, num_bodies: int +): + """Randomized gains stay within configured ranges for velocity controller. + + Tests edge cases with single and multiple environments and bodies. + """ + device = _device_param(device_str) + _patch_aggregate(monkeypatch, vel_mod, num_envs, device) + _patch_sim_context(monkeypatch, vel_mod) + robot = _DummyRobot(num_envs, num_bodies, device) + + cfg = _create_vel_cfg() + controller = vel_mod.LeeVelController(cfg, robot, num_envs=num_envs, device=str(device)) + + controller.reset_idx(env_ids=None) + + # Ensure tensors are on the correct device + K_vel_min = torch.tensor(cfg.K_vel_range[0], device=device, dtype=torch.float32) + K_vel_max = torch.tensor(cfg.K_vel_range[1], device=device, dtype=torch.float32) + + # Move controller gains to same device if needed + K_vel_current = controller.K_vel_current.to(device) + + assert K_vel_current.shape == (num_envs, 3), f"Expected shape ({num_envs}, 3), got {K_vel_current.shape}" + assert torch.all(K_vel_current >= K_vel_min), f"K_vel below minimum: {K_vel_current.min()} < {K_vel_min.min()}" + assert torch.all(K_vel_current <= K_vel_max), f"K_vel above maximum: {K_vel_current.max()} > {K_vel_max.max()}" + + +@pytest.mark.parametrize("device_str", ["cpu", "cuda"]) +@pytest.mark.parametrize("num_envs", [1, 2, 8]) +@pytest.mark.parametrize("num_bodies", [1, 4]) +def test_lee_pos_randomize_params_within_bounds( + monkeypatch: pytest.MonkeyPatch, device_str: str, num_envs: int, num_bodies: int +): + """Randomized gains stay within configured ranges for position controller. + + Tests edge cases with single and multiple environments and bodies. + """ + device = _device_param(device_str) + _patch_aggregate(monkeypatch, pos_mod, num_envs, device) + _patch_sim_context(monkeypatch, pos_mod) + robot = _DummyRobot(num_envs, num_bodies, device) + + cfg = _create_pos_cfg() + controller = pos_mod.LeePosController(cfg, robot, num_envs=num_envs, device=str(device)) + + controller.reset_idx(env_ids=None) + + # Check K_pos gains + K_pos_min = torch.tensor(cfg.K_pos_range[0], device=device, dtype=torch.float32) + K_pos_max = torch.tensor(cfg.K_pos_range[1], device=device, dtype=torch.float32) + K_pos_current = controller.K_pos_current.to(device) + + assert K_pos_current.shape == (num_envs, 3), f"Expected shape ({num_envs}, 3), got {K_pos_current.shape}" + assert torch.all(K_pos_current >= K_pos_min), f"K_pos below minimum: {K_pos_current.min()} < {K_pos_min.min()}" + assert torch.all(K_pos_current <= K_pos_max), f"K_pos above maximum: {K_pos_current.max()} > {K_pos_max.max()}" + + +@pytest.mark.parametrize("device_str", ["cpu", "cuda"]) +@pytest.mark.parametrize("num_envs", [1, 2, 8]) +@pytest.mark.parametrize("num_bodies", [1, 4]) +def test_lee_acc_randomize_params_within_bounds( + monkeypatch: pytest.MonkeyPatch, device_str: str, num_envs: int, num_bodies: int +): + """Randomized gains stay within configured ranges for acceleration controller. + + Tests edge cases with single and multiple environments and bodies. + """ + device = _device_param(device_str) + _patch_aggregate(monkeypatch, acc_mod, num_envs, device) + _patch_sim_context(monkeypatch, acc_mod) + robot = _DummyRobot(num_envs, num_bodies, device) + + cfg = _create_acc_cfg() + controller = acc_mod.LeeAccController(cfg, robot, num_envs=num_envs, device=str(device)) + + controller.reset_idx(env_ids=None) + + # Check K_rot gains + K_rot_min = torch.tensor(cfg.K_rot_range[0], device=device, dtype=torch.float32) + K_rot_max = torch.tensor(cfg.K_rot_range[1], device=device, dtype=torch.float32) + K_rot_current = controller.K_rot_current.to(device) + + assert K_rot_current.shape == (num_envs, 3), f"Expected shape ({num_envs}, 3), got {K_rot_current.shape}" + assert torch.all(K_rot_current >= K_rot_min), f"K_rot below minimum: {K_rot_current.min()} < {K_rot_min.min()}" + assert torch.all(K_rot_current <= K_rot_max), f"K_rot above maximum: {K_rot_current.max()} > {K_rot_max.max()}" + + # Check K_angvel gains + K_angvel_min = torch.tensor(cfg.K_angvel_range[0], device=device, dtype=torch.float32) + K_angvel_max = torch.tensor(cfg.K_angvel_range[1], device=device, dtype=torch.float32) + K_angvel_current = controller.K_angvel_current.to(device) + + assert K_angvel_current.shape == (num_envs, 3), f"Expected shape ({num_envs}, 3), got {K_angvel_current.shape}" + assert torch.all(K_angvel_current >= K_angvel_min), ( + f"K_angvel below minimum: {K_angvel_current.min()} < {K_angvel_min.min()}" + ) + assert torch.all(K_angvel_current <= K_angvel_max), ( + f"K_angvel above maximum: {K_angvel_current.max()} > {K_angvel_max.max()}" + ) + + +@pytest.mark.parametrize("device_str", ["cpu", "cuda"]) +@pytest.mark.parametrize("num_envs", [1, 2, 8]) +@pytest.mark.parametrize("num_bodies", [1, 4]) +def test_lee_att_randomize_params_within_bounds( + monkeypatch: pytest.MonkeyPatch, device_str: str, num_envs: int, num_bodies: int +): + """Randomized gains stay within configured ranges for attitude controller. + + Tests edge cases with single and multiple environments and bodies. + """ + device = _device_param(device_str) + _patch_aggregate(monkeypatch, att_mod, num_envs, device) + _patch_sim_context(monkeypatch, att_mod) + robot = _DummyRobot(num_envs, num_bodies, device) + + cfg = _create_att_cfg() + controller = att_mod.LeeAttController(cfg, robot, num_envs=num_envs, device=str(device)) + + controller.reset_idx(env_ids=None) + + # Check K_rot gains + K_rot_min = torch.tensor(cfg.K_rot_range[0], device=device, dtype=torch.float32) + K_rot_max = torch.tensor(cfg.K_rot_range[1], device=device, dtype=torch.float32) + K_rot_current = controller.K_rot_current.to(device) + + assert K_rot_current.shape == (num_envs, 3), f"Expected shape ({num_envs}, 3), got {K_rot_current.shape}" + assert torch.all(K_rot_current >= K_rot_min), f"K_rot below minimum: {K_rot_current.min()} < {K_rot_min.min()}" + assert torch.all(K_rot_current <= K_rot_max), f"K_rot above maximum: {K_rot_current.max()} > {K_rot_max.max()}" + + # Check K_angvel gains + K_angvel_min = torch.tensor(cfg.K_angvel_range[0], device=device, dtype=torch.float32) + K_angvel_max = torch.tensor(cfg.K_angvel_range[1], device=device, dtype=torch.float32) + K_angvel_current = controller.K_angvel_current.to(device) + + assert K_angvel_current.shape == (num_envs, 3), f"Expected shape ({num_envs}, 3), got {K_angvel_current.shape}" + assert torch.all(K_angvel_current >= K_angvel_min), ( + f"K_angvel below minimum: {K_angvel_current.min()} < {K_angvel_min.min()}" + ) + assert torch.all(K_angvel_current <= K_angvel_max), ( + f"K_angvel above maximum: {K_angvel_current.max()} > {K_angvel_max.max()}" + ) diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/drone_arl/mdp/__init__.pyi b/source/isaaclab_tasks/isaaclab_tasks/manager_based/drone_arl/mdp/__init__.pyi index d54142b0609d..3085421b05d1 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/drone_arl/mdp/__init__.pyi +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/drone_arl/mdp/__init__.pyi @@ -3,19 +3,5 @@ # # SPDX-License-Identifier: BSD-3-Clause -__all__ = [ - "DroneUniformPoseCommand", - "DroneUniformPoseCommandCfg", - "base_roll_pitch", - "generated_drone_commands", - "ang_vel_xyz_exp", - "distance_to_goal_exp", - "lin_vel_xyz_exp", - "yaw_aligned", -] - -from .commands import DroneUniformPoseCommand, DroneUniformPoseCommandCfg -from .observations import base_roll_pitch, generated_drone_commands -from .rewards import ang_vel_xyz_exp, distance_to_goal_exp, lin_vel_xyz_exp, yaw_aligned from isaaclab.envs.mdp import * from isaaclab_contrib.mdp import * diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/drone_arl/mdp/commands/drone_pose_command.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/drone_arl/mdp/commands/drone_pose_command.py index a9072367c83b..5765177a4659 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/drone_arl/mdp/commands/drone_pose_command.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/drone_arl/mdp/commands/drone_pose_command.py @@ -42,7 +42,7 @@ def _update_metrics(self): ) # compute the error pos_error, rot_error = compute_pose_error( - # Sub-terrain shift for correct position error calculation @grzemal + # Sub-terrain shift for correct position error calculation self.pose_command_b[:, :3] + self._env.scene.env_origins, self.pose_command_w[:, 3:], self.robot.data.body_pos_w.torch[:, self.body_idx], @@ -58,7 +58,7 @@ def _debug_vis_callback(self, event): return # update the markers # -- goal pose - # Sub-terrain shift for visualization purposes @grzemal + # Sub-terrain shift for visualization purposes self.goal_pose_visualizer.visualize( self.pose_command_b[:, :3] + self._env.scene.env_origins, self.pose_command_b[:, 3:] ) diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/drone_arl/mdp/curriculums.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/drone_arl/mdp/curriculums.py new file mode 100644 index 000000000000..3fc33a9328b5 --- /dev/null +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/drone_arl/mdp/curriculums.py @@ -0,0 +1,148 @@ +# Copyright (c) 2022-2026, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md). +# All rights reserved. +# +# SPDX-License-Identifier: BSD-3-Clause + +"""Common curriculum classes for the drone navigation environment. + +The curriculum classes can be passed to the :class:`isaaclab.managers.CurriculumTermCfg` object to enable +the curriculum introduced by the class. +""" + +from __future__ import annotations + +from collections.abc import Sequence +from typing import TYPE_CHECKING + +import torch +import warp as wp + +from isaaclab.managers import ManagerTermBase, SceneEntityCfg +from isaaclab.managers.manager_term_cfg import CurriculumTermCfg + +if TYPE_CHECKING: + from isaaclab.assets import Articulation + from isaaclab.envs import ManagerBasedRLEnv + + +class ObstacleDensityCurriculum(ManagerTermBase): + """Curriculum that adjusts obstacle density based on performance. + + The difficulty state is stored internally in the class instance, avoiding + the need to store state on the environment object. + + The curriculum tracks per-environment difficulty levels used to control + the number of obstacles spawned in each environment. Difficulty progresses + based on agent performance (successful goal reaching vs. collisions). + + Attributes: + cfg: The configuration of the curriculum term. + _min_difficulty: Minimum difficulty level for obstacle density. + _max_difficulty: Maximum difficulty level for obstacle density. + _difficulty_levels: Tensor of shape (num_envs,) tracking difficulty per environment. + _asset_cfg: Scene entity configuration for the robot. + _command_name: Name of the command to track. + """ + + cfg: CurriculumTermCfg + """The configuration of the curriculum term.""" + + def __init__(self, cfg: CurriculumTermCfg, env: ManagerBasedRLEnv): + """Initialize the curriculum term. + + Args: + cfg: Configuration for the curriculum term. + env: The manager-based RL environment instance. + """ + super().__init__(cfg, env) + + # Extract parameters from config + self._min_difficulty = cfg.params["min_difficulty"] + self._max_difficulty = cfg.params["max_difficulty"] + self._asset_cfg = cfg.params.get("asset_cfg", SceneEntityCfg("robot")) + self._command_name = cfg.params.get("command_name", "target_pose") + + # Initialize difficulty levels for all environments + self._difficulty_levels = torch.ones(env.num_envs, device=env.device) * self._min_difficulty + + def __call__( + self, + env: ManagerBasedRLEnv, + env_ids: Sequence[int], + asset_cfg: SceneEntityCfg = SceneEntityCfg("robot"), + command_name: str = "target_pose", + min_difficulty: int | None = None, + max_difficulty: int | None = None, + ) -> float: + """Update obstacle density curriculum based on performance. + + Args: + env: The manager-based RL environment instance. + env_ids: Environment indices to update. + asset_cfg: Scene entity configuration for the robot. Defaults to SceneEntityCfg("robot"). + command_name: Name of the command to track. Defaults to "target_pose". + max_difficulty: Maximum difficulty level. Defaults to 10. + min_difficulty: Minimum difficulty level. Defaults to 2. + + Returns: + Mean difficulty level across all environments (for logging). + """ + # Extract robot and command + asset: Articulation = env.scene[asset_cfg.name] + command = env.command_manager.get_command(command_name) + + target_position_w = command[:, :3].clone() + current_position = wp.to_torch(asset.data.root_pos_w) - env.scene.env_origins + position_error = torch.norm(target_position_w[env_ids] - current_position[env_ids], dim=1) + + # Decide difficulty changes + crashed = env.termination_manager.terminated[env_ids] + move_up = position_error < 1.5 # Success + move_down = crashed & ~move_up + + # Update difficulty levels + self._difficulty_levels[env_ids] += move_up.long() - move_down.long() + self._difficulty_levels[env_ids] = torch.clamp( + self._difficulty_levels[env_ids], min=self._min_difficulty, max=self._max_difficulty - 1 + ) + + return self._difficulty_levels.float().mean().item() + + @property + def difficulty_levels(self) -> torch.Tensor: + """Get the current difficulty levels for all environments. + + Returns: + Tensor of shape (num_envs,) with difficulty levels. + """ + return self._difficulty_levels + + @property + def min_difficulty(self) -> int: + """Get the minimum difficulty level.""" + return self._min_difficulty + + @property + def max_difficulty(self) -> int: + """Get the maximum difficulty level.""" + return self._max_difficulty + + +def get_obstacle_curriculum_term(env: ManagerBasedRLEnv) -> ObstacleDensityCurriculum | None: + """Get the ObstacleDensityCurriculum instance from the curriculum manager. + + This helper function searches the curriculum manager for an active + ObstacleDensityCurriculum term and returns it if found. This allows + other MDP components (rewards, events) to access the curriculum state. + + Args: + env: The manager-based RL environment instance. + + Returns: + The ObstacleDensityCurriculum instance if found, None otherwise. + """ + curriculum_manager = env.curriculum_manager + for term_cfg in curriculum_manager._term_cfgs: + if isinstance(term_cfg.func, ObstacleDensityCurriculum): + return term_cfg.func + return None diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/drone_arl/mdp/events.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/drone_arl/mdp/events.py new file mode 100644 index 000000000000..992521fdd47e --- /dev/null +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/drone_arl/mdp/events.py @@ -0,0 +1,189 @@ +# Copyright (c) 2022-2026, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md). +# All rights reserved. +# +# SPDX-License-Identifier: BSD-3-Clause + +"""Event functions specific to the drone ARL environments.""" + +from __future__ import annotations + +from typing import TYPE_CHECKING + +import torch + +import isaaclab.utils.math as math_utils +from isaaclab.managers import SceneEntityCfg + +from .curriculums import get_obstacle_curriculum_term + +if TYPE_CHECKING: + from isaaclab.assets import RigidObjectCollection + from isaaclab.envs import ManagerBasedRLEnv + + +def reset_obstacles_with_individual_ranges( + env: ManagerBasedRLEnv, + env_ids: torch.Tensor, + asset_cfg: SceneEntityCfg, + obstacle_configs: dict, + wall_configs: dict, + env_size: tuple[float, float, float], + use_curriculum: bool = True, + min_num_obstacles: int = 1, + max_num_obstacles: int = 10, + ground_offset: float = 0.1, +) -> None: + """Reset obstacle and wall positions for specified environments without collision checking. + + This function repositions all walls and a curriculum-determined subset of obstacles + within the specified environment bounds. + + Walls are positioned at fixed locations based on their configuration ratios. Obstacles + are randomly placed within their designated zones, with the number of active obstacles + determined by the curriculum difficulty level. Inactive obstacles are moved far below + the scene (-1000m in Z) to effectively remove them from the environment. + + The curriculum scaling works as: + num_obstacles = min + (difficulty / max_difficulty) * (max - min) + + Args: + env: The manager-based RL environment instance. + env_ids: Tensor of environment indices to reset. + asset_cfg: Scene entity configuration identifying the obstacle collection. + obstacle_configs: Dictionary mapping obstacle type names to their BoxCfg + configurations, specifying size and placement ranges. + wall_configs: Dictionary mapping wall names to their BoxCfg configurations. + env_size: Tuple of (length, width, height) defining the environment bounds in meters. + use_curriculum: If True, number of obstacles scales with curriculum difficulty. + If False, spawns max_num_obstacles in every environment. Defaults to True. + min_num_obstacles: Minimum number of obstacles to spawn per environment. + Defaults to 1. + max_num_obstacles: Maximum number of obstacles to spawn per environment. + Defaults to 10. + ground_offset: Z-axis offset to prevent obstacles from spawning at z=0. + Defaults to 0.1 meters. + + Note: + This function expects the environment to have `_obstacle_difficulty_levels` and + `_max_obstacle_difficulty` attributes when `use_curriculum=True`. These are + typically set by :func:`obstacle_density_curriculum`. + """ + obstacles: RigidObjectCollection = env.scene[asset_cfg.name] + + num_objects = obstacles.num_objects + num_envs = len(env_ids) + object_names = obstacles.object_names + + # Get difficulty levels per environment + if use_curriculum: + curriculum_term = get_obstacle_curriculum_term(env) + if curriculum_term is not None: + # Get difficulty levels for the specific environments being reset + difficulty_levels = curriculum_term.difficulty_levels[env_ids] + max_difficulty = curriculum_term.max_difficulty + else: + # Fallback: use max obstacles if curriculum not found + difficulty_levels = torch.ones(num_envs, device=env.device) * max_num_obstacles + max_difficulty = max_num_obstacles + else: + difficulty_levels = torch.ones(num_envs, device=env.device) * max_num_obstacles + max_difficulty = max_num_obstacles + + # Calculate active obstacles per env based on difficulty + obstacles_per_env = ( + min_num_obstacles + (difficulty_levels / max_difficulty) * (max_num_obstacles - min_num_obstacles) + ).long() + + # Prepare tensors + all_poses = torch.zeros(num_envs, num_objects, 7, device=env.device) + all_velocities = torch.zeros(num_envs, num_objects, 6, device=env.device) + + wall_names = list(wall_configs.keys()) + obstacle_types = list(obstacle_configs.values()) + env_size_t = torch.tensor(env_size, device=env.device) + + # place walls + for wall_name, wall_cfg in wall_configs.items(): + if wall_name in object_names: + wall_idx = object_names.index(wall_name) + + min_ratio = torch.tensor(wall_cfg.center_ratio_min, device=env.device) + max_ratio = torch.tensor(wall_cfg.center_ratio_max, device=env.device) + + if torch.allclose(min_ratio, max_ratio): + center_ratios = min_ratio.unsqueeze(0).repeat(num_envs, 1) + else: + ratios = torch.rand(num_envs, 3, device=env.device) + center_ratios = ratios * (max_ratio - min_ratio) + min_ratio + + positions = (center_ratios - 0.5) * env_size_t + positions[:, 2] += ground_offset + positions += env.scene.env_origins[env_ids] + + all_poses[:, wall_idx, 0:3] = positions + all_poses[:, wall_idx, 3:7] = torch.tensor([1.0, 0.0, 0.0, 0.0], device=env.device).repeat(num_envs, 1) + + # Get obstacle indices + obstacle_indices = [idx for idx, name in enumerate(object_names) if name not in wall_names] + + if len(obstacle_indices) == 0: + obstacles.write_object_pose_to_sim(all_poses, env_ids=env_ids) + obstacles.write_object_velocity_to_sim(all_velocities, env_ids=env_ids) + return + + # Determine which obstacles are active per env + active_masks = torch.zeros(num_envs, len(obstacle_indices), dtype=torch.bool, device=env.device) + for env_idx in range(num_envs): + num_active = obstacles_per_env[env_idx].item() + perm = torch.randperm(len(obstacle_indices), device=env.device)[:num_active] + active_masks[env_idx, perm] = True + + # place obstacles + for obj_list_idx in range(len(obstacle_indices)): + obj_idx = obstacle_indices[obj_list_idx] + + # Which envs need this obstacle? + envs_need_obstacle = active_masks[:, obj_list_idx] + + if not envs_need_obstacle.any(): + # Move all to -1000 + all_poses[:, obj_idx, 0:3] = env.scene.env_origins[env_ids] + torch.tensor( + [0.0, 0.0, -1000.0], device=env.device + ) + all_poses[:, obj_idx, 3:7] = torch.tensor([1.0, 0.0, 0.0, 0.0], device=env.device) + continue + + # Get obstacle config + config_idx = obj_list_idx % len(obstacle_types) + obs_cfg = obstacle_types[config_idx] + + min_ratio = torch.tensor(obs_cfg.center_ratio_min, device=env.device) + max_ratio = torch.tensor(obs_cfg.center_ratio_max, device=env.device) + + # sample object positions + num_active_envs = envs_need_obstacle.sum().item() + ratios = torch.rand(num_active_envs, 3, device=env.device) + positions = (ratios * (max_ratio - min_ratio) + min_ratio - 0.5) * env_size_t + positions[:, 2] += ground_offset + + # Add env origins + active_env_indices = torch.where(envs_need_obstacle)[0] + positions += env.scene.env_origins[env_ids[active_env_indices]] + + # Generate quaternions + quats = math_utils.random_orientation(num_envs, device=env.device) + + # Write poses + all_poses[envs_need_obstacle, obj_idx, 0:3] = positions + all_poses[envs_need_obstacle, obj_idx, 3:7] = quats[envs_need_obstacle] + + # Move inactive obstacles far away + inactive = ~envs_need_obstacle + all_poses[inactive, obj_idx, 0:3] = env.scene.env_origins[env_ids[inactive]] + torch.tensor( + [0.0, 0.0, -1000.0], device=env.device + ) + all_poses[inactive, obj_idx, 3:7] = torch.tensor([1.0, 0.0, 0.0, 0.0], device=env.device) + + # Write to sim + obstacles.write_object_pose_to_sim(all_poses, env_ids=env_ids) + obstacles.write_object_velocity_to_sim(all_velocities, env_ids=env_ids) diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/drone_arl/mdp/observations.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/drone_arl/mdp/observations.py index c8b8048bd68b..e084eabcd013 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/drone_arl/mdp/observations.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/drone_arl/mdp/observations.py @@ -11,20 +11,27 @@ from __future__ import annotations +import os from typing import TYPE_CHECKING import torch import isaaclab.utils.math as math_utils -from isaaclab.managers import SceneEntityCfg +from isaaclab.managers import ManagerTermBase, SceneEntityCfg if TYPE_CHECKING: from isaaclab.assets import Articulation from isaaclab.envs import ManagerBasedEnv, ManagerBasedRLEnv + from isaaclab.managers import ObservationTermCfg + from isaaclab.sensors.camera.camera import Camera + from isaaclab.sensors.camera.tiled_camera import TiledCamera + from isaaclab.sensors.ray_caster.multi_mesh_ray_caster_camera import MultiMeshRayCasterCamera + from isaaclab.sensors.ray_caster.ray_caster_camera import RayCasterCamera from isaaclab_contrib.assets import Multirotor from isaaclab.envs.utils.io_descriptors import generic_io_descriptor, record_shape +from isaaclab.utils.assets import ISAACLAB_NUCLEUS_DIR, retrieve_file_path """ State. @@ -57,6 +64,178 @@ def base_roll_pitch(env: ManagerBasedEnv, asset_cfg: SceneEntityCfg = SceneEntit return torch.cat((roll.unsqueeze(-1), pitch.unsqueeze(-1)), dim=-1) +""" +Sensors +""" + + +class ImageLatentObservation(ManagerTermBase): + """Callable observation term that returns VAE latents from camera images. + + This observation term extracts images from a configured camera sensor, normalizes them + based on the data type, and passes them through a pre-trained VAE model to obtain + latent representations. The VAE model is loaded once and cached on the class to avoid + repeated disk loads across all instances. + + The term is designed to work with the Isaac Lab observation manager and integrates + seamlessly with other observation terms in multi-modal observation spaces. + + Attributes: + camera_sensor: The camera sensor to extract images from (TiledCamera, Camera, + RayCasterCamera, or MultiMeshRayCasterCamera). + data_type: Type of data to extract from the sensor (e.g., "distance_to_image_plane"). + convert_perspective_to_orthogonal: Whether to convert perspective depth to orthogonal. + normalize: Whether to normalize images before passing to VAE. + + Example: + To use this in an environment configuration: + + .. code-block:: python + + depth_latent = ObsTerm( + func=mdp.ImageLatentObservation, + params={ + "sensor_cfg": SceneEntityCfg("depth_camera"), + "data_type": "distance_to_image_plane", + "normalize": True, + }, + ) + """ + + _model: torch.jit.ScriptModule | None = None + + def __init__(self, cfg: ObservationTermCfg, env: ManagerBasedRLEnv): + """Initialize the image latent observation term. + + Extracts configuration from cfg.params and caches a reference to the camera sensor + for efficient repeated access during observation collection. + + Args: + cfg: Configuration object containing the observation term configuration, + including params dict with: + - sensor_cfg (SceneEntityCfg): Scene entity config for the camera sensor. + - data_type (str): Data type to extract from the sensor. + - convert_perspective_to_orthogonal (bool, optional): Whether to convert + perspective to orthogonal depth. Defaults to False. + - normalize (bool, optional): Whether to normalize images. Defaults to True. + env: The manager-based RL environment instance. + + Raises: + KeyError: If required params ("sensor_cfg", "data_type") are missing. + RuntimeError: If the specified camera sensor is not found in the scene. + """ + super().__init__(cfg, env) + self.camera_sensor: TiledCamera | Camera | RayCasterCamera | MultiMeshRayCasterCamera = env.scene.sensors[ + cfg.params["sensor_cfg"].name + ] + self.data_type: str = cfg.params["data_type"] + self.convert_perspective_to_orthogonal = bool(cfg.params.get("convert_perspective_to_orthogonal", False)) + self.normalize = bool(cfg.params.get("normalize", True)) + + @classmethod + def _get_model(cls, device): + """Load or retrieve the cached VAE model. + + The model is loaded from disk only once per process and cached on the class. + Subsequent calls return the cached instance, avoiding repeated I/O and model + initialization overhead. + + Args: + device: PyTorch device to load the model onto (e.g., "cpu", "cuda:0"). + + Returns: + Loaded VAE model as a TorchScript ScriptModule, set to evaluation mode. + + Raises: + FileNotFoundError: If the VAE model file cannot be found at the expected path. + RuntimeError: If the model cannot be loaded (e.g., corrupted file). + """ + if cls._model is None: + model_path = os.path.join(ISAACLAB_NUCLEUS_DIR, "Contrib/Drone/vae_model.pt") + download_dir = os.path.join(".pretrained_checkpoints", "drone_arl", "vae_model.pt") + resume_path = retrieve_file_path(model_path, download_dir) + cls._model = torch.jit.load(resume_path, map_location=device) + cls._model.eval() + return cls._model + + def __call__(self, env: ManagerBasedEnv, sensor_cfg: SceneEntityCfg, data_type: str) -> torch.Tensor: + """Compute VAE latents for the current camera frame. + + Extracts images from the camera sensor, applies normalization if configured, + and passes them through the VAE model to obtain latent representations. + + Args: + env: The manager-based environment providing scene and device information. + sensor_cfg: Scene entity config for the camera sensor (unused, already set in __init__). + data_type: Data type to extract from the sensor (unused, already set in __init__). + convert_perspective_to_orthogonal: Whether to convert perspective to orthogonal depth + (unused, already set in __init__). + normalize: Whether to normalize images (unused, already set in __init__). + + Returns: + torch.Tensor: Latent representations from the VAE model. + Shape is determined by the VAE architecture (typically (num_envs, latent_dim)). + + Raises: + ValueError: If data_type is "distance_to_image_plane" but normalize is False, + or if an unsupported data_type is encountered with normalize=True. + RuntimeError: If the VAE model inference fails or tensors have incompatible shapes. + + Notes: + - Images are converted to float16 before passing to the VAE for efficiency. + - Infinity values in depth images are clamped to 10.0 during normalization. + - Very small depth values (< 0.02) are set to -1.0 to indicate invalid regions. + - The parameters (sensor_cfg, data_type, etc.) are ignored here as they are + already stored during initialization. They are included in the signature only + to satisfy the observation manager's parameter validation. + """ + images = self.camera_sensor.data.output[self.data_type].clone() + + if (self.data_type == "distance_to_camera") and self.convert_perspective_to_orthogonal: + images = math_utils.orthogonalize_perspective_depth(images, self.camera_sensor.data.intrinsic_matrices) + + if self.normalize: + if self.data_type == "distance_to_image_plane": + images[images == float("inf")] = 10.0 + images[images == -float("inf")] = 10.0 + images[images > 10.0] = 10.0 + images = images / 10.0 + images[images < 0.02] = -1.0 + else: + raise ValueError(f"Image data type: {self.data_type} not supported") + + vae_model = self._get_model(env.device) + with torch.no_grad(): + latents = vae_model(images.squeeze(-1).half()) + + return latents + + +""" +Actions. +""" + + +@generic_io_descriptor(dtype=torch.float32, observation_type="Action", on_inspect=[record_shape]) +def last_action_navigation(env: ManagerBasedEnv, action_name: str = "velocity_commands") -> torch.Tensor: + """The last processed position/velocity/acceleration commands from the navigation action term. + + This function accesses the position/velocity/acceleration commands (vx, vy, vz, yaw_rate) that + were computed by the NavigationAction term. This avoids duplicating the + action processing logic. + + Args: + env: Manager-based environment providing the action manager. + action_name: Name of the navigation action term. Defaults to "velocity_commands". + + Returns: + torch.Tensor: Shape (num_envs, 4) containing position/velocity/acceleration commands. + """ + action_term = env.action_manager.get_term(action_name) + # Access the velocity_commands property from NavigationAction + return action_term.prev_commands + + """ Commands. """ diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/drone_arl/mdp/rewards.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/drone_arl/mdp/rewards.py index ce635cc544d8..a691df9e2d1e 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/drone_arl/mdp/rewards.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/drone_arl/mdp/rewards.py @@ -8,10 +8,13 @@ from typing import TYPE_CHECKING import torch +import warp as wp import isaaclab.utils.math as math_utils from isaaclab.managers import SceneEntityCfg +from .curriculums import get_obstacle_curriculum_term + if TYPE_CHECKING: from isaaclab.assets import RigidObject from isaaclab.envs import ManagerBasedRLEnv @@ -49,14 +52,65 @@ def distance_to_goal_exp( asset: RigidObject = env.scene[asset_cfg.name] command = env.command_manager.get_command(command_name) - target_position_w = command[:, :3].clone() current_position = asset.data.root_pos_w.torch - env.scene.env_origins # compute the error - position_error_square = torch.sum(torch.square(target_position_w - current_position), dim=1) + position_error_square = torch.sum(torch.square(command[:, :3] - current_position), dim=1) return torch.exp(-position_error_square / std**2) +def distance_to_goal_exp_curriculum( + env: ManagerBasedRLEnv, + asset_cfg: SceneEntityCfg = SceneEntityCfg("robot"), + std: float = 1.0, + command_name: str = "target_pose", +) -> torch.Tensor: + """Reward the distance to a goal position using an exponential kernel with curriculum-based scaling. + + This reward extends the basic exponential distance reward by applying a scaling factor + that increases with the obstacle difficulty level. As the curriculum progresses and + obstacle density increases, the reward weight grows to compensate for the added difficulty. + + The scaling weight is computed as: 1.0 + (difficulty_level / max_difficulty), meaning + the reward can scale from 1.0x (at minimum difficulty) to 2.0x (at maximum difficulty). + + Args: + env: The manager-based RL environment instance. + asset_cfg: SceneEntityCfg identifying the asset (defaults to "robot"). + std: Standard deviation used in the exponential kernel; larger values + produce a gentler falloff. Defaults to 1.0. + command_name: Name of the command to read the target pose from the + environment's command manager. The function expects the command + tensor to contain positions in its first three columns. + + Returns: + A 1-D tensor of shape (num_envs,) containing the per-environment weighted + reward values. Values are in [0, weight], where weight varies based on the + current curriculum difficulty level. + + Note: + If no curriculum is active (i.e., ObstacleDensityCurriculum is not found), + the function behaves identically to :func:`distance_to_goal_exp` with weight=1.0. + """ + # extract the used quantities (to enable type-hinting) + asset: RigidObject = env.scene[asset_cfg.name] + command = env.command_manager.get_command(command_name) + + current_position = wp.to_torch(asset.data.root_pos_w) - env.scene.env_origins + + # compute the error + position_error_square = torch.sum(torch.square(command[:, :3] - current_position), dim=1) + + # Get curriculum term and compute weight + curriculum_term = get_obstacle_curriculum_term(env) + if curriculum_term is not None: + weight = 1.0 + curriculum_term.difficulty_levels.float() / float(curriculum_term.max_difficulty) + else: + weight = 1.0 + + return weight * torch.exp(-position_error_square / std**2) + + def ang_vel_xyz_exp( env: ManagerBasedRLEnv, asset_cfg: SceneEntityCfg = SceneEntityCfg("robot"), std: float = 1.0 ) -> torch.Tensor: @@ -86,6 +140,60 @@ def ang_vel_xyz_exp( return torch.exp(-ang_vel_squared / std**2) +def velocity_to_goal_reward_curriculum( + env: ManagerBasedRLEnv, asset_cfg: SceneEntityCfg = SceneEntityCfg("robot"), command_name: str = "target_pose" +) -> torch.Tensor: + """Reward velocity alignment toward the goal with curriculum-based scaling. + + This reward encourages the agent to move in the direction of the goal by computing + the dot product between the asset's velocity vector and the normalized direction + vector to the goal. A curriculum-based scaling factor is applied that increases + with obstacle difficulty. + + The reward is positive when moving toward the goal, negative when moving away, + and zero when moving perpendicular to the goal direction. The magnitude scales + linearly with speed in the goal direction. + + The scaling weight is computed as: 1.0 + (difficulty_level / max_difficulty), + allowing the reward to scale from 1.0x to 2.0x as difficulty increases. + + Args: + env: The manager-based RL environment instance. + asset_cfg: SceneEntityCfg identifying the asset (defaults to "robot"). + command_name: Name of the command to read the target pose from the + environment's command manager. The function expects the command + tensor to contain positions in its first three columns. + + Returns: + A 1-D tensor of shape (num_envs,) containing the per-environment weighted + reward values. Values can be positive (moving toward goal), negative + (moving away), or zero (perpendicular motion), scaled by the curriculum weight. + + Note: + If no curriculum is active (i.e., ObstacleDensityCurriculum is not found), + the function uses weight=1.0 without curriculum scaling. + """ + # extract the used quantities (to enable type-hinting) + asset: RigidObject = env.scene[asset_cfg.name] + # get the center of the environment + command = env.command_manager.get_command(command_name) + + current_position = wp.to_torch(asset.data.root_pos_w) - env.scene.env_origins + direction_to_goal = command[:, :3] - current_position + direction_to_goal = direction_to_goal / (torch.norm(direction_to_goal, dim=1, keepdim=True) + 1e-8) + # compute the reward as the dot product between the velocity and the direction to the goal + velocity_towards_goal = torch.sum(wp.to_torch(asset.data.root_lin_vel_w) * direction_to_goal, dim=1) + + # Get curriculum term and compute weight + curriculum_term = get_obstacle_curriculum_term(env) + if curriculum_term is not None: + weight = 1.0 + curriculum_term.difficulty_levels.float() / float(curriculum_term.max_difficulty) + else: + weight = 1.0 + + return weight * velocity_towards_goal + + def lin_vel_xyz_exp( env: ManagerBasedRLEnv, asset_cfg: SceneEntityCfg = SceneEntityCfg("robot"), std: float = 1.0 ) -> torch.Tensor: diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/drone_arl/navigation/__init__.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/drone_arl/navigation/__init__.py new file mode 100644 index 000000000000..a2a3a87e6232 --- /dev/null +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/drone_arl/navigation/__init__.py @@ -0,0 +1,6 @@ +# Copyright (c) 2022-2026, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md). +# All rights reserved. +# +# SPDX-License-Identifier: BSD-3-Clause + +"""Drone NTNU navigation environments.""" diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/drone_arl/navigation/config/__init__.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/drone_arl/navigation/config/__init__.py new file mode 100644 index 000000000000..61d66a54093c --- /dev/null +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/drone_arl/navigation/config/__init__.py @@ -0,0 +1,6 @@ +# Copyright (c) 2022-2026, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md). +# All rights reserved. +# +# SPDX-License-Identifier: BSD-3-Clause + +"""Configurations for drone NTNU navigation environments.""" diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/drone_arl/navigation/config/arl_robot_1/__init__.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/drone_arl/navigation/config/arl_robot_1/__init__.py new file mode 100644 index 000000000000..7e7984260403 --- /dev/null +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/drone_arl/navigation/config/arl_robot_1/__init__.py @@ -0,0 +1,36 @@ +# Copyright (c) 2022-2026, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md). +# All rights reserved. +# +# SPDX-License-Identifier: BSD-3-Clause + +import gymnasium as gym + +from . import agents + +## +# Register Gym environments. +## + +gym.register( + id="Isaac-Navigation-3DObstacles-ARL-Robot-1-v0", + entry_point="isaaclab.envs:ManagerBasedRLEnv", + disable_env_checker=True, + kwargs={ + "env_cfg_entry_point": f"{__name__}.floating_obstacles_env_cfg:FloatingObstacleEnvCfg", + "rl_games_cfg_entry_point": f"{agents.__name__}:rl_games_rough_ppo_cfg.yaml", + "rsl_rl_cfg_entry_point": f"{agents.__name__}.rsl_rl_ppo_cfg:NavigationEnvPPORunnerCfg", + "skrl_cfg_entry_point": f"{agents.__name__}:skrl_rough_ppo_cfg.yaml", + }, +) + +gym.register( + id="Isaac-Navigation-3DObstacles-ARL-Robot-1-Play-v0", + entry_point="isaaclab.envs:ManagerBasedRLEnv", + disable_env_checker=True, + kwargs={ + "env_cfg_entry_point": f"{__name__}.floating_obstacles_env_cfg:FloatingObstacleEnvCfg_PLAY", + "rl_games_cfg_entry_point": f"{agents.__name__}:rl_games_rough_ppo_cfg.yaml", + "rsl_rl_cfg_entry_point": f"{agents.__name__}.rsl_rl_ppo_cfg:NavigationEnvPPORunnerCfg", + "skrl_cfg_entry_point": f"{agents.__name__}:skrl_rough_ppo_cfg.yaml", + }, +) diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/drone_arl/navigation/config/arl_robot_1/agents/__init__.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/drone_arl/navigation/config/arl_robot_1/agents/__init__.py new file mode 100644 index 000000000000..460a30569089 --- /dev/null +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/drone_arl/navigation/config/arl_robot_1/agents/__init__.py @@ -0,0 +1,4 @@ +# Copyright (c) 2022-2026, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md). +# All rights reserved. +# +# SPDX-License-Identifier: BSD-3-Clause diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/drone_arl/navigation/config/arl_robot_1/agents/rl_games_rough_ppo_cfg.yaml b/source/isaaclab_tasks/isaaclab_tasks/manager_based/drone_arl/navigation/config/arl_robot_1/agents/rl_games_rough_ppo_cfg.yaml new file mode 100644 index 000000000000..078d89875f77 --- /dev/null +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/drone_arl/navigation/config/arl_robot_1/agents/rl_games_rough_ppo_cfg.yaml @@ -0,0 +1,87 @@ +# Copyright (c) 2022-2026, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md). +# All rights reserved. +# +# SPDX-License-Identifier: BSD-3-Clause + +params: + seed: 42 + + # environment wrapper clipping + env: + clip_actions: 1.0 + algo: + name: a2c_continuous + + model: + name: continuous_a2c_logstd + + network: + name: actor_critic + separate: False + space: + continuous: + mu_activation: None + sigma_activation: None + mu_init: + name: default + sigma_init: + name: const_initializer + val: 0 + fixed_sigma: True + mlp: + units: [256,128,64] + d2rl: False + activation: elu + initializer: + name: default + scale: 2 + rnn: + name: gru + units: 64 + layers: 1 + # before_mlp: False + # layer_norm: True + config: + name: arl_robot_1_navigation + env_name: rlgpu + device: 'cuda:0' + device_name: 'cuda:0' + env_config: + num_envs: 8192 + + reward_shaper: + # min_val: -1 + scale_value: 0.1 + + normalize_advantage: True + gamma: 0.98 + tau: 0.95 + ppo: True + learning_rate: 1e-4 + lr_schedule: adaptive + kl_threshold: 0.016 + save_best_after: 10 + score_to_win: 100000 + grad_norm: 1.0 + entropy_coef: 0 + truncate_grads: True + e_clip: 0.2 + clip_value: False + num_actors: 1024 + horizon_length: 32 + minibatch_size: 2048 + mini_epochs: 4 + critic_coef: 2 + normalize_input: True + bounds_loss_coef: 0.0001 + max_epochs: 1500 + normalize_value: True + use_diagnostics: True + value_bootstrap: True + #weight_decay: 0.0001 + use_smooth_clamp: False + + player: + render: True + deterministic: True + games_num: 100000 diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/drone_arl/navigation/config/arl_robot_1/agents/rsl_rl_ppo_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/drone_arl/navigation/config/arl_robot_1/agents/rsl_rl_ppo_cfg.py new file mode 100644 index 000000000000..aeddab56e5f8 --- /dev/null +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/drone_arl/navigation/config/arl_robot_1/agents/rsl_rl_ppo_cfg.py @@ -0,0 +1,37 @@ +# Copyright (c) 2022-2026, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md). +# All rights reserved. +# +# SPDX-License-Identifier: BSD-3-Clause + +from isaaclab.utils import configclass + +from isaaclab_rl.rsl_rl import RslRlOnPolicyRunnerCfg, RslRlPpoActorCriticCfg, RslRlPpoAlgorithmCfg + + +@configclass +class NavigationEnvPPORunnerCfg(RslRlOnPolicyRunnerCfg): + num_steps_per_env = 24 + max_iterations = 1500 + save_interval = 50 + experiment_name = "arl_robot_1_navigation" + empirical_normalization = False + policy = RslRlPpoActorCriticCfg( + init_noise_std=0.5, + actor_hidden_dims=[256, 128, 64], + critic_hidden_dims=[256, 128, 64], + activation="elu", + ) + algorithm = RslRlPpoAlgorithmCfg( + value_loss_coef=1.0, + use_clipped_value_loss=True, + clip_param=0.2, + entropy_coef=0.001, + num_learning_epochs=4, + num_mini_batches=4, + learning_rate=4.0e-4, + schedule="adaptive", + gamma=0.98, + lam=0.95, + desired_kl=0.01, + max_grad_norm=1.0, + ) diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/drone_arl/navigation/config/arl_robot_1/agents/skrl_rough_ppo_cfg.yaml b/source/isaaclab_tasks/isaaclab_tasks/manager_based/drone_arl/navigation/config/arl_robot_1/agents/skrl_rough_ppo_cfg.yaml new file mode 100644 index 000000000000..c1465d64bef5 --- /dev/null +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/drone_arl/navigation/config/arl_robot_1/agents/skrl_rough_ppo_cfg.yaml @@ -0,0 +1,95 @@ +# Copyright (c) 2022-2026, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md). +# All rights reserved. +# +# SPDX-License-Identifier: BSD-3-Clause + +seed: 42 + + +# Models are instantiated using skrl's model instantiator utility +# https://skrl.readthedocs.io/en/latest/api/utils/model_instantiators.html +models: + separate: False + policy: + class: GaussianMixin + clip_actions: False + clip_log_std: True + min_log_std: -20.0 + max_log_std: 2.0 + initial_log_std: 0.0 + network: + - name: mlp + input: STATES + layers: [256, 128, 64] + activations: elu + - name: gru + input: mlp + type: GRU + layers: [64] + num_layers: 1 + output: ACTIONS + value: + class: DeterministicMixin + clip_actions: False + network: + - name: mlp + input: STATES + layers: [256, 128, 64] + activations: elu + - name: gru + input: mlp + type: GRU + layers: [64] + num_layers: 1 + output: ONE + + +# Rollout memory +# https://skrl.readthedocs.io/en/latest/api/memories/random.html +memory: + class: RandomMemory + memory_size: -1 # automatically determined (same as agent:rollouts) + + +# PPO agent configuration (field names are from PPO_DEFAULT_CONFIG) +# https://skrl.readthedocs.io/en/latest/api/agents/ppo.html +agent: + class: PPO + rollouts: 24 + learning_epochs: 5 + mini_batches: 4 + discount_factor: 0.99 + lambda: 0.95 + learning_rate: 1.0e-03 + learning_rate_scheduler: KLAdaptiveLR + learning_rate_scheduler_kwargs: + kl_threshold: 0.01 + state_preprocessor: null + state_preprocessor_kwargs: null + value_preprocessor: RunningStandardScaler + value_preprocessor_kwargs: null + random_timesteps: 0 + learning_starts: 0 + grad_norm_clip: 1.0 + ratio_clip: 0.2 + value_clip: 0.2 + clip_predicted_values: True + entropy_loss_scale: 0.005 + value_loss_scale: 1.0 + kl_threshold: 0.0 + rewards_shaper_scale: 0.6 + time_limit_bootstrap: False + # logging and checkpoint + experiment: + directory: "arl_robot_1_navigation" + experiment_name: "" + write_interval: auto + checkpoint_interval: auto + + +# Sequential trainer +# https://skrl.readthedocs.io/en/latest/api/trainers/sequential.html +trainer: + class: SequentialTrainer + timesteps: 36000 + environment_info: log diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/drone_arl/navigation/config/arl_robot_1/floating_obstacles_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/drone_arl/navigation/config/arl_robot_1/floating_obstacles_env_cfg.py new file mode 100644 index 000000000000..1990750eefc0 --- /dev/null +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/drone_arl/navigation/config/arl_robot_1/floating_obstacles_env_cfg.py @@ -0,0 +1,41 @@ +# Copyright (c) 2022-2026, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md). +# All rights reserved. +# +# SPDX-License-Identifier: BSD-3-Clause + +## +# Pre-defined configs +## +from isaaclab.utils import configclass + +from isaaclab_tasks.manager_based.drone_arl.navigation.config.arl_robot_1.navigation_env_cfg import ( + NavigationVelocityFloatingObstacleEnvCfg, +) + +from isaaclab_assets.robots.arl_robot_1 import ARL_ROBOT_1_CFG + + +@configclass +class FloatingObstacleEnvCfg(NavigationVelocityFloatingObstacleEnvCfg): + def __post_init__(self): + # post init of parent + super().__post_init__() + # switch robot to arl_robot_1 + self.scene.robot = ARL_ROBOT_1_CFG.replace(prim_path="{ENV_REGEX_NS}/Robot") + self.scene.robot.actuators["thrusters"].dt = self.sim.dt + + +@configclass +class FloatingObstacleEnvCfg_PLAY(FloatingObstacleEnvCfg): + def __post_init__(self): + # post init of parent + super().__post_init__() + + self.curriculum.obstacle_levels.params["max_difficulty"] = 40 + self.curriculum.obstacle_levels.params["min_difficulty"] = 39 + + # disable randomization for play + self.observations.policy.enable_corruption = False + # remove random pushing event + self.events.base_external_force_torque = None + self.events.push_robot = None diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/drone_arl/navigation/config/arl_robot_1/navigation_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/drone_arl/navigation/config/arl_robot_1/navigation_env_cfg.py new file mode 100644 index 000000000000..6b4039e254a0 --- /dev/null +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/drone_arl/navigation/config/arl_robot_1/navigation_env_cfg.py @@ -0,0 +1,344 @@ +# Copyright (c) 2022-2026, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md). +# All rights reserved. +# +# SPDX-License-Identifier: BSD-3-Clause + +import logging +import math +from dataclasses import MISSING + +from isaaclab_physx.physics import PhysxCfg + +import isaaclab.sim as sim_utils +from isaaclab.assets import AssetBaseCfg +from isaaclab.envs import ManagerBasedRLEnvCfg +from isaaclab.managers import CurriculumTermCfg as CurrTerm +from isaaclab.managers import EventTermCfg as EventTerm +from isaaclab.managers import ObservationGroupCfg as ObsGroup +from isaaclab.managers import ObservationTermCfg as ObsTerm +from isaaclab.managers import RewardTermCfg as RewTerm +from isaaclab.managers import SceneEntityCfg +from isaaclab.managers import TerminationTermCfg as DoneTerm +from isaaclab.scene import InteractiveSceneCfg +from isaaclab.sensors import ContactSensorCfg +from isaaclab.sensors.ray_caster.multi_mesh_ray_caster_camera_cfg import MultiMeshRayCasterCameraCfg +from isaaclab.sensors.ray_caster.patterns import PinholeCameraPatternCfg +from isaaclab.utils import configclass +from isaaclab.utils.assets import ISAAC_NUCLEUS_DIR +from isaaclab.utils.noise import UniformNoiseCfg as Unoise + +from isaaclab_contrib.assets import MultirotorCfg +from isaaclab_contrib.controllers import LeeVelControllerCfg + +import isaaclab_tasks.manager_based.drone_arl.mdp as mdp +from isaaclab_tasks.manager_based.drone_arl.mdp.commands import DroneUniformPoseCommandCfg +from isaaclab_tasks.manager_based.drone_arl.mdp.curriculums import ObstacleDensityCurriculum +from isaaclab_tasks.manager_based.drone_arl.mdp.events import reset_obstacles_with_individual_ranges +from isaaclab_tasks.manager_based.drone_arl.mdp.observations import ( + ImageLatentObservation, + base_roll_pitch, + generated_drone_commands, + last_action_navigation, +) +from isaaclab_tasks.manager_based.drone_arl.mdp.rewards import ( + distance_to_goal_exp_curriculum, + velocity_to_goal_reward_curriculum, +) + +logging.getLogger("isaaclab.sensors.ray_caster.multi_mesh_ray_caster").setLevel(logging.WARNING) + +## +# Pre-defined configs +## +from .scenes.obstacle_scenes.obstacle_scene import ( + OBSTACLE_SCENE_CFG, + generate_obstacle_collection, +) + + +## +# Scene definition +## +@configclass +class ArlNavigationSceneCfg(InteractiveSceneCfg): + """Scene configuration for drone navigation with obstacles.""" + + # obstacles + object_collection = generate_obstacle_collection(OBSTACLE_SCENE_CFG) + + # robots + robot: MultirotorCfg = MISSING + + # sensors + depth_camera = MultiMeshRayCasterCameraCfg( + prim_path="{ENV_REGEX_NS}/Robot/base_link", + mesh_prim_paths=[ + MultiMeshRayCasterCameraCfg.RaycastTargetCfg( + prim_expr=f"{{ENV_REGEX_NS}}/obstacle_{wall_name}", is_shared=False, track_mesh_transforms=True + ) + for wall_name, _ in OBSTACLE_SCENE_CFG.wall_cfgs.items() + ] + + [ + MultiMeshRayCasterCameraCfg.RaycastTargetCfg( + prim_expr=f"{{ENV_REGEX_NS}}/obstacle_{i}", is_shared=False, track_mesh_transforms=True + ) + for i in range(OBSTACLE_SCENE_CFG.max_num_obstacles) + ], + offset=MultiMeshRayCasterCameraCfg.OffsetCfg( + pos=(0.15, 0.0, 0.04), rot=(1.0, 0.0, 0.0, 0.0), convention="world" + ), + update_period=0.1, + pattern_cfg=PinholeCameraPatternCfg( + width=480, height=270, focal_length=0.193, horizontal_aperture=0.36, vertical_aperture=0.21 + ), + data_types=["distance_to_image_plane"], + max_distance=10.0, + depth_clipping_behavior="max", + ) + + contact_forces = ContactSensorCfg( + prim_path="{ENV_REGEX_NS}/Robot/.*", + update_period=0.0, + history_length=10, + debug_vis=False, + ) + # lights + sky_light = AssetBaseCfg( + prim_path="/World/skyLight", + spawn=sim_utils.DomeLightCfg( + intensity=750.0, + texture_file=f"{ISAAC_NUCLEUS_DIR}/Materials/Textures/Skies/PolyHaven/kloofendal_43d_clear_puresky_4k.hdr", + ), + ) + + +## +# MDP settings +## + + +@configclass +class CommandsCfg: + """Command specifications for the MDP.""" + + target_pose = DroneUniformPoseCommandCfg( + asset_name="robot", + body_name="base_link", + resampling_time_range=(10.0, 10.0), + debug_vis=True, + ranges=DroneUniformPoseCommandCfg.Ranges( + pos_x=(4.0, 5.0), + pos_y=(-3.0, 3.0), + pos_z=(1.0, 5.0), + roll=(-0.0, 0.0), + pitch=(-0.0, 0.0), + yaw=(-0.0, 0.0), + ), + ) + + +@configclass +class ActionsCfg: + """Action specifications for the MDP.""" + + velocity_commands = mdp.NavigationActionCfg( + asset_name="robot", + scale=1.0, + offset=0.0, + preserve_order=False, + use_default_offset=False, + controller_cfg=LeeVelControllerCfg( + K_vel_range=((2.5, 2.5, 1.5), (3.5, 3.5, 2.0)), + K_rot_range=((1.6, 1.6, 0.25), (1.85, 1.85, 0.4)), + K_angvel_range=((0.4, 0.4, 0.075), (0.5, 0.5, 0.09)), + max_inclination_angle_rad=1.0471975511965976, + max_yaw_rate=1.0471975511965976, + ), + max_magnitude=2.0, + max_yaw_command=3.14 / 3.0, + max_inclination_angle=3.14 / 4.0, + ) + + +@configclass +class ObservationsCfg: + """Observation specifications for the MDP.""" + + @configclass + class PolicyCfg(ObsGroup): + """Observations for policy group.""" + + # observation terms (order preserved) + base_link_position = ObsTerm( + func=generated_drone_commands, + params={"command_name": "target_pose", "asset_cfg": SceneEntityCfg("robot")}, + noise=Unoise(n_min=-0.1, n_max=0.1), + ) + base_roll_pitch = ObsTerm(func=base_roll_pitch, noise=Unoise(n_min=-0.1, n_max=0.1)) + base_lin_vel = ObsTerm(func=mdp.base_lin_vel, noise=Unoise(n_min=-0.1, n_max=0.1)) + base_ang_vel = ObsTerm(func=mdp.base_ang_vel, noise=Unoise(n_min=-0.1, n_max=0.1)) + last_action = ObsTerm( + func=last_action_navigation, + params={"action_name": "velocity_commands"}, + ) + depth_latent = ObsTerm( + func=ImageLatentObservation, + params={"sensor_cfg": SceneEntityCfg("depth_camera"), "data_type": "distance_to_image_plane"}, + ) + + def __post_init__(self): + self.enable_corruption = False + self.concatenate_terms = True + + # observation groups + policy: PolicyCfg = PolicyCfg() + + +@configclass +class EventCfg: + """Configuration for events.""" + + # reset + + reset_base = EventTerm( + func=mdp.reset_root_state_uniform, + mode="reset", + params={ + "pose_range": { + "x": (-5.0, -4.5), + "y": (-3.0, 3.0), + "z": (1.0, 5.0), + "yaw": (-math.pi / 6.0, math.pi / 6.0), + }, + "velocity_range": { + "x": (-0.2, 0.2), + "y": (-0.2, 0.2), + "z": (-0.2, 0.2), + "roll": (-0.2, 0.2), + "pitch": (-0.2, 0.2), + "yaw": (-0.2, 0.2), + }, + }, + ) + + reset_obstacles = EventTerm( + func=reset_obstacles_with_individual_ranges, + mode="reset", + params={ + "asset_cfg": SceneEntityCfg("object_collection"), + "obstacle_configs": OBSTACLE_SCENE_CFG.obstacle_cfgs, + "wall_configs": OBSTACLE_SCENE_CFG.wall_cfgs, + "env_size": OBSTACLE_SCENE_CFG.env_size, + "use_curriculum": True, + "min_num_obstacles": OBSTACLE_SCENE_CFG.min_num_obstacles, + "max_num_obstacles": OBSTACLE_SCENE_CFG.max_num_obstacles, + "ground_offset": OBSTACLE_SCENE_CFG.ground_offset, + }, + ) + + +@configclass +class RewardsCfg: + """Reward terms for the MDP.""" + + goal_dist_exp1 = RewTerm( + func=distance_to_goal_exp_curriculum, + weight=2.0, + params={ + "asset_cfg": SceneEntityCfg("robot"), + "std": 7.0, + "command_name": "target_pose", + }, + ) + goal_dist_exp2 = RewTerm( + func=distance_to_goal_exp_curriculum, + weight=4.0, + params={ + "asset_cfg": SceneEntityCfg("robot"), + "std": 0.5, + "command_name": "target_pose", + }, + ) + velocity_reward = RewTerm( + func=velocity_to_goal_reward_curriculum, + weight=0.5, + params={ + "asset_cfg": SceneEntityCfg("robot"), + "command_name": "target_pose", + }, + ) + action_rate_l2 = RewTerm(func=mdp.action_rate_l2, weight=-0.05) + action_magnitude_l2 = RewTerm(func=mdp.action_l2, weight=-0.05) + + termination_penalty = RewTerm( + func=mdp.is_terminated, + weight=-100.0, + ) + + +@configclass +class TerminationsCfg: + """Termination terms for the MDP.""" + + time_out = DoneTerm(func=mdp.time_out, time_out=True) + collision = DoneTerm( + func=mdp.illegal_contact, + params={"sensor_cfg": SceneEntityCfg("contact_forces", body_names=".*"), "threshold": 1.0}, + time_out=False, + ) + + +@configclass +class CurriculumCfg: + """Curriculum terms for the MDP.""" + + obstacle_levels = CurrTerm( + func=ObstacleDensityCurriculum, + params={ + "asset_cfg": SceneEntityCfg("robot"), + "max_difficulty": 10, + "min_difficulty": 0, + }, + ) + + +## +# Environment configuration +## + + +@configclass +class NavigationVelocityFloatingObstacleEnvCfg(ManagerBasedRLEnvCfg): + """Configuration for the locomotion velocity-tracking environment.""" + + # Scene settings + scene: ArlNavigationSceneCfg = ArlNavigationSceneCfg(num_envs=4096, env_spacing=20.5) + # Basic settings + observations: ObservationsCfg = ObservationsCfg() + actions: ActionsCfg = ActionsCfg() + commands: CommandsCfg = CommandsCfg() + # MDP settings + rewards: RewardsCfg = RewardsCfg() + terminations: TerminationsCfg = TerminationsCfg() + events: EventCfg = EventCfg() + curriculum: CurriculumCfg = CurriculumCfg() + + def __post_init__(self): + """Post initialization.""" + # general settings + self.decimation = 10 + self.episode_length_s = 10.0 + # simulation settings + self.sim.dt = 0.01 + self.sim.render_interval = self.decimation + self.sim.physics_material = sim_utils.RigidBodyMaterialCfg( + friction_combine_mode="multiply", + restitution_combine_mode="multiply", + static_friction=1.0, + dynamic_friction=1.0, + ) + self.sim.physics = PhysxCfg(gpu_max_rigid_patch_count=2**21) + # update sensor update periods + # we tick all the sensors based on the smallest update period (physics update period) + if self.scene.contact_forces is not None: + self.scene.contact_forces.update_period = self.sim.dt diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/drone_arl/navigation/config/arl_robot_1/scenes/obstacle_scenes/obstacle_scene.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/drone_arl/navigation/config/arl_robot_1/scenes/obstacle_scenes/obstacle_scene.py new file mode 100644 index 000000000000..711a9e990742 --- /dev/null +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/drone_arl/navigation/config/arl_robot_1/scenes/obstacle_scenes/obstacle_scene.py @@ -0,0 +1,114 @@ +# Copyright (c) 2022-2026, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md). +# All rights reserved. +# +# SPDX-License-Identifier: BSD-3-Clause + +import numpy as np + +import isaaclab.sim as sim_utils +from isaaclab.assets import RigidObjectCfg, RigidObjectCollectionCfg + +from .obstacle_scene_cfg import ObstaclesSceneCfg + +"""Obstacle scene generation and reset functionality for drone navigation environments. + +This module provides utilities for generating dynamic 3D obstacle courses with walls and +floating obstacles. The obstacle configurations support curriculum learning where difficulty +can be progressively increased by adjusting the number of active obstacles. +""" + +OBSTACLE_SCENE_CFG = ObstaclesSceneCfg( + env_size=(12.0, 8.0, 6.0), + min_num_obstacles=20, + max_num_obstacles=40, + ground_offset=3.0, +) + + +def generate_obstacle_collection(cfg: ObstaclesSceneCfg) -> RigidObjectCollectionCfg: + """Generate a rigid object collection configuration for walls and obstacles. + + Creates a complete scene with boundary walls and a variety of floating obstacles + (panels, cubes, rods, etc.) based on the provided configuration. Each obstacle is + assigned random colors and configured with appropriate physics properties. + + Wall objects are configured with very high mass (10^7 kg) and high damping to remain + stationary during collisions. Obstacle objects have moderate mass (100 kg) to move in the right position if reset + in collision. + + Args: + cfg: Configuration object specifying obstacle types, sizes, quantities, and + positioning constraints. + + Returns: + A RigidObjectCollectionCfg containing all wall and obstacle configurations, + ready to be added to a scene. + + Note: + All obstacles are initially placed at origin [0, 0, 0]. Actual positions are + set during environment reset via :func:`reset_obstacles_with_individual_ranges`. + """ + max_num_obstacles = cfg.max_num_obstacles + + rigid_objects = {} + + for wall_name, wall_cfg in cfg.wall_cfgs.items(): + # Walls get their specific size and default center + default_center = [0.0, 0.0, 0.0] # Will be set properly at reset + color = float(np.random.randint(0, 256, size=1, dtype=np.uint8)) / 255.0 + + rigid_objects[wall_name] = RigidObjectCfg( + prim_path=f"{{ENV_REGEX_NS}}/obstacle_{wall_name}", + spawn=sim_utils.CuboidCfg( + size=wall_cfg.size, + visual_material=sim_utils.PreviewSurfaceCfg(diffuse_color=(0.5, 0.5, color), metallic=0.2), + rigid_props=sim_utils.RigidBodyPropertiesCfg( + solver_position_iteration_count=4, + solver_velocity_iteration_count=0, + disable_gravity=True, + kinematic_enabled=False, + linear_damping=9999.0, + angular_damping=9999.0, + max_linear_velocity=0.0, + max_angular_velocity=0.0, + ), + # mass of walls needs to be way larger than weight of obstacles to make them not move during reset + mass_props=sim_utils.MassPropertiesCfg(mass=10000000.0), + collision_props=sim_utils.CollisionPropertiesCfg(), + ), + init_state=RigidObjectCfg.InitialStateCfg(pos=tuple(default_center)), + collision_group=0, + ) + + obstacle_types = list(cfg.obstacle_cfgs.values()) + for i in range(max_num_obstacles): + obj_name = f"obstacle_{i}" + obs_cfg = obstacle_types[i % len(obstacle_types)] + + default_center = [0.0, 0.0, 0.0] + color = np.random.randint(0, 256, size=3, dtype=np.uint8) + color_normalized = tuple(float(c) / 255.0 for c in color) + + rigid_objects[obj_name] = RigidObjectCfg( + prim_path=f"{{ENV_REGEX_NS}}/{obj_name}", + spawn=sim_utils.CuboidCfg( + size=obs_cfg.size, + visual_material=sim_utils.PreviewSurfaceCfg(diffuse_color=color_normalized, metallic=0.2), + rigid_props=sim_utils.RigidBodyPropertiesCfg( + solver_position_iteration_count=4, + solver_velocity_iteration_count=0, + disable_gravity=True, + kinematic_enabled=False, + linear_damping=1.0, + angular_damping=1.0, + max_linear_velocity=0.0, + max_angular_velocity=0.0, + ), + mass_props=sim_utils.MassPropertiesCfg(mass=100.0), + collision_props=sim_utils.CollisionPropertiesCfg(), + ), + init_state=RigidObjectCfg.InitialStateCfg(pos=tuple(default_center)), + collision_group=0, + ) + + return RigidObjectCollectionCfg(rigid_objects=rigid_objects) diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/drone_arl/navigation/config/arl_robot_1/scenes/obstacle_scenes/obstacle_scene_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/drone_arl/navigation/config/arl_robot_1/scenes/obstacle_scenes/obstacle_scene_cfg.py new file mode 100644 index 000000000000..c42610dc10b7 --- /dev/null +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/drone_arl/navigation/config/arl_robot_1/scenes/obstacle_scenes/obstacle_scene_cfg.py @@ -0,0 +1,88 @@ +# Copyright (c) 2022-2026, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md). +# All rights reserved. +# +# SPDX-License-Identifier: BSD-3-Clause + +from dataclasses import MISSING + +from isaaclab.utils import configclass + + +@configclass +class ObstaclesSceneCfg: + """Configuration for a terrain with floating obstacles.""" + + min_num_obstacles: int = 1 + max_num_obstacles: int = 40 + ground_offset: float = 3.0 + + env_size: tuple[float, float, float] = MISSING + + @configclass + class BoxCfg: + """Configuration for a box-shaped obstacle or wall. + + Defines the size and placement constraints for rectangular obstacles within + the environment. The center position is specified as ratios of the environment + size, allowing for flexible scaling. + + Attributes: + size: Tuple of (length, width, height) in meters. + center_ratio_min: Minimum position as ratio of env_size (0.0 to 1.0) for + each axis. Used for random placement bounds. + center_ratio_max: Maximum position as ratio of env_size (0.0 to 1.0) for + each axis. For fixed positions, set equal to center_ratio_min. + """ + + size: tuple[float, float, float] = MISSING + center_ratio_min: tuple[float, float, float] = MISSING + center_ratio_max: tuple[float, float, float] = MISSING + + # Obstacle configurations + panel_obs_cfg = BoxCfg( + size=(0.1, 1.2, 3.0), center_ratio_min=(0.3, 0.05, 0.05), center_ratio_max=(0.85, 0.95, 0.95) + ) + + small_wall_obs_cfg = BoxCfg( + size=(0.1, 0.5, 0.5), center_ratio_min=(0.3, 0.05, 0.05), center_ratio_max=(0.85, 0.9, 0.9) + ) + + big_wall_obs_cfg = BoxCfg( + size=(0.1, 1.0, 1.0), center_ratio_min=(0.3, 0.05, 0.05), center_ratio_max=(0.85, 0.9, 0.9) + ) + + small_cube_obs_cfg = BoxCfg( + size=(0.4, 0.4, 0.4), center_ratio_min=(0.3, 0.05, 0.05), center_ratio_max=(0.85, 0.9, 0.9) + ) + + rod_obs_cfg = BoxCfg(size=(0.1, 0.1, 2.0), center_ratio_min=(0.3, 0.05, 0.05), center_ratio_max=(0.85, 0.9, 0.9)) + + # Wall configurations + left_wall_cfg = BoxCfg(size=(12.0, 0.2, 6.0), center_ratio_min=(0.5, 1.0, 0.5), center_ratio_max=(0.5, 1.0, 0.5)) + + right_wall_cfg = BoxCfg(size=(12.0, 0.2, 6.0), center_ratio_min=(0.5, 0.0, 0.5), center_ratio_max=(0.5, 0.0, 0.5)) + + back_wall_cfg = BoxCfg(size=(0.2, 8.0, 6.0), center_ratio_min=(0.0, 0.5, 0.5), center_ratio_max=(0.0, 0.5, 0.5)) + + front_wall_cfg = BoxCfg(size=(0.2, 8.0, 6.0), center_ratio_min=(1.0, 0.5, 0.5), center_ratio_max=(1.0, 0.5, 0.5)) + + top_wall_cfg = BoxCfg(size=(12.0, 8.0, 0.2), center_ratio_min=(0.5, 0.5, 1.0), center_ratio_max=(0.5, 0.5, 1.0)) + + bottom_wall_cfg = BoxCfg(size=(12.0, 8.0, 0.2), center_ratio_min=(0.5, 0.5, 0.0), center_ratio_max=(0.5, 0.5, 0.0)) + + wall_cfgs = { + "left_wall": left_wall_cfg, + "right_wall": right_wall_cfg, + "back_wall": back_wall_cfg, + "front_wall": front_wall_cfg, + "bottom_wall": bottom_wall_cfg, + "top_wall": top_wall_cfg, + } + + obstacle_cfgs = { + "panel": panel_obs_cfg, + "small_wall": small_wall_obs_cfg, + "big_wall": big_wall_obs_cfg, + "small_cube": small_cube_obs_cfg, + "rod": rod_obs_cfg, + } diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/drone_arl/track_position_state_based/config/arl_robot_1/track_position_state_based_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/drone_arl/track_position_state_based/config/arl_robot_1/track_position_state_based_env_cfg.py index a78e4a151162..de61f13b8a9a 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/drone_arl/track_position_state_based/config/arl_robot_1/track_position_state_based_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/drone_arl/track_position_state_based/config/arl_robot_1/track_position_state_based_env_cfg.py @@ -25,13 +25,20 @@ from isaaclab_contrib.assets import MultirotorCfg import isaaclab_tasks.manager_based.drone_arl.mdp as mdp +from isaaclab_tasks.manager_based.drone_arl.mdp.commands import DroneUniformPoseCommandCfg +from isaaclab_tasks.manager_based.drone_arl.mdp.rewards import ( + ang_vel_xyz_exp, + distance_to_goal_exp, + lin_vel_xyz_exp, + yaw_aligned, +) ## # Scene definition ## @configclass -class MySceneCfg(InteractiveSceneCfg): +class ArlTrackPositionStateBasedSceneCfg(InteractiveSceneCfg): """Configuration for the terrain scene with a flying robot.""" # robots @@ -56,12 +63,12 @@ class MySceneCfg(InteractiveSceneCfg): class CommandsCfg: """Command specifications for the MDP.""" - target_pose = mdp.DroneUniformPoseCommandCfg( + target_pose = DroneUniformPoseCommandCfg( asset_name="robot", body_name="base_link", resampling_time_range=(10.0, 10.0), debug_vis=True, - ranges=mdp.DroneUniformPoseCommandCfg.Ranges( + ranges=DroneUniformPoseCommandCfg.Ranges( pos_x=(-0.0, 0.0), pos_y=(-0.0, 0.0), pos_z=(-0.0, 0.0), @@ -149,7 +156,7 @@ class RewardsCfg: """Reward terms for the MDP.""" distance_to_goal_exp = RewTerm( - func=mdp.distance_to_goal_exp, + func=distance_to_goal_exp, weight=25.0, params={ "asset_cfg": SceneEntityCfg("robot"), @@ -163,17 +170,17 @@ class RewardsCfg: params={"asset_cfg": SceneEntityCfg("robot")}, ) yaw_aligned = RewTerm( - func=mdp.yaw_aligned, + func=yaw_aligned, weight=2.0, params={"asset_cfg": SceneEntityCfg("robot"), "std": 1.0}, ) lin_vel_xyz_exp = RewTerm( - func=mdp.lin_vel_xyz_exp, + func=lin_vel_xyz_exp, weight=2.5, params={"asset_cfg": SceneEntityCfg("robot"), "std": 2.0}, ) ang_vel_xyz_exp = RewTerm( - func=mdp.ang_vel_xyz_exp, + func=ang_vel_xyz_exp, weight=10.0, params={"asset_cfg": SceneEntityCfg("robot"), "std": 10.0}, ) @@ -204,7 +211,7 @@ class TrackPositionNoObstaclesEnvCfg(ManagerBasedRLEnvCfg): """Configuration for the state-based drone pose-control environment.""" # Scene settings - scene: MySceneCfg = MySceneCfg(num_envs=4096, env_spacing=2.5) + scene: ArlTrackPositionStateBasedSceneCfg = ArlTrackPositionStateBasedSceneCfg(num_envs=4096, env_spacing=2.5) # Basic settings observations: ObservationsCfg = ObservationsCfg() actions: ActionsCfg = ActionsCfg() From 8d9af88f0041ad53a5188e9036ee7d15795ae62c Mon Sep 17 00:00:00 2001 From: myurasov-nv <168484206+myurasov-nv@users.noreply.github.com> Date: Fri, 8 May 2026 12:21:07 -0700 Subject: [PATCH 26/51] Fixes various installation bugs (#5530) # Description Fixed bugs: - [NVBug 6122918] - Grammar in installation docs (``these dependency`` -> ``these dependencies``; drop redundant ``guides`` after ``:ref:`how-to```). - [NVBug 6125106] - Add an ``Environment setup`` section to the kit-less install page so it does not jump from ``git clone`` straight to ``./isaaclab.sh --install``. - [NVBug 6125054] - Relax ``starlette==0.49.1`` -> ``>=0.46.0,<0.50`` so ``isaaclab[isaacsim,all]==3.0.0`` resolves alongside ``isaacsim==6.0.0.0`` (transitively requires ``starlette<0.49.0``). - [NVBug 6122885] - Bump recommended driver versions on the installation index to the Beta2 POR (Linux ``580.95.05``, Spark ``580.142``, Windows ``581.42.00``). ## Type of change - Bug fix (non-breaking change which fixes an issue) - Documentation update ## Checklist - [x] I have read and understood the [contribution guidelines](https://isaac-sim.github.io/IsaacLab/main/source/refs/contributing.html) - [x] I have run the [``pre-commit`` checks](https://pre-commit.com/) with ``./isaaclab.sh --format`` - [x] I have made corresponding changes to the documentation - [x] My changes generate no new warnings - [ ] I have added tests that prove my fix is effective or that my feature works - [x] I have added a changelog fragment under ``source//changelog.d/`` for every touched package (do **not** edit ``CHANGELOG.rst`` or bump ``extension.toml`` -- CI handles that) - [x] I have added my name to the ``CONTRIBUTORS.md`` or my name already exists there --------- Co-authored-by: Antoine RICHARD --- .../setup/installation/include/src_build_isaaclab.rst | 2 +- .../setup/installation/include/src_verify_isaaclab.rst | 2 +- docs/source/setup/installation/index.rst | 7 +++---- docs/source/setup/installation/kitless_installation.rst | 7 +++++++ source/isaaclab/changelog.d/my-nvbugs-2.rst | 8 ++++++++ source/isaaclab/setup.py | 3 ++- tools/wheel_builder/res/python_packages.toml | 3 ++- 7 files changed, 24 insertions(+), 8 deletions(-) create mode 100644 source/isaaclab/changelog.d/my-nvbugs-2.rst diff --git a/docs/source/setup/installation/include/src_build_isaaclab.rst b/docs/source/setup/installation/include/src_build_isaaclab.rst index ffec4f6cb0b7..3d93e8f3452d 100644 --- a/docs/source/setup/installation/include/src_build_isaaclab.rst +++ b/docs/source/setup/installation/include/src_build_isaaclab.rst @@ -5,7 +5,7 @@ Installation .. code:: bash - # these dependency are needed by robomimic which is not available on Windows + # these dependencies are needed by robomimic which is not available on Windows sudo apt install cmake build-essential On **aarch64** systems (e.g., DGX Spark), Python, OpenGL and X11 development packages are also required. diff --git a/docs/source/setup/installation/include/src_verify_isaaclab.rst b/docs/source/setup/installation/include/src_verify_isaaclab.rst index 38f51100ec5f..4488e30cb7ab 100644 --- a/docs/source/setup/installation/include/src_verify_isaaclab.rst +++ b/docs/source/setup/installation/include/src_verify_isaaclab.rst @@ -94,7 +94,7 @@ We recommend adding ``--headless`` for faster training. isaaclab.bat -p scripts/reinforcement_learning/rsl_rl/train.py --task=Isaac-Velocity-Rough-Anymal-C-v0 --headless Isaac Lab provides the tools you'll need to create your own **Tasks** and **Workflows** for whatever your project needs may be. -Take a look at our :ref:`how-to` guides like :ref:`Adding your own learning Library ` or :ref:`Wrapping Environments ` for details. +Take a look at our :ref:`how-to` like :ref:`Adding your own learning Library ` or :ref:`Wrapping Environments ` for details. .. figure:: /source/_static/setup/isaac_ants_example.jpg :align: center diff --git a/docs/source/setup/installation/index.rst b/docs/source/setup/installation/index.rst index 6d00776ee754..c3c450fc530b 100644 --- a/docs/source/setup/installation/index.rst +++ b/docs/source/setup/installation/index.rst @@ -84,10 +84,9 @@ Drivers other than those recommended on `Omniverse Technical Requirements `_ using the ``.run`` installer. diff --git a/docs/source/setup/installation/kitless_installation.rst b/docs/source/setup/installation/kitless_installation.rst index 4c6768b3dc0a..506a70eeb0bd 100644 --- a/docs/source/setup/installation/kitless_installation.rst +++ b/docs/source/setup/installation/kitless_installation.rst @@ -6,6 +6,13 @@ Kit-less Installation Isaac Lab can be installed and used **without Isaac Sim** using the kit-less mode. This is the fastest way to get started and is ideal for users who only need the Newton physics backend. +.. include:: include/pip_python_virtual_env.rst + +Cloning and installing Isaac Lab +-------------------------------- + +With the virtual environment activated, clone the repository and run the kit-less installer: + .. code-block:: bash # Clone Isaac Lab diff --git a/source/isaaclab/changelog.d/my-nvbugs-2.rst b/source/isaaclab/changelog.d/my-nvbugs-2.rst new file mode 100644 index 000000000000..29bc762d964d --- /dev/null +++ b/source/isaaclab/changelog.d/my-nvbugs-2.rst @@ -0,0 +1,8 @@ +Fixed +^^^^^ + +* Relaxed the ``starlette`` pin in :mod:`isaaclab` from ``==0.49.1`` to + ``>=0.46.0,<0.50`` so installs of ``isaaclab[isaacsim,all]==3.0.0`` + alongside ``isaacsim==6.0.0.0`` resolve cleanly. The transitive pin + from ``isaacsim-kernel`` -> ``fastapi==0.117.1`` requires + ``starlette<0.49.0``; the previous exact pin was mutually exclusive. diff --git a/source/isaaclab/setup.py b/source/isaaclab/setup.py index 4f54032f6d14..ac556cc7434e 100644 --- a/source/isaaclab/setup.py +++ b/source/isaaclab/setup.py @@ -42,7 +42,8 @@ # required by omni.replicator.core S3 backend "botocore", # livestream - "starlette==0.49.1", + # range chosen to coexist with isaacsim 6.0 (isaacsim-kernel pulls fastapi==0.117.1 -> starlette<0.49.0) + "starlette>=0.46.0,<0.50", "omniverseclient==2.71.1.7015", # testing "pytest", diff --git a/tools/wheel_builder/res/python_packages.toml b/tools/wheel_builder/res/python_packages.toml index 285d1cddbc66..9944580034e0 100644 --- a/tools/wheel_builder/res/python_packages.toml +++ b/tools/wheel_builder/res/python_packages.toml @@ -28,7 +28,8 @@ pyproject.dependencies.all = [ "pillow==12.1.1", "botocore", # livestream - "starlette==0.49.1", # TODO: update starlette once Isaac Lab be released with Isaac Sim 6.0.0 + # range chosen to coexist with isaacsim 6.0 (isaacsim-kernel pulls fastapi==0.117.1 -> starlette<0.49.0) + "starlette>=0.46.0,<0.50", "omniverseclient==2.71.1.7015", # testing "pytest", From 4687c34ff481481b7aa94575226ca01bdf520840 Mon Sep 17 00:00:00 2001 From: Antoine RICHARD Date: Fri, 8 May 2026 21:22:55 +0200 Subject: [PATCH 27/51] Replaces fcntl with filelock to avoid windows import issues (#5544) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit # Description The `isaaclab.sim.spawners.from_files` module imports `fcntl` unconditionally at module load. `fcntl` is Unix-only, so on Windows the import fails with: ``` ModuleNotFoundError: No module named 'fcntl' ``` This breaks **any** Windows usage of the spawner — including single-GPU runs that never take the lock path. Reproducer reported by a user (IsaacLab `develop` @ `b258e87`, IsaacSim `6.0.0rc41`): ``` python scripts/reinforcement_learning/rl_games/train.py --task=Isaac-Cartpole-v0 --headless --video --video_length 100 --video_interval 500 --max_iterations 5 ``` `fcntl` was introduced in #5032 to serialize USD download/stage composition across distributed ranks (preventing segfaults in `Sdf_CrateFile::_MmapStream::Read` on shared cached USD files). The intent is correct — only the implementation is Unix-only. ## Change - Replace `fcntl.flock` with [`filelock.FileLock`](https://pypi.org/project/filelock/), which uses `fcntl` on POSIX and `msvcrt` on Windows. - Use `contextlib.nullcontext` for the single-rank path so the lock file is only created when actually needed (i.e., `LOCAL_WORLD_SIZE > 1`). - Drop the manual `try/finally` and the `# noqa: SIM115` on the bare `open(...)` — the `with FileLock(...)` form is exception-safe. - Declare `filelock` in `source/isaaclab/setup.py::INSTALL_REQUIRES`. It was previously only transitively available via `transformers` → `huggingface_hub`; making it a direct dep so we don't depend on a transitive chain that could change. The lock semantics are unchanged: an exclusive advisory lock on `/isaaclab_usd_spawn.lock`, held only while `LOCAL_WORLD_SIZE > 1`. Original lock implementation: @ooctipus (#5032) — tagging for review since this changes the locking primitive. ## Type of change - Bug fix (non-breaking change which fixes an issue) ## Screenshots N/A — import-time failure on Windows; no UI surface. ## Checklist - [x] I have read and understood the [contribution guidelines](https://isaac-sim.github.io/IsaacLab/main/source/refs/contributing.html) - [x] I have run the [`pre-commit` checks](https://pre-commit.com/) with `./isaaclab.sh --format` - [ ] I have made corresponding changes to the documentation (N/A — internal change) - [x] My changes generate no new warnings - [ ] I have added tests that prove my fix is effective or that my feature works — the failure is `import fcntl` at module load on Windows; a regression test would require a Windows CI runner, which IsaacLab does not currently exercise. Locally verified the module imports and `FileLock` resolves to `filelock._unix.UnixFileLock` on Linux (and would resolve to `WindowsFileLock` on Windows). - [x] I have added a changelog fragment under `source//changelog.d/` for every touched package (do **not** edit `CHANGELOG.rst` or bump `extension.toml` — CI handles that) - [x] I have added my name to the `CONTRIBUTORS.md` or my name already exists there --- docs/conf.py | 1 + .../antoiner-fix-from-files-windows-filelock.rst | 12 ++++++++++++ .../sim/spawners/from_files/from_files.py | 16 +++++++--------- source/isaaclab/setup.py | 2 ++ 4 files changed, 22 insertions(+), 9 deletions(-) create mode 100644 source/isaaclab/changelog.d/antoiner-fix-from-files-windows-filelock.rst diff --git a/docs/conf.py b/docs/conf.py index 65ad5468d34e..d75475634e30 100644 --- a/docs/conf.py +++ b/docs/conf.py @@ -205,6 +205,7 @@ "pinocchio", "nvidia.srl", "flatdict", + "filelock", "IPython", "cv2", "imageio", diff --git a/source/isaaclab/changelog.d/antoiner-fix-from-files-windows-filelock.rst b/source/isaaclab/changelog.d/antoiner-fix-from-files-windows-filelock.rst new file mode 100644 index 000000000000..3ceaeab12231 --- /dev/null +++ b/source/isaaclab/changelog.d/antoiner-fix-from-files-windows-filelock.rst @@ -0,0 +1,12 @@ +Fixed +^^^^^ + +* Fixed :mod:`isaaclab.sim.spawners.from_files` failing to import on Windows + due to an unconditional ``import fcntl`` (Unix-only). The distributed-rank + USD spawn lock now uses :class:`filelock.FileLock`, which works on both + Windows and POSIX. + +Changed +^^^^^^^ + +* Added :mod:`filelock` to ``isaaclab`` install requirements. diff --git a/source/isaaclab/isaaclab/sim/spawners/from_files/from_files.py b/source/isaaclab/isaaclab/sim/spawners/from_files/from_files.py index be7bd6e7074e..892d2e78b387 100644 --- a/source/isaaclab/isaaclab/sim/spawners/from_files/from_files.py +++ b/source/isaaclab/isaaclab/sim/spawners/from_files/from_files.py @@ -5,12 +5,14 @@ from __future__ import annotations -import fcntl import logging import os import tempfile +from contextlib import nullcontext from typing import TYPE_CHECKING +from filelock import FileLock + # deformables only supported on PhysX backend from isaaclab_physx.sim import schemas as schemas_physx from isaaclab_physx.sim.spawners.materials import SurfaceDeformableBodyMaterialCfg @@ -316,10 +318,10 @@ def _spawn_from_usd_file( raise FileNotFoundError(f"USD file not found at path: '{usd_path}'.") if _world_size > 1: - lock_path = os.path.join(tempfile.gettempdir(), "isaaclab_usd_spawn.lock") - lock_fd = open(lock_path, "w") # noqa: SIM115 - fcntl.flock(lock_fd, fcntl.LOCK_EX) - try: + lock = FileLock(os.path.join(tempfile.gettempdir(), "isaaclab_usd_spawn.lock")) + else: + lock = nullcontext() + with lock: if file_status == 2: usd_path = retrieve_file_path(usd_path, force_download=False) stage = get_current_stage() @@ -334,10 +336,6 @@ def _spawn_from_usd_file( ) else: logger.warning(f"A prim already exists at prim path: '{prim_path}'.") - finally: - if _world_size > 1: - fcntl.flock(lock_fd, fcntl.LOCK_UN) - lock_fd.close() # modify variants if hasattr(cfg, "variants") and cfg.variants is not None: diff --git a/source/isaaclab/setup.py b/source/isaaclab/setup.py index ac556cc7434e..d56f73a34225 100644 --- a/source/isaaclab/setup.py +++ b/source/isaaclab/setup.py @@ -55,6 +55,8 @@ "flaky", "packaging", "psutil", + # cross-platform file locking (used to serialize USD spawn across distributed ranks) + "filelock", # Required by pydantic-core/imgui_bundle on Python 3.12 (Sentinel symbol). "typing_extensions>=4.14.0", "lazy_loader>=0.4", From 1e0e37924cc3c13b75fdc9580ae33ea85dd0383e Mon Sep 17 00:00:00 2001 From: Kelly Guo Date: Fri, 8 May 2026 21:20:08 -0700 Subject: [PATCH 28/51] Disables articulation tests in Isaac Sim CI (#5557) # Description articulation tests have been timing out in CI. disabling it to unblock isaac sim MR merging until we figure out why the timeouts are happening. ## Type of change - Bug fix (non-breaking change which fixes an issue) ## Checklist - [x] I have read and understood the [contribution guidelines](https://isaac-sim.github.io/IsaacLab/main/source/refs/contributing.html) - [x] I have run the [`pre-commit` checks](https://pre-commit.com/) with `./isaaclab.sh --format` - [x] I have made corresponding changes to the documentation - [x] My changes generate no new warnings - [ ] I have added tests that prove my fix is effective or that my feature works - [ ] I have updated the changelog and the corresponding version in the extension's `config/extension.toml` file - [ ] I have added my name to the `CONTRIBUTORS.md` or my name already exists there --- .../disable-articulation-sim-ci.skip | 0 .../test/assets/test_articulation.py | 30 ------------------- .../disable-articulation-sim-ci.skip | 0 .../test/assets/test_articulation.py | 30 ------------------- 4 files changed, 60 deletions(-) create mode 100644 source/isaaclab_newton/changelog.d/disable-articulation-sim-ci.skip create mode 100644 source/isaaclab_physx/changelog.d/disable-articulation-sim-ci.skip diff --git a/source/isaaclab_newton/changelog.d/disable-articulation-sim-ci.skip b/source/isaaclab_newton/changelog.d/disable-articulation-sim-ci.skip new file mode 100644 index 000000000000..e69de29bb2d1 diff --git a/source/isaaclab_newton/test/assets/test_articulation.py b/source/isaaclab_newton/test/assets/test_articulation.py index fdb335291fa5..cd0f2dcb03b9 100644 --- a/source/isaaclab_newton/test/assets/test_articulation.py +++ b/source/isaaclab_newton/test/assets/test_articulation.py @@ -379,7 +379,6 @@ def sim(request): yield sim -@pytest.mark.isaacsim_ci @pytest.mark.parametrize("num_articulations", [1, 2]) @pytest.mark.parametrize("device", ["cuda:0", "cpu"]) @pytest.mark.parametrize("add_ground_plane", [True]) @@ -429,7 +428,6 @@ def test_initialization_floating_base_non_root(sim, num_articulations, device, a articulation.update(sim.cfg.dt) -@pytest.mark.isaacsim_ci @pytest.mark.parametrize("num_articulations", [1, 2]) @pytest.mark.parametrize("device", ["cuda:0", "cpu"]) @pytest.mark.parametrize("add_ground_plane", [True]) @@ -480,7 +478,6 @@ def test_initialization_floating_base(sim, num_articulations, device, add_ground articulation.update(sim.cfg.dt) -@pytest.mark.isaacsim_ci @pytest.mark.parametrize("num_articulations", [1, 2]) @pytest.mark.parametrize("device", ["cuda:0", "cpu"]) @pytest.mark.parametrize("articulation_type", ["panda"]) @@ -538,7 +535,6 @@ def test_initialization_fixed_base(sim, num_articulations, device, articulation_ torch.testing.assert_close(articulation.data.root_com_vel_w.torch, default_root_vel) -@pytest.mark.isaacsim_ci @pytest.mark.parametrize("num_articulations", [1, 2]) @pytest.mark.parametrize("device", ["cuda:0", "cpu"]) @pytest.mark.parametrize("add_ground_plane", [True]) @@ -597,7 +593,6 @@ def test_initialization_fixed_base_single_joint(sim, num_articulations, device, torch.testing.assert_close(articulation.data.root_com_vel_w.torch, default_root_vel) -@pytest.mark.isaacsim_ci @pytest.mark.parametrize("num_articulations", [1, 2]) @pytest.mark.parametrize("device", ["cuda:0", "cpu"]) @pytest.mark.parametrize("articulation_type", ["shadow_hand"]) @@ -647,7 +642,6 @@ def test_initialization_hand_with_tendons(sim, num_articulations, device, articu articulation.update(sim.cfg.dt) -@pytest.mark.isaacsim_ci @pytest.mark.parametrize("num_articulations", [1, 2]) @pytest.mark.parametrize("device", ["cuda:0", "cpu"]) @pytest.mark.parametrize("add_ground_plane", [True]) @@ -702,7 +696,6 @@ def test_initialization_floating_base_made_fixed_base( torch.testing.assert_close(articulation.data.root_com_vel_w.torch, default_root_vel) -@pytest.mark.isaacsim_ci @pytest.mark.parametrize("num_articulations", [1, 2]) @pytest.mark.parametrize("device", ["cuda:0", "cpu"]) @pytest.mark.parametrize("add_ground_plane", [True]) @@ -749,7 +742,6 @@ def test_initialization_fixed_base_made_floating_base( articulation.update(sim.cfg.dt) -@pytest.mark.isaacsim_ci @pytest.mark.parametrize("num_articulations", [1, 2]) @pytest.mark.parametrize("device", ["cuda:0", "cpu"]) @pytest.mark.parametrize("add_ground_plane", [True]) @@ -782,7 +774,6 @@ def test_out_of_range_default_joint_pos(sim, num_articulations, device, add_grou sim.reset() -@pytest.mark.isaacsim_ci @pytest.mark.parametrize("device", ["cuda:0", "cpu"]) @pytest.mark.parametrize("articulation_type", ["panda"]) def test_out_of_range_default_joint_vel(sim, device, articulation_type): @@ -807,7 +798,6 @@ def test_out_of_range_default_joint_vel(sim, device, articulation_type): sim.reset() -@pytest.mark.isaacsim_ci @pytest.mark.parametrize("num_articulations", [1, 2]) @pytest.mark.parametrize("device", ["cuda:0", "cpu"]) @pytest.mark.parametrize("add_ground_plane", [True]) @@ -918,7 +908,6 @@ def __init__(self, art): assert torch.all(out) -@pytest.mark.isaacsim_ci @pytest.mark.parametrize("num_articulations", [1, 2]) @pytest.mark.parametrize("device", ["cuda:0", "cpu"]) @pytest.mark.parametrize("articulation_type", ["anymal"]) @@ -1004,7 +993,6 @@ def test_external_force_buffer(sim, num_articulations, device, articulation_type articulation.update(sim.cfg.dt) -@pytest.mark.isaacsim_ci @pytest.mark.parametrize("num_articulations", [1, 2]) @pytest.mark.parametrize("device", ["cuda:0", "cpu"]) @pytest.mark.parametrize("articulation_type", ["anymal"]) @@ -1063,7 +1051,6 @@ def test_external_force_on_single_body(sim, num_articulations, device, articulat assert articulation.data.root_pos_w.torch[i, 2].item() < 0.2 -@pytest.mark.isaacsim_ci @pytest.mark.parametrize("num_articulations", [1, 2]) @pytest.mark.parametrize("device", ["cuda:0", "cpu"]) @pytest.mark.parametrize("articulation_type", ["anymal"]) @@ -1159,7 +1146,6 @@ def test_external_force_on_single_body_at_position(sim, num_articulations, devic assert articulation.data.root_pos_w.torch[i, 2].item() < 0.2 -@pytest.mark.isaacsim_ci @pytest.mark.parametrize("num_articulations", [1, 2]) @pytest.mark.parametrize("device", ["cuda:0", "cpu"]) @pytest.mark.parametrize("articulation_type", ["anymal"]) @@ -1220,7 +1206,6 @@ def test_external_force_on_multiple_bodies(sim, num_articulations, device, artic assert articulation.data.root_ang_vel_w.torch[i, 2].item() > 0.1 -@pytest.mark.isaacsim_ci @pytest.mark.parametrize("num_articulations", [1, 2]) @pytest.mark.parametrize("device", ["cuda:0", "cpu"]) @pytest.mark.parametrize("articulation_type", ["anymal"]) @@ -1315,7 +1300,6 @@ def test_external_force_on_multiple_bodies_at_position(sim, num_articulations, d assert torch.abs(articulation.data.root_ang_vel_w.torch[i, 2]).item() > 0.1 -@pytest.mark.isaacsim_ci @pytest.mark.parametrize("num_articulations", [1, 2]) @pytest.mark.parametrize("device", ["cuda:0", "cpu"]) @pytest.mark.parametrize("articulation_type", ["humanoid"]) @@ -1378,7 +1362,6 @@ def test_loading_gains_from_usd(sim, num_articulations, device, articulation_typ torch.testing.assert_close(articulation.actuators["body"].damping, expected_damping) -@pytest.mark.isaacsim_ci @pytest.mark.parametrize("num_articulations", [1, 2]) @pytest.mark.parametrize("device", ["cuda:0", "cpu"]) @pytest.mark.parametrize("add_ground_plane", [True]) @@ -1414,7 +1397,6 @@ def test_setting_gains_from_cfg(sim, num_articulations, device, add_ground_plane torch.testing.assert_close(articulation.actuators["body"].damping, expected_damping) -@pytest.mark.isaacsim_ci @pytest.mark.parametrize("num_articulations", [1, 2]) @pytest.mark.parametrize("device", ["cuda:0", "cpu"]) @pytest.mark.parametrize("articulation_type", ["humanoid"]) @@ -1448,7 +1430,6 @@ def test_setting_gains_from_cfg_dict(sim, num_articulations, device, articulatio torch.testing.assert_close(articulation.actuators["body"].damping, expected_damping) -@pytest.mark.isaacsim_ci @pytest.mark.parametrize("num_articulations", [1, 2]) @pytest.mark.parametrize("device", ["cuda:0", "cpu"]) @pytest.mark.parametrize("vel_limit_sim", [1e5, None]) @@ -1521,7 +1502,6 @@ def test_setting_velocity_limit_implicit( torch.testing.assert_close(newton_vel_limit, expected_velocity_limit) -@pytest.mark.isaacsim_ci @pytest.mark.parametrize("num_articulations", [1, 2]) @pytest.mark.parametrize("device", ["cuda:0", "cpu"]) @pytest.mark.parametrize("vel_limit_sim", [1e5, None]) @@ -1578,7 +1558,6 @@ def test_setting_velocity_limit_explicit(sim, num_articulations, device, vel_lim torch.testing.assert_close(newton_vel_limit, expected_vel_limit) -@pytest.mark.isaacsim_ci @pytest.mark.parametrize("num_articulations", [1, 2]) @pytest.mark.parametrize("device", ["cuda:0", "cpu"]) @pytest.mark.parametrize("effort_limit_sim", [1e5, None]) @@ -1636,7 +1615,6 @@ def test_setting_effort_limit_implicit( torch.testing.assert_close(newton_effort_limit, expected_effort_limit) -@pytest.mark.isaacsim_ci @pytest.mark.parametrize("num_articulations", [1, 2]) @pytest.mark.parametrize("device", ["cuda:0", "cpu"]) @pytest.mark.parametrize("effort_limit_sim", [1e5, None]) @@ -1703,7 +1681,6 @@ def test_setting_effort_limit_explicit( torch.testing.assert_close(newton_effort_limit, expected_effort_limit) -@pytest.mark.isaacsim_ci @pytest.mark.parametrize("num_articulations", [1, 2]) @pytest.mark.parametrize("device", ["cuda:0", "cpu"]) @pytest.mark.parametrize("articulation_type", ["humanoid"]) @@ -1748,7 +1725,6 @@ def test_reset(sim, num_articulations, device, articulation_type): assert torch.count_nonzero(articulation._permanent_wrench_composer.out_torque_b.torch) == num_bodies * 3 -@pytest.mark.isaacsim_ci @pytest.mark.parametrize("num_articulations", [1, 2]) @pytest.mark.parametrize("device", ["cuda:0", "cpu"]) @pytest.mark.parametrize("add_ground_plane", [True]) @@ -1789,7 +1765,6 @@ def test_apply_joint_command(sim, num_articulations, device, add_ground_plane, a assert not torch.allclose(articulation.data.joint_pos.torch, joint_pos) -@pytest.mark.isaacsim_ci @pytest.mark.parametrize("num_articulations", [1, 2]) @pytest.mark.parametrize("device", ["cuda:0", "cpu"]) @pytest.mark.parametrize("with_offset", [True, False]) @@ -1915,7 +1890,6 @@ def test_body_root_state(sim, num_articulations, device, with_offset, articulati torch.testing.assert_close(body_com_vel_w, body_link_vel_w) -@pytest.mark.isaacsim_ci @pytest.mark.parametrize("num_articulations", [1, 2]) @pytest.mark.parametrize("device", ["cuda:0", "cpu"]) @pytest.mark.parametrize("with_offset", [True, False]) @@ -2006,7 +1980,6 @@ def test_write_root_state( torch.testing.assert_close(rand_state[..., 7:], articulation.data.root_link_vel_w.torch) -@pytest.mark.isaacsim_ci @pytest.mark.parametrize("device", ["cuda:0", "cpu"]) @pytest.mark.parametrize("articulation_type", ["humanoid"]) def test_setting_articulation_root_prim_path(sim, device, articulation_type): @@ -2026,7 +1999,6 @@ def test_setting_articulation_root_prim_path(sim, device, articulation_type): assert articulation._is_initialized -@pytest.mark.isaacsim_ci @pytest.mark.parametrize("device", ["cuda:0", "cpu"]) @pytest.mark.parametrize("articulation_type", ["humanoid"]) def test_setting_invalid_articulation_root_prim_path(sim, device, articulation_type): @@ -2045,7 +2017,6 @@ def test_setting_invalid_articulation_root_prim_path(sim, device, articulation_t sim.reset() -@pytest.mark.isaacsim_ci @pytest.mark.parametrize("num_articulations", [1, 2]) @pytest.mark.parametrize("device", ["cuda:0", "cpu"]) @pytest.mark.parametrize("gravity_enabled", [False]) @@ -2357,7 +2328,6 @@ def _patched_simulate(cls): ) -@pytest.mark.isaacsim_ci @pytest.mark.parametrize("add_ground_plane", [True]) @pytest.mark.parametrize("num_articulations", [1, 2]) @pytest.mark.parametrize("device", ["cuda:0", "cpu"]) diff --git a/source/isaaclab_physx/changelog.d/disable-articulation-sim-ci.skip b/source/isaaclab_physx/changelog.d/disable-articulation-sim-ci.skip new file mode 100644 index 000000000000..e69de29bb2d1 diff --git a/source/isaaclab_physx/test/assets/test_articulation.py b/source/isaaclab_physx/test/assets/test_articulation.py index bd015562c4df..227c091a1652 100644 --- a/source/isaaclab_physx/test/assets/test_articulation.py +++ b/source/isaaclab_physx/test/assets/test_articulation.py @@ -204,7 +204,6 @@ def sim(request): @pytest.mark.parametrize("num_articulations", [1, 2]) @pytest.mark.parametrize("device", ["cuda:0", "cpu"]) @pytest.mark.parametrize("add_ground_plane", [True]) -@pytest.mark.isaacsim_ci def test_initialization_floating_base_non_root(sim, num_articulations, device, add_ground_plane): """Test initialization for a floating-base with articulation root on a rigid body. @@ -261,7 +260,6 @@ def test_initialization_floating_base_non_root(sim, num_articulations, device, a @pytest.mark.parametrize("num_articulations", [1, 2]) @pytest.mark.parametrize("device", ["cuda:0", "cpu"]) @pytest.mark.parametrize("add_ground_plane", [True]) -@pytest.mark.isaacsim_ci def test_initialization_floating_base(sim, num_articulations, device, add_ground_plane): """Test initialization for a floating-base with articulation root on provided prim path. @@ -318,7 +316,6 @@ def test_initialization_floating_base(sim, num_articulations, device, add_ground @pytest.mark.parametrize("num_articulations", [1, 2]) @pytest.mark.parametrize("device", ["cuda:0", "cpu"]) -@pytest.mark.isaacsim_ci def test_initialization_fixed_base(sim, num_articulations, device): """Test initialization for fixed base. @@ -384,7 +381,6 @@ def test_initialization_fixed_base(sim, num_articulations, device): @pytest.mark.parametrize("num_articulations", [1, 2]) @pytest.mark.parametrize("device", ["cuda:0", "cpu"]) @pytest.mark.parametrize("add_ground_plane", [True]) -@pytest.mark.isaacsim_ci def test_initialization_fixed_base_single_joint(sim, num_articulations, device, add_ground_plane): """Test initialization for fixed base articulation with a single joint. @@ -449,7 +445,6 @@ def test_initialization_fixed_base_single_joint(sim, num_articulations, device, @pytest.mark.parametrize("num_articulations", [1, 2]) @pytest.mark.parametrize("device", ["cuda:0", "cpu"]) -@pytest.mark.isaacsim_ci def test_initialization_hand_with_tendons(sim, num_articulations, device): """Test initialization for fixed base articulated hand with tendons. @@ -504,7 +499,6 @@ def test_initialization_hand_with_tendons(sim, num_articulations, device): @pytest.mark.parametrize("num_articulations", [1, 2]) @pytest.mark.parametrize("device", ["cuda:0", "cpu"]) @pytest.mark.parametrize("add_ground_plane", [True]) -@pytest.mark.isaacsim_ci def test_initialization_floating_base_made_fixed_base(sim, num_articulations, device, add_ground_plane): """Test initialization for a floating-base articulation made fixed-base using schema properties. @@ -565,7 +559,6 @@ def test_initialization_floating_base_made_fixed_base(sim, num_articulations, de @pytest.mark.parametrize("num_articulations", [1, 2]) @pytest.mark.parametrize("device", ["cuda:0", "cpu"]) @pytest.mark.parametrize("add_ground_plane", [True]) -@pytest.mark.isaacsim_ci def test_initialization_fixed_base_made_floating_base(sim, num_articulations, device, add_ground_plane): """Test initialization for fixed base made floating-base using schema properties. @@ -618,7 +611,6 @@ def test_initialization_fixed_base_made_floating_base(sim, num_articulations, de @pytest.mark.parametrize("num_articulations", [1, 2]) @pytest.mark.parametrize("device", ["cuda:0", "cpu"]) @pytest.mark.parametrize("add_ground_plane", [True]) -@pytest.mark.isaacsim_ci def test_out_of_range_default_joint_pos(sim, num_articulations, device, add_ground_plane): """Test that the default joint position from configuration is out of range. @@ -648,7 +640,6 @@ def test_out_of_range_default_joint_pos(sim, num_articulations, device, add_grou @pytest.mark.parametrize("device", ["cuda:0", "cpu"]) -@pytest.mark.isaacsim_ci def test_out_of_range_default_joint_vel(sim, device): """Test that the default joint velocity from configuration is out of range. @@ -674,7 +665,6 @@ def test_out_of_range_default_joint_vel(sim, device): @pytest.mark.parametrize("num_articulations", [1, 2]) @pytest.mark.parametrize("device", ["cuda:0", "cpu"]) @pytest.mark.parametrize("add_ground_plane", [True]) -@pytest.mark.isaacsim_ci def test_joint_pos_limits(sim, num_articulations, device, add_ground_plane): """Test write_joint_limits_to_sim API and when default pos falls outside of the new limits. @@ -782,7 +772,6 @@ def __init__(self, art): @pytest.mark.parametrize("num_articulations", [1, 2]) @pytest.mark.parametrize("device", ["cuda:0", "cpu"]) -@pytest.mark.isaacsim_ci def test_external_force_buffer(sim, num_articulations, device): """Test if external force buffer correctly updates in the force value is zero case. @@ -867,7 +856,6 @@ def test_external_force_buffer(sim, num_articulations, device): @pytest.mark.parametrize("num_articulations", [1, 2]) @pytest.mark.parametrize("device", ["cuda:0", "cpu"]) -@pytest.mark.isaacsim_ci def test_external_force_on_single_body(sim, num_articulations, device): """Test application of external force on the base of the articulation. @@ -925,7 +913,6 @@ def test_external_force_on_single_body(sim, num_articulations, device): @pytest.mark.parametrize("num_articulations", [1, 2]) @pytest.mark.parametrize("device", ["cuda:0", "cpu"]) -@pytest.mark.isaacsim_ci def test_external_force_on_single_body_at_position(sim, num_articulations, device): """Test application of external force on the base of the articulation at a given position. @@ -1020,7 +1007,6 @@ def test_external_force_on_single_body_at_position(sim, num_articulations, devic @pytest.mark.parametrize("num_articulations", [1, 2]) @pytest.mark.parametrize("device", ["cuda:0", "cpu"]) -@pytest.mark.isaacsim_ci def test_external_force_on_multiple_bodies(sim, num_articulations, device): """Test application of external force on the legs of the articulation. @@ -1080,7 +1066,6 @@ def test_external_force_on_multiple_bodies(sim, num_articulations, device): @pytest.mark.parametrize("num_articulations", [1, 2]) @pytest.mark.parametrize("device", ["cuda:0", "cpu"]) -@pytest.mark.isaacsim_ci def test_external_force_on_multiple_bodies_at_position(sim, num_articulations, device): """Test application of external force on the legs of the articulation at a given position. @@ -1174,7 +1159,6 @@ def test_external_force_on_multiple_bodies_at_position(sim, num_articulations, d @pytest.mark.parametrize("num_articulations", [1, 2]) @pytest.mark.parametrize("device", ["cuda:0", "cpu"]) -@pytest.mark.isaacsim_ci def test_loading_gains_from_usd(sim, num_articulations, device): """Test that gains are loaded from USD file if actuator model has them as None. @@ -1237,7 +1221,6 @@ def test_loading_gains_from_usd(sim, num_articulations, device): @pytest.mark.parametrize("num_articulations", [1, 2]) @pytest.mark.parametrize("device", ["cuda:0", "cpu"]) @pytest.mark.parametrize("add_ground_plane", [True]) -@pytest.mark.isaacsim_ci def test_setting_gains_from_cfg(sim, num_articulations, device, add_ground_plane): """Test that gains are loaded from the configuration correctly. @@ -1271,7 +1254,6 @@ def test_setting_gains_from_cfg(sim, num_articulations, device, add_ground_plane @pytest.mark.parametrize("num_articulations", [1, 2]) @pytest.mark.parametrize("device", ["cuda:0", "cpu"]) -@pytest.mark.isaacsim_ci def test_setting_gains_from_cfg_dict(sim, num_articulations, device): """Test that gains are loaded from the configuration dictionary correctly. @@ -1307,7 +1289,6 @@ def test_setting_gains_from_cfg_dict(sim, num_articulations, device): @pytest.mark.parametrize("vel_limit_sim", [1e5, None]) @pytest.mark.parametrize("vel_limit", [1e2, None]) @pytest.mark.parametrize("add_ground_plane", [False]) -@pytest.mark.isaacsim_ci def test_setting_velocity_limit_implicit(sim, num_articulations, device, vel_limit_sim, vel_limit, add_ground_plane): """Test setting of velocity limit for implicit actuators. @@ -1374,7 +1355,6 @@ def test_setting_velocity_limit_implicit(sim, num_articulations, device, vel_lim @pytest.mark.parametrize("device", ["cuda:0", "cpu"]) @pytest.mark.parametrize("vel_limit_sim", [1e5, None]) @pytest.mark.parametrize("vel_limit", [1e2, None]) -@pytest.mark.isaacsim_ci def test_setting_velocity_limit_explicit(sim, num_articulations, device, vel_limit_sim, vel_limit): """Test setting of velocity limit for explicit actuators.""" articulation_cfg = generate_articulation_cfg( @@ -1428,7 +1408,6 @@ def test_setting_velocity_limit_explicit(sim, num_articulations, device, vel_lim @pytest.mark.parametrize("device", ["cuda:0", "cpu"]) @pytest.mark.parametrize("effort_limit_sim", [1e5, None]) @pytest.mark.parametrize("effort_limit", [1e2, 80.0, None]) -@pytest.mark.isaacsim_ci def test_setting_effort_limit_implicit(sim, num_articulations, device, effort_limit_sim, effort_limit): """Test setting of effort limit for implicit actuators. @@ -1481,7 +1460,6 @@ def test_setting_effort_limit_implicit(sim, num_articulations, device, effort_li @pytest.mark.parametrize("device", ["cuda:0", "cpu"]) @pytest.mark.parametrize("effort_limit_sim", [1e5, None]) @pytest.mark.parametrize("effort_limit", [80.0, 1e2, None]) -@pytest.mark.isaacsim_ci def test_setting_effort_limit_explicit(sim, num_articulations, device, effort_limit_sim, effort_limit): """Test setting of effort limit for explicit actuators. @@ -1541,7 +1519,6 @@ def test_setting_effort_limit_explicit(sim, num_articulations, device, effort_li @pytest.mark.parametrize("num_articulations", [1, 2]) @pytest.mark.parametrize("device", ["cuda:0", "cpu"]) -@pytest.mark.isaacsim_ci def test_reset(sim, num_articulations, device): """Test that reset method works properly.""" articulation_cfg = generate_articulation_cfg(articulation_type="humanoid") @@ -1586,7 +1563,6 @@ def test_reset(sim, num_articulations, device): @pytest.mark.parametrize("num_articulations", [1, 2]) @pytest.mark.parametrize("device", ["cuda:0", "cpu"]) @pytest.mark.parametrize("add_ground_plane", [True]) -@pytest.mark.isaacsim_ci def test_apply_joint_command(sim, num_articulations, device, add_ground_plane): """Test applying of joint position target functions correctly for a robotic arm.""" articulation_cfg = generate_articulation_cfg(articulation_type="panda") @@ -1626,7 +1602,6 @@ def test_apply_joint_command(sim, num_articulations, device, add_ground_plane): @pytest.mark.parametrize("num_articulations", [1, 2]) @pytest.mark.parametrize("device", ["cuda:0", "cpu"]) @pytest.mark.parametrize("with_offset", [True, False]) -@pytest.mark.isaacsim_ci def test_body_root_state(sim, num_articulations, device, with_offset): """Test for reading the `body_state_w` property. @@ -1752,7 +1727,6 @@ def test_body_root_state(sim, num_articulations, device, with_offset): @pytest.mark.parametrize("with_offset", [True, False]) @pytest.mark.parametrize("state_location", ["com", "link"]) @pytest.mark.parametrize("gravity_enabled", [False]) -@pytest.mark.isaacsim_ci def test_write_root_state(sim, num_articulations, device, with_offset, state_location, gravity_enabled): """Test the setters for root_state using both the link frame and center of mass as reference frame. @@ -1831,7 +1805,6 @@ def test_write_root_state(sim, num_articulations, device, with_offset, state_loc @pytest.mark.parametrize("device", ["cuda:0", "cpu"]) -@pytest.mark.isaacsim_ci def test_setting_articulation_root_prim_path(sim, device): """Test that the articulation root prim path can be set explicitly.""" sim._app_control_on_stop_handle = None @@ -1850,7 +1823,6 @@ def test_setting_articulation_root_prim_path(sim, device): @pytest.mark.parametrize("device", ["cuda:0", "cpu"]) -@pytest.mark.isaacsim_ci def test_setting_invalid_articulation_root_prim_path(sim, device): """Test that the articulation root prim path can be set explicitly.""" sim._app_control_on_stop_handle = None @@ -1870,7 +1842,6 @@ def test_setting_invalid_articulation_root_prim_path(sim, device): @pytest.mark.parametrize("num_articulations", [1, 2]) @pytest.mark.parametrize("device", ["cuda:0", "cpu"]) @pytest.mark.parametrize("gravity_enabled", [False]) -@pytest.mark.isaacsim_ci def test_write_joint_state_data_consistency(sim, num_articulations, device, gravity_enabled): """Test the setters for root_state using both the link frame and center of mass as reference frame. @@ -2121,7 +2092,6 @@ def test_write_joint_frictions_to_sim(sim, num_articulations, device, add_ground @pytest.mark.parametrize("num_articulations", [1, 2]) @pytest.mark.parametrize("device", ["cuda:0", "cpu"]) @pytest.mark.parametrize("articulation_type", ["panda"]) -@pytest.mark.isaacsim_ci def test_set_material_properties(sim, num_articulations, device, add_ground_plane, articulation_type): """Test getting and setting material properties (friction/restitution) of articulation shapes.""" articulation_cfg = generate_articulation_cfg(articulation_type=articulation_type) From 39a9aecfdb20395d06d23daa75effce3e05a7094 Mon Sep 17 00:00:00 2001 From: Piotr Barejko Date: Fri, 8 May 2026 21:23:48 -0700 Subject: [PATCH 29/51] Initialize Warp runtime (#5548) # Description OVRTX renderer relies on Warp. In some instances, i.e. unit tests, the ovrtx integration layer can fail with following error: ```python else: try: if torch_device.type == "cuda": > return warp._src.context.runtime.cuda_devices[torch_device.index] ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ E AttributeError: 'NoneType' object has no attribute 'cuda_devices' ovphysx-ovrtx/lib/python3.12/site-packages/warp/_src/torch.py:41: AttributeError ``` This problem is because warp runtime isn't initialized, by importing `import isaaclab.utils.warp` module we ensure warp runtime is initialized. Fixes # (issue) ## Type of change - Bug fix (non-breaking change which fixes an issue) - New feature (non-breaking change which adds functionality) - Breaking change (existing functionality will not work without user modification) - Documentation update ## Screenshots Please attach before and after screenshots of the change if applicable. ## Checklist - [ ] I have read and understood the [contribution guidelines](https://isaac-sim.github.io/IsaacLab/main/source/refs/contributing.html) - [ ] I have run the [`pre-commit` checks](https://pre-commit.com/) with `./isaaclab.sh --format` - [ ] I have made corresponding changes to the documentation - [ ] My changes generate no new warnings - [ ] I have added tests that prove my fix is effective or that my feature works - [ ] I have updated the changelog and the corresponding version in the extension's `config/extension.toml` file - [ ] I have added my name to the `CONTRIBUTORS.md` or my name already exists there --- docs/source/overview/environments.rst | 2 +- .../changelog.d/pbarejko-add-seed-to-math-module.rst | 4 ++++ source/isaaclab/test/utils/test_math.py | 5 ++++- source/isaaclab_ov/changelog.d/pbarejko-init-warp.rst | 4 ++++ source/isaaclab_ov/isaaclab_ov/renderers/ovrtx_renderer.py | 2 ++ 5 files changed, 15 insertions(+), 2 deletions(-) create mode 100644 source/isaaclab/changelog.d/pbarejko-add-seed-to-math-module.rst create mode 100644 source/isaaclab_ov/changelog.d/pbarejko-init-warp.rst diff --git a/docs/source/overview/environments.rst b/docs/source/overview/environments.rst index 6a13f8c087d7..a28d129f7027 100644 --- a/docs/source/overview/environments.rst +++ b/docs/source/overview/environments.rst @@ -531,7 +531,7 @@ Multirotor .. |arl_robot_track_position_state_based| image:: ../_static/tasks/drone_arl/arl_robot_1_track_position_state_based.jpg -.. |arl_robot_navigation-link| replace:: `Isaac-Navigation-3DObstacles-ARL-Robot-1-v0 `__ +.. |arl_robot_navigation-link| replace:: `Isaac-Navigation-3DObstacles-ARL-Robot-1-v0 `__ .. |arl_robot_navigation| image:: ../_static/tasks/drone_arl/arl_robot_1_navigation.jpg diff --git a/source/isaaclab/changelog.d/pbarejko-add-seed-to-math-module.rst b/source/isaaclab/changelog.d/pbarejko-add-seed-to-math-module.rst new file mode 100644 index 000000000000..885c962d90b2 --- /dev/null +++ b/source/isaaclab/changelog.d/pbarejko-add-seed-to-math-module.rst @@ -0,0 +1,4 @@ +Fixed +^^^^^ + +* Certain functions in test_math were failing non deterministically. This was caused by not setting seed values. diff --git a/source/isaaclab/test/utils/test_math.py b/source/isaaclab/test/utils/test_math.py index e0d85b14eb25..6bff0b31e267 100644 --- a/source/isaaclab/test/utils/test_math.py +++ b/source/isaaclab/test/utils/test_math.py @@ -554,12 +554,15 @@ def test_combine_frame_transform(device): @pytest.mark.parametrize("device", ["cpu", "cuda:0"]) -def test_interpolate_poses(device): +@pytest.mark.parametrize("seed", [0, 1, 2, 3, 4]) +def test_interpolate_poses(device, seed): """Test interpolate_poses function. This test checks the output from the :meth:`~isaaclab.utils.math_utils.interpolate_poses` function against the output from :func:`scipy.spatial.transform.Slerp` and :func:`np.linspace`. """ + torch.manual_seed(seed) + np.random.seed(seed) for _ in range(100): mat1 = math_utils.generate_random_transformation_matrix() mat2 = math_utils.generate_random_transformation_matrix() diff --git a/source/isaaclab_ov/changelog.d/pbarejko-init-warp.rst b/source/isaaclab_ov/changelog.d/pbarejko-init-warp.rst new file mode 100644 index 000000000000..413bfe794f05 --- /dev/null +++ b/source/isaaclab_ov/changelog.d/pbarejko-init-warp.rst @@ -0,0 +1,4 @@ +Fixed +^^^^^ + +* Initialize Warp runtime for OvRTX renderer. diff --git a/source/isaaclab_ov/isaaclab_ov/renderers/ovrtx_renderer.py b/source/isaaclab_ov/isaaclab_ov/renderers/ovrtx_renderer.py index 00e0a1d06d3a..3c05a72dc30f 100644 --- a/source/isaaclab_ov/isaaclab_ov/renderers/ovrtx_renderer.py +++ b/source/isaaclab_ov/isaaclab_ov/renderers/ovrtx_renderer.py @@ -30,6 +30,8 @@ import torch import warp as wp +import isaaclab.utils.warp # noqa: F401 # initializes Warp runtime + # The ovrtx C library links to its own version of the USD libraries. Having # the pxr Python package available can cause the C library to load an # incompatible version of libusd, potentially leading to undefined behavior. From b59b3ae844d1490eddf5e288b7cefd381f41c46a Mon Sep 17 00:00:00 2001 From: "isaaclab-bot[bot]" <282401363+isaaclab-bot[bot]@users.noreply.github.com> Date: Sat, 9 May 2026 05:57:31 +0000 Subject: [PATCH 30/51] [CI][Auto Version Bump] Compile changelog fragments (schedule) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Bumped packages: - isaaclab: 4.8.0 → 4.8.1 - isaaclab_contrib: 0.3.0 → 0.3.1 - isaaclab_newton: 0.7.0 → 0.7.1 - isaaclab_ov: 0.1.5 → 0.1.6 - isaaclab_ovphysx: 0.1.3 → 0.1.4 - isaaclab_physx: 0.6.1 → 0.6.2 - isaaclab_tasks: 1.5.35 → 1.5.36 --- ...oiner-core-deprecation-warning-cleanup.rst | 5 --- .../antoiner-docs-joint-friction.rst | 4 -- .../antoiner-docs-sensor-updates.rst | 8 ---- ...toiner-fix-from-files-windows-filelock.rst | 12 ------ .../jichuanh-fix-warp-intersphinx.rst | 5 --- .../malesiani-ovphysx-04-fixes.rst | 5 --- source/isaaclab/changelog.d/my-nvbugs-2.rst | 8 ---- .../pbarejko-add-seed-to-math-module.rst | 4 -- .../pr-5423-state-observation-mdp.rst | 6 --- source/isaaclab/config/extension.toml | 2 +- source/isaaclab/docs/CHANGELOG.rst | 38 +++++++++++++++++++ ...-5410-task-deprecation-warning-cleanup.rst | 6 --- source/isaaclab_contrib/config/extension.toml | 2 +- source/isaaclab_contrib/docs/CHANGELOG.rst | 11 ++++++ ...er-backend-deprecation-warning-cleanup.rst | 6 --- .../antoiner-docs-joint-friction.rst | 5 --- .../antoiner-fix-fk-invalidation.rst | 6 --- .../disable-articulation-sim-ci.skip | 0 source/isaaclab_newton/config/extension.toml | 2 +- source/isaaclab_newton/docs/CHANGELOG.rst | 16 ++++++++ .../huidongc-ovrtx-keep-system-alive.rst | 6 --- .../changelog.d/pbarejko-init-warp.rst | 4 -- source/isaaclab_ov/config/extension.toml | 2 +- source/isaaclab_ov/docs/CHANGELOG.rst | 12 ++++++ .../malesiani-ovphysx-04-fixes.rst | 6 --- source/isaaclab_ovphysx/config/extension.toml | 2 +- source/isaaclab_ovphysx/docs/CHANGELOG.rst | 11 ++++++ ...er-backend-deprecation-warning-cleanup.rst | 5 --- .../antoiner-docs-joint-friction.rst | 5 --- .../disable-articulation-sim-ci.skip | 0 source/isaaclab_physx/config/extension.toml | 2 +- source/isaaclab_physx/docs/CHANGELOG.rst | 12 ++++++ .../huidongc-enable-ovrtx-rendering.skip | 0 .../malesiani-ovphysx-camera-cartpole.rst | 4 -- ...-5410-task-deprecation-warning-cleanup.rst | 8 ---- .../pr-5423-state-observation-mdp.rst | 21 ---------- source/isaaclab_tasks/config/extension.toml | 2 +- source/isaaclab_tasks/docs/CHANGELOG.rst | 32 ++++++++++++++++ 38 files changed, 139 insertions(+), 146 deletions(-) delete mode 100644 source/isaaclab/changelog.d/antoiner-core-deprecation-warning-cleanup.rst delete mode 100644 source/isaaclab/changelog.d/antoiner-docs-joint-friction.rst delete mode 100644 source/isaaclab/changelog.d/antoiner-docs-sensor-updates.rst delete mode 100644 source/isaaclab/changelog.d/antoiner-fix-from-files-windows-filelock.rst delete mode 100644 source/isaaclab/changelog.d/jichuanh-fix-warp-intersphinx.rst delete mode 100644 source/isaaclab/changelog.d/malesiani-ovphysx-04-fixes.rst delete mode 100644 source/isaaclab/changelog.d/my-nvbugs-2.rst delete mode 100644 source/isaaclab/changelog.d/pbarejko-add-seed-to-math-module.rst delete mode 100644 source/isaaclab/changelog.d/pr-5423-state-observation-mdp.rst delete mode 100644 source/isaaclab_contrib/changelog.d/pr-5410-task-deprecation-warning-cleanup.rst delete mode 100644 source/isaaclab_newton/changelog.d/antoiner-backend-deprecation-warning-cleanup.rst delete mode 100644 source/isaaclab_newton/changelog.d/antoiner-docs-joint-friction.rst delete mode 100644 source/isaaclab_newton/changelog.d/antoiner-fix-fk-invalidation.rst delete mode 100644 source/isaaclab_newton/changelog.d/disable-articulation-sim-ci.skip delete mode 100644 source/isaaclab_ov/changelog.d/huidongc-ovrtx-keep-system-alive.rst delete mode 100644 source/isaaclab_ov/changelog.d/pbarejko-init-warp.rst delete mode 100644 source/isaaclab_ovphysx/changelog.d/malesiani-ovphysx-04-fixes.rst delete mode 100644 source/isaaclab_physx/changelog.d/antoiner-backend-deprecation-warning-cleanup.rst delete mode 100644 source/isaaclab_physx/changelog.d/antoiner-docs-joint-friction.rst delete mode 100644 source/isaaclab_physx/changelog.d/disable-articulation-sim-ci.skip delete mode 100644 source/isaaclab_tasks/changelog.d/huidongc-enable-ovrtx-rendering.skip delete mode 100644 source/isaaclab_tasks/changelog.d/malesiani-ovphysx-camera-cartpole.rst delete mode 100644 source/isaaclab_tasks/changelog.d/pr-5410-task-deprecation-warning-cleanup.rst delete mode 100644 source/isaaclab_tasks/changelog.d/pr-5423-state-observation-mdp.rst diff --git a/source/isaaclab/changelog.d/antoiner-core-deprecation-warning-cleanup.rst b/source/isaaclab/changelog.d/antoiner-core-deprecation-warning-cleanup.rst deleted file mode 100644 index a3a3e51f8b3a..000000000000 --- a/source/isaaclab/changelog.d/antoiner-core-deprecation-warning-cleanup.rst +++ /dev/null @@ -1,5 +0,0 @@ -Fixed -^^^^^ - -* Fixed :class:`~isaaclab.envs.mdp.actions.PinkInverseKinematicsAction` - base link pose reads to avoid deprecated body link state access. diff --git a/source/isaaclab/changelog.d/antoiner-docs-joint-friction.rst b/source/isaaclab/changelog.d/antoiner-docs-joint-friction.rst deleted file mode 100644 index 4b7e63eeb995..000000000000 --- a/source/isaaclab/changelog.d/antoiner-docs-joint-friction.rst +++ /dev/null @@ -1,4 +0,0 @@ -Fixed -^^^^^ - -* Fixed :class:`~isaaclab.assets.Articulation` joint friction API docs to clarify backend-specific semantics. diff --git a/source/isaaclab/changelog.d/antoiner-docs-sensor-updates.rst b/source/isaaclab/changelog.d/antoiner-docs-sensor-updates.rst deleted file mode 100644 index fd8e62a260cb..000000000000 --- a/source/isaaclab/changelog.d/antoiner-docs-sensor-updates.rst +++ /dev/null @@ -1,8 +0,0 @@ -Fixed -^^^^^ - -* Fixed the sensor overview documentation to include - :class:`~isaaclab.sensors.Pva` and - :class:`~isaaclab.sensors.JointWrenchSensor`. -* Fixed the PVA sensor demo to align front-foot sensor names with their prim - paths. diff --git a/source/isaaclab/changelog.d/antoiner-fix-from-files-windows-filelock.rst b/source/isaaclab/changelog.d/antoiner-fix-from-files-windows-filelock.rst deleted file mode 100644 index 3ceaeab12231..000000000000 --- a/source/isaaclab/changelog.d/antoiner-fix-from-files-windows-filelock.rst +++ /dev/null @@ -1,12 +0,0 @@ -Fixed -^^^^^ - -* Fixed :mod:`isaaclab.sim.spawners.from_files` failing to import on Windows - due to an unconditional ``import fcntl`` (Unix-only). The distributed-rank - USD spawn lock now uses :class:`filelock.FileLock`, which works on both - Windows and POSIX. - -Changed -^^^^^^^ - -* Added :mod:`filelock` to ``isaaclab`` install requirements. diff --git a/source/isaaclab/changelog.d/jichuanh-fix-warp-intersphinx.rst b/source/isaaclab/changelog.d/jichuanh-fix-warp-intersphinx.rst deleted file mode 100644 index 7aa72335f9e1..000000000000 --- a/source/isaaclab/changelog.d/jichuanh-fix-warp-intersphinx.rst +++ /dev/null @@ -1,5 +0,0 @@ -Fixed -^^^^^ - -* Fixed Sphinx docs build failing due to ``https://nvidia.github.io/warp/objects.inv`` returning 404. - Pinned the ``warp`` intersphinx mapping to ``/stable/``, which is where the inventory now lives. diff --git a/source/isaaclab/changelog.d/malesiani-ovphysx-04-fixes.rst b/source/isaaclab/changelog.d/malesiani-ovphysx-04-fixes.rst deleted file mode 100644 index 8a3e0a90d796..000000000000 --- a/source/isaaclab/changelog.d/malesiani-ovphysx-04-fixes.rst +++ /dev/null @@ -1,5 +0,0 @@ -Fixed -^^^^^ - -* Fixed the sensor prim-deletion callback guard so the OvPhysX backend is not - treated as the Kit PhysX backend. diff --git a/source/isaaclab/changelog.d/my-nvbugs-2.rst b/source/isaaclab/changelog.d/my-nvbugs-2.rst deleted file mode 100644 index 29bc762d964d..000000000000 --- a/source/isaaclab/changelog.d/my-nvbugs-2.rst +++ /dev/null @@ -1,8 +0,0 @@ -Fixed -^^^^^ - -* Relaxed the ``starlette`` pin in :mod:`isaaclab` from ``==0.49.1`` to - ``>=0.46.0,<0.50`` so installs of ``isaaclab[isaacsim,all]==3.0.0`` - alongside ``isaacsim==6.0.0.0`` resolve cleanly. The transitive pin - from ``isaacsim-kernel`` -> ``fastapi==0.117.1`` requires - ``starlette<0.49.0``; the previous exact pin was mutually exclusive. diff --git a/source/isaaclab/changelog.d/pbarejko-add-seed-to-math-module.rst b/source/isaaclab/changelog.d/pbarejko-add-seed-to-math-module.rst deleted file mode 100644 index 885c962d90b2..000000000000 --- a/source/isaaclab/changelog.d/pbarejko-add-seed-to-math-module.rst +++ /dev/null @@ -1,4 +0,0 @@ -Fixed -^^^^^ - -* Certain functions in test_math were failing non deterministically. This was caused by not setting seed values. diff --git a/source/isaaclab/changelog.d/pr-5423-state-observation-mdp.rst b/source/isaaclab/changelog.d/pr-5423-state-observation-mdp.rst deleted file mode 100644 index 62193bc0796f..000000000000 --- a/source/isaaclab/changelog.d/pr-5423-state-observation-mdp.rst +++ /dev/null @@ -1,6 +0,0 @@ -Changed -^^^^^^^ - -* Changed the Pink IK task-space action base link frame lookup to read direct - body link pose data instead of slicing packed body link state. No user - migration is required. diff --git a/source/isaaclab/config/extension.toml b/source/isaaclab/config/extension.toml index ce77d89f4c45..98d55ac40369 100644 --- a/source/isaaclab/config/extension.toml +++ b/source/isaaclab/config/extension.toml @@ -1,7 +1,7 @@ [package] # Note: Semantic Versioning is used: https://semver.org/ -version = "4.8.0" +version = "4.8.1" # Description title = "Isaac Lab framework for Robot Learning" diff --git a/source/isaaclab/docs/CHANGELOG.rst b/source/isaaclab/docs/CHANGELOG.rst index 152979d60df4..dda10e77f1f4 100644 --- a/source/isaaclab/docs/CHANGELOG.rst +++ b/source/isaaclab/docs/CHANGELOG.rst @@ -1,6 +1,44 @@ Changelog --------- +4.8.1 (2026-05-09) +~~~~~~~~~~~~~~~~~~ + +Changed +^^^^^^^ + +* Changed the Pink IK task-space action base link frame lookup to read direct + body link pose data instead of slicing packed body link state. No user + migration is required. +* Added :mod:`filelock` to ``isaaclab`` install requirements. + +Fixed +^^^^^ + +* Fixed :class:`~isaaclab.assets.Articulation` joint friction API docs to clarify backend-specific semantics. +* Fixed :class:`~isaaclab.envs.mdp.actions.PinkInverseKinematicsAction` + base link pose reads to avoid deprecated body link state access. +* Fixed the sensor overview documentation to include + :class:`~isaaclab.sensors.Pva` and + :class:`~isaaclab.sensors.JointWrenchSensor`. +* Fixed the PVA sensor demo to align front-foot sensor names with their prim + paths. +* Fixed Sphinx docs build failing due to ``https://nvidia.github.io/warp/objects.inv`` returning 404. + Pinned the ``warp`` intersphinx mapping to ``/stable/``, which is where the inventory now lives. +* Fixed the sensor prim-deletion callback guard so the OvPhysX backend is not + treated as the Kit PhysX backend. +* Relaxed the ``starlette`` pin in :mod:`isaaclab` from ``==0.49.1`` to + ``>=0.46.0,<0.50`` so installs of ``isaaclab[isaacsim,all]==3.0.0`` + alongside ``isaacsim==6.0.0.0`` resolve cleanly. The transitive pin + from ``isaacsim-kernel`` -> ``fastapi==0.117.1`` requires + ``starlette<0.49.0``; the previous exact pin was mutually exclusive. +* Fixed :mod:`isaaclab.sim.spawners.from_files` failing to import on Windows + due to an unconditional ``import fcntl`` (Unix-only). The distributed-rank + USD spawn lock now uses :class:`filelock.FileLock`, which works on both + Windows and POSIX. +* Certain functions in test_math were failing non deterministically. This was caused by not setting seed values. + + 4.8.0 (2026-05-08) ~~~~~~~~~~~~~~~~~~ diff --git a/source/isaaclab_contrib/changelog.d/pr-5410-task-deprecation-warning-cleanup.rst b/source/isaaclab_contrib/changelog.d/pr-5410-task-deprecation-warning-cleanup.rst deleted file mode 100644 index 9a8805b42e1d..000000000000 --- a/source/isaaclab_contrib/changelog.d/pr-5410-task-deprecation-warning-cleanup.rst +++ /dev/null @@ -1,6 +0,0 @@ -Changed -^^^^^^^ - -* Updated TacSL visuotactile sensor camera configuration and examples to use - :class:`~isaaclab.sensors.CameraCfg` and :class:`~isaaclab.sensors.Camera` - instead of deprecated tiled-camera aliases. diff --git a/source/isaaclab_contrib/config/extension.toml b/source/isaaclab_contrib/config/extension.toml index 7fd2b5d139e5..0fba6e220442 100644 --- a/source/isaaclab_contrib/config/extension.toml +++ b/source/isaaclab_contrib/config/extension.toml @@ -1,6 +1,6 @@ [package] # Semantic Versioning is used: https://semver.org/ -version = "0.3.0" +version = "0.3.1" # Description title = "Isaac Lab External Contributions" diff --git a/source/isaaclab_contrib/docs/CHANGELOG.rst b/source/isaaclab_contrib/docs/CHANGELOG.rst index 721c705a5981..ff3fa5a2a96a 100644 --- a/source/isaaclab_contrib/docs/CHANGELOG.rst +++ b/source/isaaclab_contrib/docs/CHANGELOG.rst @@ -1,6 +1,17 @@ Changelog --------- +0.3.1 (2026-05-09) +~~~~~~~~~~~~~~~~~~ + +Changed +^^^^^^^ + +* Updated TacSL visuotactile sensor camera configuration and examples to use + :class:`~isaaclab.sensors.CameraCfg` and :class:`~isaaclab.sensors.Camera` + instead of deprecated tiled-camera aliases. + + 0.3.0 (2026-02-13) ~~~~~~~~~~~~~~~~~~ diff --git a/source/isaaclab_newton/changelog.d/antoiner-backend-deprecation-warning-cleanup.rst b/source/isaaclab_newton/changelog.d/antoiner-backend-deprecation-warning-cleanup.rst deleted file mode 100644 index 2fd8df763f82..000000000000 --- a/source/isaaclab_newton/changelog.d/antoiner-backend-deprecation-warning-cleanup.rst +++ /dev/null @@ -1,6 +0,0 @@ -Fixed -^^^^^ - -* Fixed :class:`~isaaclab_newton.sensors.contact_sensor.ContactSensor` to use - current Newton contact sensor API names, removing deprecation warnings from - Newton contact sensor test runs. diff --git a/source/isaaclab_newton/changelog.d/antoiner-docs-joint-friction.rst b/source/isaaclab_newton/changelog.d/antoiner-docs-joint-friction.rst deleted file mode 100644 index e84764b739c9..000000000000 --- a/source/isaaclab_newton/changelog.d/antoiner-docs-joint-friction.rst +++ /dev/null @@ -1,5 +0,0 @@ -Fixed -^^^^^ - -* Fixed :class:`~isaaclab_newton.assets.Articulation` joint friction docs to identify Newton friction as a force or - torque value instead of a unitless coefficient. diff --git a/source/isaaclab_newton/changelog.d/antoiner-fix-fk-invalidation.rst b/source/isaaclab_newton/changelog.d/antoiner-fix-fk-invalidation.rst deleted file mode 100644 index e3f16a0a8893..000000000000 --- a/source/isaaclab_newton/changelog.d/antoiner-fix-fk-invalidation.rst +++ /dev/null @@ -1,6 +0,0 @@ -Fixed -^^^^^ - -* Fixed stale Newton forward-kinematics state after explicit pose writes so - downstream collision queries and :attr:`~isaaclab_newton.assets.RigidObjectData.body_link_pose_w` - reads use updated transforms. diff --git a/source/isaaclab_newton/changelog.d/disable-articulation-sim-ci.skip b/source/isaaclab_newton/changelog.d/disable-articulation-sim-ci.skip deleted file mode 100644 index e69de29bb2d1..000000000000 diff --git a/source/isaaclab_newton/config/extension.toml b/source/isaaclab_newton/config/extension.toml index 8ddb2526072e..0a55aaddb353 100644 --- a/source/isaaclab_newton/config/extension.toml +++ b/source/isaaclab_newton/config/extension.toml @@ -1,7 +1,7 @@ [package] # Note: Semantic Versioning is used: https://semver.org/ -version = "0.7.0" +version = "0.7.1" # Description title = "Newton simulation interfaces for IsaacLab core package" diff --git a/source/isaaclab_newton/docs/CHANGELOG.rst b/source/isaaclab_newton/docs/CHANGELOG.rst index afde5c8d2ec5..a472bf0643c6 100644 --- a/source/isaaclab_newton/docs/CHANGELOG.rst +++ b/source/isaaclab_newton/docs/CHANGELOG.rst @@ -1,6 +1,22 @@ Changelog --------- +0.7.1 (2026-05-09) +~~~~~~~~~~~~~~~~~~ + +Fixed +^^^^^ + +* Fixed :class:`~isaaclab_newton.assets.Articulation` joint friction docs to identify Newton friction as a force or + torque value instead of a unitless coefficient. +* Fixed :class:`~isaaclab_newton.sensors.contact_sensor.ContactSensor` to use + current Newton contact sensor API names, removing deprecation warnings from + Newton contact sensor test runs. +* Fixed stale Newton forward-kinematics state after explicit pose writes so + downstream collision queries and :attr:`~isaaclab_newton.assets.RigidObjectData.body_link_pose_w` + reads use updated transforms. + + 0.7.0 (2026-05-08) ~~~~~~~~~~~~~~~~~~ diff --git a/source/isaaclab_ov/changelog.d/huidongc-ovrtx-keep-system-alive.rst b/source/isaaclab_ov/changelog.d/huidongc-ovrtx-keep-system-alive.rst deleted file mode 100644 index 834776759402..000000000000 --- a/source/isaaclab_ov/changelog.d/huidongc-ovrtx-keep-system-alive.rst +++ /dev/null @@ -1,6 +0,0 @@ -Fixed -^^^^^ - -* Set ``keep_system_alive=True`` on the internal OVRTX ``RendererConfig`` in - :class:`~isaaclab_ov.renderers.ovrtx_renderer.OVRTXRenderer` so the renderer - system is not torn down prematurely during pytest sessions. diff --git a/source/isaaclab_ov/changelog.d/pbarejko-init-warp.rst b/source/isaaclab_ov/changelog.d/pbarejko-init-warp.rst deleted file mode 100644 index 413bfe794f05..000000000000 --- a/source/isaaclab_ov/changelog.d/pbarejko-init-warp.rst +++ /dev/null @@ -1,4 +0,0 @@ -Fixed -^^^^^ - -* Initialize Warp runtime for OvRTX renderer. diff --git a/source/isaaclab_ov/config/extension.toml b/source/isaaclab_ov/config/extension.toml index 63cda50eb5c0..7bc51bfb5e75 100644 --- a/source/isaaclab_ov/config/extension.toml +++ b/source/isaaclab_ov/config/extension.toml @@ -1,5 +1,5 @@ [package] -version = "0.1.5" +version = "0.1.6" title = "Omniverse renderers for IsaacLab" description = "Extension providing Omniverse renderers (OVRTX, ovphysx, etc.) for tiled camera rendering." readme = "docs/README.md" diff --git a/source/isaaclab_ov/docs/CHANGELOG.rst b/source/isaaclab_ov/docs/CHANGELOG.rst index d1af152a61e5..d0ae068e08d9 100644 --- a/source/isaaclab_ov/docs/CHANGELOG.rst +++ b/source/isaaclab_ov/docs/CHANGELOG.rst @@ -1,6 +1,18 @@ Changelog --------- +0.1.6 (2026-05-09) +~~~~~~~~~~~~~~~~~~ + +Fixed +^^^^^ + +* Set ``keep_system_alive=True`` on the internal OVRTX ``RendererConfig`` in + :class:`~isaaclab_ov.renderers.ovrtx_renderer.OVRTXRenderer` so the renderer + system is not torn down prematurely during pytest sessions. +* Initialize Warp runtime for OvRTX renderer. + + 0.1.5 (2026-05-08) ~~~~~~~~~~~~~~~~~~ diff --git a/source/isaaclab_ovphysx/changelog.d/malesiani-ovphysx-04-fixes.rst b/source/isaaclab_ovphysx/changelog.d/malesiani-ovphysx-04-fixes.rst deleted file mode 100644 index 1708ee377f18..000000000000 --- a/source/isaaclab_ovphysx/changelog.d/malesiani-ovphysx-04-fixes.rst +++ /dev/null @@ -1,6 +0,0 @@ -Fixed -^^^^^ - -* Fixed OvPhysX articulation tensor reads and writes for ``ovphysx`` 0.4 - compatibility. -* Restored DirectGPU startup settings for OvPhysX GPU simulations. diff --git a/source/isaaclab_ovphysx/config/extension.toml b/source/isaaclab_ovphysx/config/extension.toml index 1e541402d828..1ad422a1df32 100644 --- a/source/isaaclab_ovphysx/config/extension.toml +++ b/source/isaaclab_ovphysx/config/extension.toml @@ -1,7 +1,7 @@ [package] # Note: Semantic Versioning is used: https://semver.org/ -version = "0.1.3" +version = "0.1.4" # Description title = "OvPhysX simulation interfaces for IsaacLab core package" diff --git a/source/isaaclab_ovphysx/docs/CHANGELOG.rst b/source/isaaclab_ovphysx/docs/CHANGELOG.rst index 8eef22620a69..cea22cdc70c5 100644 --- a/source/isaaclab_ovphysx/docs/CHANGELOG.rst +++ b/source/isaaclab_ovphysx/docs/CHANGELOG.rst @@ -1,6 +1,17 @@ Changelog --------- +0.1.4 (2026-05-09) +~~~~~~~~~~~~~~~~~~ + +Fixed +^^^^^ + +* Fixed OvPhysX articulation tensor reads and writes for ``ovphysx`` 0.4 + compatibility. +* Restored DirectGPU startup settings for OvPhysX GPU simulations. + + 0.1.3 (2026-05-08) ~~~~~~~~~~~~~~~~~~ diff --git a/source/isaaclab_physx/changelog.d/antoiner-backend-deprecation-warning-cleanup.rst b/source/isaaclab_physx/changelog.d/antoiner-backend-deprecation-warning-cleanup.rst deleted file mode 100644 index bdec42289b0d..000000000000 --- a/source/isaaclab_physx/changelog.d/antoiner-backend-deprecation-warning-cleanup.rst +++ /dev/null @@ -1,5 +0,0 @@ -Fixed -^^^^^ - -* Fixed PhysX backend tests to use current contact sensor and asset API names, - removing deprecation warnings from scoped test runs. diff --git a/source/isaaclab_physx/changelog.d/antoiner-docs-joint-friction.rst b/source/isaaclab_physx/changelog.d/antoiner-docs-joint-friction.rst deleted file mode 100644 index 652271d896b1..000000000000 --- a/source/isaaclab_physx/changelog.d/antoiner-docs-joint-friction.rst +++ /dev/null @@ -1,5 +0,0 @@ -Fixed -^^^^^ - -* Fixed :class:`~isaaclab_physx.assets.Articulation` joint friction docs to distinguish legacy coefficients from - PhysX 5 static and dynamic friction efforts. diff --git a/source/isaaclab_physx/changelog.d/disable-articulation-sim-ci.skip b/source/isaaclab_physx/changelog.d/disable-articulation-sim-ci.skip deleted file mode 100644 index e69de29bb2d1..000000000000 diff --git a/source/isaaclab_physx/config/extension.toml b/source/isaaclab_physx/config/extension.toml index 00264e1238ff..d630d9c945c8 100644 --- a/source/isaaclab_physx/config/extension.toml +++ b/source/isaaclab_physx/config/extension.toml @@ -1,7 +1,7 @@ [package] # Note: Semantic Versioning is used: https://semver.org/ -version = "0.6.1" +version = "0.6.2" # Description title = "PhysX simulation interfaces for IsaacLab core package" diff --git a/source/isaaclab_physx/docs/CHANGELOG.rst b/source/isaaclab_physx/docs/CHANGELOG.rst index bc487f3190ab..0220a659e721 100644 --- a/source/isaaclab_physx/docs/CHANGELOG.rst +++ b/source/isaaclab_physx/docs/CHANGELOG.rst @@ -1,6 +1,18 @@ Changelog --------- +0.6.2 (2026-05-09) +~~~~~~~~~~~~~~~~~~ + +Fixed +^^^^^ + +* Fixed :class:`~isaaclab_physx.assets.Articulation` joint friction docs to distinguish legacy coefficients from + PhysX 5 static and dynamic friction efforts. +* Fixed PhysX backend tests to use current contact sensor and asset API names, + removing deprecation warnings from scoped test runs. + + 0.6.1 (2026-05-08) ~~~~~~~~~~~~~~~~~~ diff --git a/source/isaaclab_tasks/changelog.d/huidongc-enable-ovrtx-rendering.skip b/source/isaaclab_tasks/changelog.d/huidongc-enable-ovrtx-rendering.skip deleted file mode 100644 index e69de29bb2d1..000000000000 diff --git a/source/isaaclab_tasks/changelog.d/malesiani-ovphysx-camera-cartpole.rst b/source/isaaclab_tasks/changelog.d/malesiani-ovphysx-camera-cartpole.rst deleted file mode 100644 index 5a352196a0ed..000000000000 --- a/source/isaaclab_tasks/changelog.d/malesiani-ovphysx-camera-cartpole.rst +++ /dev/null @@ -1,4 +0,0 @@ -Added -^^^^^ - -* Added the ``ovphysx`` physics preset to the cartpole camera presets task. diff --git a/source/isaaclab_tasks/changelog.d/pr-5410-task-deprecation-warning-cleanup.rst b/source/isaaclab_tasks/changelog.d/pr-5410-task-deprecation-warning-cleanup.rst deleted file mode 100644 index 6fd8e22e713f..000000000000 --- a/source/isaaclab_tasks/changelog.d/pr-5410-task-deprecation-warning-cleanup.rst +++ /dev/null @@ -1,8 +0,0 @@ -Changed -^^^^^^^ - -* Updated task camera configs and environments to use - :class:`~isaaclab.sensors.CameraCfg` and :class:`~isaaclab.sensors.Camera` - instead of deprecated tiled-camera aliases. -* Updated task state and write call sites to use explicit state properties and - indexed simulation write APIs. diff --git a/source/isaaclab_tasks/changelog.d/pr-5423-state-observation-mdp.rst b/source/isaaclab_tasks/changelog.d/pr-5423-state-observation-mdp.rst deleted file mode 100644 index 655f379a939a..000000000000 --- a/source/isaaclab_tasks/changelog.d/pr-5423-state-observation-mdp.rst +++ /dev/null @@ -1,21 +0,0 @@ -Added -^^^^^ - -* Added explicit GR1T2 and Unitree G1 pick-place robot link pose and velocity - MDP helpers as replacements for packed robot link state observations. - -Changed -^^^^^^^ - -* Changed Dexsuite orientation tracking rewards to read root link orientation - directly instead of slicing packed root state tensors. - -Deprecated -^^^^^^^^^^ - -* Deprecated - :func:`~isaaclab_tasks.manager_based.manipulation.pick_place.mdp.observations.get_all_robot_link_state` - in favor of - :func:`~isaaclab_tasks.manager_based.manipulation.pick_place.mdp.observations.get_all_robot_link_pose` - and - :func:`~isaaclab_tasks.manager_based.manipulation.pick_place.mdp.observations.get_all_robot_link_velocity`. diff --git a/source/isaaclab_tasks/config/extension.toml b/source/isaaclab_tasks/config/extension.toml index c797fcdb2cb9..486b9faccf4c 100644 --- a/source/isaaclab_tasks/config/extension.toml +++ b/source/isaaclab_tasks/config/extension.toml @@ -1,7 +1,7 @@ [package] # Note: Semantic Versioning is used: https://semver.org/ -version = "1.5.35" +version = "1.5.36" # Description title = "Isaac Lab Environments" diff --git a/source/isaaclab_tasks/docs/CHANGELOG.rst b/source/isaaclab_tasks/docs/CHANGELOG.rst index cc3f6a513120..3638b0aa6910 100644 --- a/source/isaaclab_tasks/docs/CHANGELOG.rst +++ b/source/isaaclab_tasks/docs/CHANGELOG.rst @@ -1,6 +1,38 @@ Changelog --------- +1.5.36 (2026-05-09) +~~~~~~~~~~~~~~~~~~~ + +Added +^^^^^ + +* Added explicit GR1T2 and Unitree G1 pick-place robot link pose and velocity + MDP helpers as replacements for packed robot link state observations. +* Added the ``ovphysx`` physics preset to the cartpole camera presets task. + +Changed +^^^^^^^ + +* Changed Dexsuite orientation tracking rewards to read root link orientation + directly instead of slicing packed root state tensors. +* Updated task camera configs and environments to use + :class:`~isaaclab.sensors.CameraCfg` and :class:`~isaaclab.sensors.Camera` + instead of deprecated tiled-camera aliases. +* Updated task state and write call sites to use explicit state properties and + indexed simulation write APIs. + +Deprecated +^^^^^^^^^^ + +* Deprecated + :func:`~isaaclab_tasks.manager_based.manipulation.pick_place.mdp.observations.get_all_robot_link_state` + in favor of + :func:`~isaaclab_tasks.manager_based.manipulation.pick_place.mdp.observations.get_all_robot_link_pose` + and + :func:`~isaaclab_tasks.manager_based.manipulation.pick_place.mdp.observations.get_all_robot_link_velocity`. + + 1.5.35 (2026-05-08) ~~~~~~~~~~~~~~~~~~~ From 4934cd0ce5a53b86342f32d89e5491016c841769 Mon Sep 17 00:00:00 2001 From: ooctipus Date: Sat, 9 May 2026 14:57:18 -0700 Subject: [PATCH 31/51] Fix Pink IK DAQP dependency checks (#5556) # Description Pink IK uses DAQP through `qpsolvers`, but the install-time dependency repair only verified that Pinocchio could be imported. In environments where `pin-pink` or `qpsolvers` is present but DAQP is missing, unregistered, or too old for `qpsolvers` warm-start arguments, `solve_ik(..., solver="daqp")` can fail and fall back to current joint targets. The controller then reports a misleading end-effector position error in `test_pink_ik.py`. This change makes the installer probe the full Pink IK stack: `pinocchio`, DAQP registration in `qpsolvers`, and the `daqp.solve` API shape required by current `qpsolvers` (`primal_start`). It also aligns the IsaacLab dependency pin with the compatible DAQP release, `daqp==0.8.5`. Runtime handling stays narrow: ordinary IK failures keep the existing fallback, while missing DAQP or the specific `primal_start` API mismatch is surfaced with an actionable install message instead of being swallowed as an IK fallback. The docs config also mocks `qpsolvers`, matching the existing docs treatment for optional Pink IK dependencies such as `pink` and `pinocchio`, so API docs can be built without the runtime solver stack installed. ## Type of change - Bug fix (non-breaking change which fixes an issue) ## Test Plan - `./isaaclab.sh -p -m py_compile source/isaaclab/isaaclab/cli/commands/install.py source/isaaclab/isaaclab/controllers/pink_ik/pink_ik.py source/isaaclab/setup.py docs/conf.py` - `./isaaclab.sh -p -c "import inspect, pinocchio, daqp, qpsolvers; assert 'daqp' in qpsolvers.available_solvers; assert 'primal_start' in inspect.signature(daqp.solve).parameters; print('pink ik dependency probe passed')"` - `./isaaclab.sh -p -c "..."` small monkeypatch check that `TypeError("solve() got an unexpected keyword argument 'primal_start'")` raises the new DAQP compatibility `RuntimeError` - `./isaaclab.sh -p -m pytest source/isaaclab/test/controllers/test_pink_ik.py::test_movement_types -k "GR1T2-Abs-v0 and stay_still" -q --tb=short -s -x` - `./isaaclab.sh -p -m pytest source/isaaclab/test/controllers/test_pink_ik.py -q --tb=short -x` (`23 passed, 1 skipped`) - `VIRTUAL_ENV=/home/zhengyuz/Projects/IsaacLab.wt/feature-heterogeneous_dexsuite/env_isaaclab PATH=/home/zhengyuz/Projects/IsaacLab.wt/feature-heterogeneous_dexsuite/env_isaaclab/bin:$PATH make current-docs` from `docs/` - `VIRTUAL_ENV=/home/zhengyuz/Projects/IsaacLab.wt/feature-heterogeneous_dexsuite/env_isaaclab ./isaaclab.sh -f` ## Screenshots N/A. ## Checklist - [x] I have read and understood the [contribution guidelines](https://isaac-sim.github.io/IsaacLab/main/source/refs/contributing.html) - [x] I have run the [`pre-commit` checks](https://pre-commit.com/) with `./isaaclab.sh --format` - [x] I have made corresponding changes to the documentation (N/A - docs config only) - [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 added a changelog fragment under `source//changelog.d/` for every touched package (do **not** edit `CHANGELOG.rst` or bump `extension.toml` -- CI handles that) - [x] I have added my name to the `CONTRIBUTORS.md` or my name already exists there --- docs/conf.py | 1 + .../changelog.d/fix-pink-ik-daqp-install.rst | 5 +++ .../isaaclab/isaaclab/cli/commands/install.py | 45 ++++++++++--------- .../isaaclab/controllers/pink_ik/pink_ik.py | 45 +++++++++++++------ source/isaaclab/setup.py | 2 +- 5 files changed, 63 insertions(+), 35 deletions(-) create mode 100644 source/isaaclab/changelog.d/fix-pink-ik-daqp-install.rst diff --git a/docs/conf.py b/docs/conf.py index d75475634e30..a52ff90d31cc 100644 --- a/docs/conf.py +++ b/docs/conf.py @@ -203,6 +203,7 @@ "toml", "pink", "pinocchio", + "qpsolvers", "nvidia.srl", "flatdict", "filelock", diff --git a/source/isaaclab/changelog.d/fix-pink-ik-daqp-install.rst b/source/isaaclab/changelog.d/fix-pink-ik-daqp-install.rst new file mode 100644 index 000000000000..e4d25c7ba957 --- /dev/null +++ b/source/isaaclab/changelog.d/fix-pink-ik-daqp-install.rst @@ -0,0 +1,5 @@ +Fixed +^^^^^ + +* Fixed Pink IK setup checks to reinstall and report the required ``daqp`` + solver when it is missing or incompatible. diff --git a/source/isaaclab/isaaclab/cli/commands/install.py b/source/isaaclab/isaaclab/cli/commands/install.py index ba9735b92a6d..46125ae46f1e 100644 --- a/source/isaaclab/isaaclab/cli/commands/install.py +++ b/source/isaaclab/isaaclab/cli/commands/install.py @@ -159,22 +159,22 @@ def _maybe_uninstall_prebundled_torch( ) -# Pinocchio stack required by isaaclab.controllers.pink_ik. Installed via the cmeel -# ``pin`` wheel, which provides the ``pinocchio`` Python module under +# Dependency stack required by isaaclab.controllers.pink_ik. Pinocchio is installed +# via the cmeel ``pin`` wheel, which provides the ``pinocchio`` Python module under # ``cmeel.prefix/lib/python3.12/site-packages/`` and registers it on sys.path via a -# ``cmeel.pth`` hook. -_PINOCCHIO_STACK = ("pin", "pin-pink==3.1.0", "daqp==0.7.2") +# ``cmeel.pth`` hook. DAQP provides the QP solver selected by the Pink IK controller. +_PINK_IK_STACK = ("pin", "pin-pink==3.1.0", "daqp==0.8.5") -def _ensure_pinocchio_installed(python_exe: str, pip_cmd: list[str], *, probe_env: dict[str, str]) -> None: - """Ensure ``pinocchio`` is importable, force-installing the cmeel pin stack if not. +def _ensure_pink_ik_dependencies_installed(python_exe: str, pip_cmd: list[str], *, probe_env: dict[str, str]) -> None: + """Ensure the Pink IK dependency stack is importable, force-installing it if not. Recent Isaac Sim base images preinstall ``pin-pink`` into the kit's bundled ``site-packages`` without its ``pin`` (cmeel pinocchio) dependency. Pip then treats the ``pin-pink`` requirement as satisfied and never resolves the - transitive ``pin`` dep, leaving ``import pinocchio`` broken. This probes - for ``pinocchio`` at runtime and force-installs the cmeel stack when needed - so the pink IK controller and its tests work out of the box. + transitive ``pin`` dep, leaving ``import pinocchio`` broken. This checks + the runtime dependencies and force-installs the cmeel stack when needed so + the pink IK controller and its tests work out of the box. Only runs on Linux x86_64 / aarch64 — the same platforms that have pinocchio listed in :mod:`isaaclab`'s ``setup.py`` install requirements. @@ -194,7 +194,13 @@ def _ensure_pinocchio_installed(python_exe: str, pip_cmd: list[str], *, probe_en return probe_result = run_command( - [python_exe, "-c", "import pinocchio"], + [ + python_exe, + "-c", + "import inspect, pinocchio, daqp, qpsolvers; " + "assert 'daqp' in qpsolvers.available_solvers; " + "assert 'primal_start' in inspect.signature(daqp.solve).parameters", + ], env=probe_env, check=False, capture_output=True, @@ -203,19 +209,16 @@ def _ensure_pinocchio_installed(python_exe: str, pip_cmd: list[str], *, probe_en if probe_result.returncode == 0: return - print_info( - "``import pinocchio`` failed — the kit-bundled ``pin-pink`` likely shipped without its" - " ``pin`` dep. Force-installing the cmeel pinocchio stack." - ) + print_info("Pink IK dependency probe failed. Force-installing the cmeel pinocchio and DAQP stack.") install_result = run_command( - pip_cmd + ["install", "--upgrade", "--force-reinstall", *_PINOCCHIO_STACK], + pip_cmd + ["install", "--upgrade", "--force-reinstall", *_PINK_IK_STACK], check=False, ) if install_result.returncode != 0: print_warning( - "Force-installing the cmeel pinocchio stack failed (returncode " + "Force-installing the cmeel pinocchio and DAQP stack failed (returncode " f"{install_result.returncode}). The pink IK controller and its tests will not be" - " usable until ``pin pin-pink==3.1.0 daqp==0.7.2`` is installed manually." + " usable until ``pin pin-pink==3.1.0 daqp==0.8.5`` is installed manually." ) @@ -735,10 +738,10 @@ def command_install(install_type: str = "all") -> None: # Can prevent that from happening. _ensure_cuda_torch() - # Ensure ``pinocchio`` is actually importable. The kit-bundled ``pin-pink`` in recent - # Isaac Sim images ships without its cmeel ``pin`` dependency, so the transitive - # requirement from ``pip install -e source/isaaclab`` can be silently skipped. - _ensure_pinocchio_installed(python_exe, pip_cmd, probe_env=probe_env) + # Ensure Pink IK's runtime dependencies are actually importable. The kit-bundled + # ``pin-pink`` in recent Isaac Sim images can cause transitive dependencies from + # ``pip install -e source/isaaclab`` to be silently skipped. + _ensure_pink_ik_dependencies_installed(python_exe, pip_cmd, probe_env=probe_env) # Repoint prebundled packages in Isaac Sim to the environment's copies so # the active venv/conda versions are always loaded regardless of PYTHONPATH diff --git a/source/isaaclab/isaaclab/controllers/pink_ik/pink_ik.py b/source/isaaclab/isaaclab/controllers/pink_ik/pink_ik.py index d1162b480910..1520afdb0177 100644 --- a/source/isaaclab/isaaclab/controllers/pink_ik/pink_ik.py +++ b/source/isaaclab/isaaclab/controllers/pink_ik/pink_ik.py @@ -20,6 +20,7 @@ import torch from pink import solve_ik from pink.tasks import Task +from qpsolvers.exceptions import SolverNotFound from isaaclab.assets import ArticulationCfg from isaaclab.controllers import utils as controller_utils @@ -34,6 +35,9 @@ from .pink_ik_cfg import PinkIKControllerCfg +_QP_SOLVER = "daqp" + + class PinkIKController: """Integration of Pink IK controller with Isaac Lab. @@ -240,30 +244,45 @@ def compute( # Update Pink's robot configuration with the current joint positions self.pink_configuration.update(joint_positions_pink) + def _return_current_joint_positions(error: Exception) -> torch.Tensor: + if self.cfg.show_ik_warnings: + print( + "Warning: IK quadratic solver could not find a solution! Did not update the target joint" + f" positions.\nError: {error}" + ) + + if self.cfg.xr_enabled: + from isaaclab.ui.xr_widgets import XRVisualization + + XRVisualization.push_event("ik_error", {"error": error}) + return torch.tensor(curr_controlled_joint_pos, device=self.device, dtype=torch.float32) + # Solve IK using Pink's solver try: velocity = solve_ik( self.pink_configuration, self._variable_input_tasks + self._fixed_input_tasks, dt, - solver="daqp", + solver=_QP_SOLVER, safety_break=self.cfg.fail_on_joint_limit_violation, ) assert not np.isnan(velocity).any(), "Solution to IK contains NaN." joint_angle_changes = velocity * dt + except SolverNotFound as e: + raise RuntimeError( + f"Pink IK requires the '{_QP_SOLVER}' QP solver. Install the Pink IK stack with " + "``./isaaclab.sh -i`` or manually install ``pin pin-pink==3.1.0 daqp==0.8.5``." + ) from e + except TypeError as e: + if "primal_start" in str(e): + raise RuntimeError( + "Pink IK requires a DAQP version compatible with qpsolvers warm-start arguments. " + "Install the Pink IK stack with ``./isaaclab.sh -i`` or manually install " + "``pin pin-pink==3.1.0 daqp==0.8.5``." + ) from e + return _return_current_joint_positions(e) except (AssertionError, Exception) as e: - # Print warning and return the current joint positions as the target - if self.cfg.show_ik_warnings: - print( - "Warning: IK quadratic solver could not find a solution! Did not update the target joint" - f" positions.\nError: {e}" - ) - - if self.cfg.xr_enabled: - from isaaclab.ui.xr_widgets import XRVisualization - - XRVisualization.push_event("ik_error", {"error": e}) - return torch.tensor(curr_controlled_joint_pos, device=self.device, dtype=torch.float32) + return _return_current_joint_positions(e) # Reorder the joint angle changes back to Isaac Lab conventions joint_vel_isaac_lab = torch.tensor( diff --git a/source/isaaclab/setup.py b/source/isaaclab/setup.py index d56f73a34225..cfced25a24aa 100644 --- a/source/isaaclab/setup.py +++ b/source/isaaclab/setup.py @@ -69,7 +69,7 @@ # required by isaaclab.isaaclab.controllers.pink_ik f"pin ; platform_system == 'Linux' and ({SUPPORTED_ARCHS_ARM})", f"pin-pink==3.1.0 ; platform_system == 'Linux' and ({SUPPORTED_ARCHS_ARM})", - f"daqp==0.7.2 ; platform_system == 'Linux' and ({SUPPORTED_ARCHS_ARM})", + f"daqp==0.8.5 ; platform_system == 'Linux' and ({SUPPORTED_ARCHS_ARM})", ] # Adds OpenUSD dependencies based on architecture for Kit less mode. INSTALL_REQUIRES += [ From 63b1257f9c026a9e0f62ffd59aaa2dbe1e396202 Mon Sep 17 00:00:00 2001 From: "isaaclab-bot[bot]" <282401363+isaaclab-bot[bot]@users.noreply.github.com> Date: Sun, 10 May 2026 06:03:58 +0000 Subject: [PATCH 32/51] [CI][Auto Version Bump] Compile changelog fragments (schedule) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Bumped packages: - isaaclab: 4.8.1 → 4.8.2 --- .../isaaclab/changelog.d/fix-pink-ik-daqp-install.rst | 5 ----- source/isaaclab/config/extension.toml | 2 +- source/isaaclab/docs/CHANGELOG.rst | 10 ++++++++++ 3 files changed, 11 insertions(+), 6 deletions(-) delete mode 100644 source/isaaclab/changelog.d/fix-pink-ik-daqp-install.rst diff --git a/source/isaaclab/changelog.d/fix-pink-ik-daqp-install.rst b/source/isaaclab/changelog.d/fix-pink-ik-daqp-install.rst deleted file mode 100644 index e4d25c7ba957..000000000000 --- a/source/isaaclab/changelog.d/fix-pink-ik-daqp-install.rst +++ /dev/null @@ -1,5 +0,0 @@ -Fixed -^^^^^ - -* Fixed Pink IK setup checks to reinstall and report the required ``daqp`` - solver when it is missing or incompatible. diff --git a/source/isaaclab/config/extension.toml b/source/isaaclab/config/extension.toml index 98d55ac40369..338691cd0c00 100644 --- a/source/isaaclab/config/extension.toml +++ b/source/isaaclab/config/extension.toml @@ -1,7 +1,7 @@ [package] # Note: Semantic Versioning is used: https://semver.org/ -version = "4.8.1" +version = "4.8.2" # Description title = "Isaac Lab framework for Robot Learning" diff --git a/source/isaaclab/docs/CHANGELOG.rst b/source/isaaclab/docs/CHANGELOG.rst index dda10e77f1f4..186d00855ac4 100644 --- a/source/isaaclab/docs/CHANGELOG.rst +++ b/source/isaaclab/docs/CHANGELOG.rst @@ -1,6 +1,16 @@ Changelog --------- +4.8.2 (2026-05-10) +~~~~~~~~~~~~~~~~~~ + +Fixed +^^^^^ + +* Fixed Pink IK setup checks to reinstall and report the required ``daqp`` + solver when it is missing or incompatible. + + 4.8.1 (2026-05-09) ~~~~~~~~~~~~~~~~~~ From 6dedbb7c2b1e8430a43479c7e14791c25c85c538 Mon Sep 17 00:00:00 2001 From: ooctipus Date: Sun, 10 May 2026 00:37:08 -0700 Subject: [PATCH 33/51] Refactor cloning around cfg-driven ClonePlan (#5528) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit # Description This PR a lot simplify cloner logic: Refactors scene cloning so `InteractiveScene` builds a `ClonePlan` directly from asset configuration, rewrites spawner configs to spawn representative sources in their selected environment paths, and then replicates directly from those sources to the remaining destinations. This removes the previous template round trip and hard-deletes `clone_from_template`. This also updates the cloner API around `CloneCfg` and `make_clone_plan`, adds explicit `spawn_paths` support for multi-asset spawners, tightens rigid object collection spawning invariants, and refreshes docs, tests, and changelog coverage for the new planning flow. Fixes # N/A Dependencies: none. ## Type of change - New feature (non-breaking change which adds functionality) - Breaking change (existing functionality will not work without user modification) - Documentation update ## Screenshots N/A. ## Test plan Focused tests were run individually while developing this branch: - `source/isaaclab/test/scene/test_interactive_scene.py` - `source/isaaclab/test/sim/test_cloner.py` - `source/isaaclab/test/sim/test_spawn_wrappers.py` - `source/isaaclab_physx/test/sim/test_cloner.py` - `py_compile` checks for touched Python modules ## Checklist - [x] I have read and understood the [contribution guidelines](https://isaac-sim.github.io/IsaacLab/main/source/refs/contributing.html) - [x] I have run the [`pre-commit` checks](https://pre-commit.com/) with `./isaaclab.sh --format` - [x] I have made corresponding changes to the documentation - [x] My changes generate no new warnings - [x] I have added tests that prove my fix is effective or that my feature works - [x] I have added a changelog fragment under `source//changelog.d/` for every touched package (do **not** edit `CHANGELOG.rst` or bump `extension.toml` — CI handles that) - [x] I have added my name to the `CONTRIBUTORS.md` or my name already exists there --------- Co-authored-by: Cursor --- docs/source/how-to/cloning.rst | 476 +++++++++++------- .../multi_backend_architecture.rst | 2 +- .../clone-plan-visualizer-cleanup.minor.rst | 35 ++ .../octi-cloner_ordering.major.rst | 29 ++ source/isaaclab/isaaclab/cloner/__init__.pyi | 6 +- source/isaaclab/isaaclab/cloner/clone_plan.py | 38 +- source/isaaclab/isaaclab/cloner/cloner_cfg.py | 48 +- .../isaaclab/isaaclab/cloner/cloner_utils.py | 144 +----- .../isaaclab/scene/interactive_scene.py | 249 +++++---- .../isaaclab/sim/simulation_context.py | 23 +- .../sim/spawners/wrappers/wrappers.py | 48 +- .../sim/spawners/wrappers/wrappers_cfg.py | 16 + .../test/scene/test_interactive_scene.py | 266 ++++++++-- source/isaaclab/test/sim/test_cloner.py | 66 +-- ...scene_data_provider_visualizer_contract.py | 120 ++--- .../test_simulation_context_visualizers.py | 2 +- .../isaaclab/test/sim/test_spawn_wrappers.py | 35 ++ .../changelog.d/octi-cloner_ordering.rst | 5 + .../rigid_object_collection.py | 3 +- .../cloner/newton_replicate.py | 20 +- .../changelog.d/octi-cloner_ordering.skip | 0 .../cloner/ovphysx_replicate.py | 12 +- .../changelog.d/octi-cloner_ordering.rst | 5 + .../rigid_object_collection.py | 3 +- .../isaaclab_physx/cloner/physx_replicate.py | 6 +- .../physx_scene_data_provider.py | 75 +-- source/isaaclab_physx/test/sim/test_cloner.py | 60 ++- 27 files changed, 1055 insertions(+), 737 deletions(-) create mode 100644 source/isaaclab/changelog.d/clone-plan-visualizer-cleanup.minor.rst create mode 100644 source/isaaclab/changelog.d/octi-cloner_ordering.major.rst create mode 100644 source/isaaclab_newton/changelog.d/octi-cloner_ordering.rst create mode 100644 source/isaaclab_ovphysx/changelog.d/octi-cloner_ordering.skip create mode 100644 source/isaaclab_physx/changelog.d/octi-cloner_ordering.rst diff --git a/docs/source/how-to/cloning.rst b/docs/source/how-to/cloning.rst index bad0ff8a5026..ce513cd29497 100644 --- a/docs/source/how-to/cloning.rst +++ b/docs/source/how-to/cloning.rst @@ -5,213 +5,347 @@ Cloning Environments .. currentmodule:: isaaclab -Isaac Lab uses a **template-based cloning** system to efficiently replicate environments for -parallel simulation. Instead of authoring each environment individually on the USD stage, -you define a single template and let the cloner stamp out copies with optional per-environment -variation. +Isaac Lab creates many parallel environments by spawning representative source prims and +then cloning them to the remaining environment paths. This guide starts with direct cloning +so the primitive contract is clear, then shows how :class:`~isaaclab.cloner.ClonePlan` and +:class:`~isaaclab.scene.InteractiveScene` build on top of that contract. -This guide covers the cloning API and how to customize environment creation. +.. contents:: On this page + :local: + :depth: 2 -How Cloning Works ------------------ -The cloning pipeline has three stages: +Direct Cloning +-------------- -1. **Template authoring** -- You place one or more *prototype* prims under a template root - (default ``/World/template``). Each prototype is a variant of an asset (e.g., different robot - configurations or object meshes). +Use direct cloning for custom scene pipelines, tooling, or tests that need explicit +control over the replication contract. -2. **Clone plan** -- The cloner discovers prototypes, enumerates all possible combinations (one - per prototype group), and assigns a combination to each environment using a *strategy*. +The cloner operates on three pieces of data: -3. **Replication** -- The selected prototypes are replicated to per-environment prim paths via - USD spec copying and physics-backend-specific replication. +1. **Source prims** that already exist on the stage. +2. **Destination templates** containing ``{}``, which is formatted with each environment id. +3. **A boolean mask** with shape ``[len(sources), num_envs]`` that selects which source + populates each environment. -Most users interact with cloning indirectly through -:class:`~isaaclab.scene.InteractiveScene`, which calls -:func:`~isaaclab.cloner.clone_from_template` during ``clone_environments()``. -For advanced use cases, you can call the cloning utilities directly. +The direct flow is: - -Basic Usage ------------ - -The simplest case is homogeneous cloning -- every environment gets the same assets: +1. Create the environment namespace prims. +2. Spawn representative source prims. +3. Call the physics replicate function for your backend. +4. Call :func:`~isaaclab.cloner.usd_replicate` with the same source-to-environment mapping. .. code-block:: python - from isaaclab.cloner import TemplateCloneCfg, clone_from_template - from isaaclab.sim import SimulationContext - - sim = SimulationContext() - stage = sim.stage + import torch - # Spawn a single prototype under the template root using a spawner import isaaclab.sim as sim_utils + from isaaclab.cloner import usd_replicate + from isaaclab_physx.cloner import physx_replicate - spawn_cfg = sim_utils.UsdFileCfg(usd_path="path/to/robot.usd") - spawn_cfg.func("/World/template/Robot/proto_asset_0", spawn_cfg) + num_envs = 128 + stage = sim_utils.get_current_stage() + env_ids = torch.arange(num_envs, device="cuda:0") - # Configure and clone - clone_cfg = TemplateCloneCfg(device=sim.cfg.device) - clone_from_template(stage, num_clones=128, template_clone_cfg=clone_cfg) + sim_utils.create_prim("/World/envs", "Xform") + for env_id in range(num_envs): + sim_utils.create_prim(f"/World/envs/env_{env_id}", "Xform") -This creates 128 environments at ``/World/envs/env_0`` through ``/World/envs/env_127``, -each containing a copy of the robot. + source = "/World/envs/env_0/Cube" + destination = "/World/envs/env_{}/Object" + cube_cfg = sim_utils.CuboidCfg(size=(0.5, 0.5, 0.5)) + cube_cfg.func(source, cube_cfg) -Configuration Reference ------------------------ + mask = torch.ones((1, num_envs), dtype=torch.bool, device="cuda:0") -:class:`~isaaclab.cloner.TemplateCloneCfg` controls the cloning behavior: + physx_replicate(stage, [source], [destination], env_ids, mask, device="cuda:0") + usd_replicate(stage, [source], [destination], env_ids, mask) -.. list-table:: - :header-rows: 1 - :widths: 25 15 60 +This creates one source cube at ``/World/envs/env_0/Cube`` and clones it to +``/World/envs/env_1/Object`` through ``/World/envs/env_127/Object``. When a source path is +the same as the destination for an environment, ``usd_replicate`` skips the self-copy. - * - Field - - Default - - Description - * - ``template_root`` - - ``"/World/template"`` - - Root path under which prototype prims are authored. - * - ``template_prototype_identifier`` - - ``"proto_asset"`` - - Name prefix used to discover prototype prims. The cloner finds all prims whose - base name starts with this identifier (e.g., ``proto_asset_0``, ``proto_asset_1``). - * - ``clone_regex`` - - ``"/World/envs/env_.*"`` - - Destination path template. The ``.*`` is replaced with the environment index. - * - ``clone_usd`` - - ``True`` - - Whether to replicate USD prim specs to destination paths. - * - ``clone_physics`` - - ``True`` - - Whether to perform physics-backend-specific replication. - * - ``physics_clone_fn`` - - ``None`` - - Backend-specific physics replication function. Set automatically by - :class:`~isaaclab.scene.InteractiveScene`. - * - ``visualizer_clone_fn`` - - ``None`` - - Optional callback to prebuild visualizer artifacts from the clone plan. - * - ``clone_strategy`` - - ``random`` - - Strategy function for assigning prototypes to environments. See - :ref:`cloning-strategies` below. - * - ``device`` - - ``"cpu"`` - - Torch device for mapping buffers. - * - ``clone_in_fabric`` - - ``False`` - - Enable cloning in Fabric (PhysX only, experimental). +Direct heterogeneous cloning uses the same API with more source rows. Each row in ``mask`` +selects the environments that receive the matching source. For example, this explicit mask +clones a cone into environments 0 and 2, and a sphere into environments 1 and 3: +.. code-block:: python -.. _cloning-strategies: + env_ids = torch.arange(4, device="cuda:0") + sources = ["/World/envs/env_0/Cone", "/World/envs/env_1/Sphere"] + destinations = ["/World/envs/env_{}/Object", "/World/envs/env_{}/Object"] -Cloning Strategies ------------------- + cone_cfg = sim_utils.ConeCfg(radius=0.25, height=0.5) + sphere_cfg = sim_utils.SphereCfg(radius=0.25) + cone_cfg.func(sources[0], cone_cfg) + sphere_cfg.func(sources[1], sphere_cfg) -When multiple prototypes exist in the template, the **clone strategy** determines which -prototype each environment receives. Isaac Lab provides two built-in strategies: + mask = torch.tensor([[True, False, True, False], [False, True, False, True]], dtype=torch.bool) -**Random** (default) + physx_replicate(stage, sources, destinations, env_ids, mask, device="cuda:0") + usd_replicate(stage, sources, destinations, env_ids, mask) -Each environment receives a randomly sampled prototype combination: +The mask above reads as: + +.. list-table:: + :header-rows: 1 + :widths: 15 40 20 25 + + * - Source row + - Source path + - Env ids + - Destination path + * - ``0`` + - ``/World/envs/env_0/Cone`` + - ``0, 2`` + - ``/World/envs/env_{}/Object`` + * - ``1`` + - ``/World/envs/env_1/Sphere`` + - ``1, 3`` + - ``/World/envs/env_{}/Object`` + +``usd_replicate`` copies parent paths before children and supports optional ``positions`` +and ``quaternions`` buffers. If ``positions`` is provided, it authors +``xformOp:translate`` on each destination using the environment id. The helper +:func:`~isaaclab.cloner.grid_transforms` creates the same grid layout used by +:class:`~isaaclab.scene.InteractiveScene`. .. code-block:: python - from isaaclab.cloner import TemplateCloneCfg, random + from isaaclab.cloner import grid_transforms - clone_cfg = TemplateCloneCfg( - clone_strategy=random, + positions, orientations = grid_transforms( + N=num_envs, + spacing=2.0, + up_axis="z", device="cuda:0", ) + usd_replicate(stage, [source], [destination], env_ids, mask, positions=positions) -This is useful for domain randomization and curriculum learning where you want diverse -environments. -**Sequential** +Clone Plans +----------- -Prototypes are assigned in round-robin order (``env_id % num_combinations``): +For one source row, passing ``sources``, ``destinations``, and ``mask`` by hand is simple. +For heterogeneous scenes, the mapping is easier to build with +:func:`~isaaclab.cloner.make_clone_plan`. -.. code-block:: python +:class:`~isaaclab.cloner.ClonePlan` stores the same flat contract used by direct cloning: - from isaaclab.cloner import TemplateCloneCfg, sequential +.. code-block:: text - clone_cfg = TemplateCloneCfg( - clone_strategy=sequential, - device="cuda:0", - ) + sources = [source_0, source_1, ...] + destinations = [destination_0, destination_1, ...] + clone_mask = bool tensor, shape [len(sources), num_envs] -This produces a deterministic, balanced distribution -- useful for reproducible experiments. +``clone_mask[i, j]`` is ``True`` when environment ``j`` should receive source row ``i``. +The same plan can be passed to USD replication, physics replication, and scene-data +providers. -**Custom strategies** can be written as any callable matching the signature -``(combinations: torch.Tensor, num_clones: int, device: str) -> torch.Tensor``, -where ``combinations`` has shape ``(num_combinations, num_groups)`` and the return -value has shape ``(num_clones, num_groups)``. +Homogeneous Plans +~~~~~~~~~~~~~~~~~ +In a homogeneous scene, every environment receives the same asset layout. The default plan +is: -Heterogeneous Environments --------------------------- +.. code-block:: text -To create environments with different assets, place multiple prototypes under the same -group in the template: + sources = ["/World/envs/env_0"] + destinations = ["/World/envs/env_{}"] + clone_mask = all True, shape [1, num_envs] -.. code-block:: python +This means the scene spawns everything for ``env_0`` and replicates that environment to +``env_1`` through ``env_N``. - # Spawn three different object prototypes under the same group - import isaaclab.sim as sim_utils +Heterogeneous Plans +~~~~~~~~~~~~~~~~~~~ - sim_utils.CuboidCfg(size=(0.5, 0.5, 0.5)).func( - "/World/template/Object/proto_asset_0", sim_utils.CuboidCfg(size=(0.5, 0.5, 0.5)) - ) - sim_utils.ConeCfg(radius=0.25, height=0.5).func( - "/World/template/Object/proto_asset_1", sim_utils.ConeCfg(radius=0.25, height=0.5) - ) - sim_utils.SphereCfg(radius=0.25).func( - "/World/template/Object/proto_asset_2", sim_utils.SphereCfg(radius=0.25) - ) +Heterogeneous cloning is used when different environments receive different prototypes. +For example, an object with three variants may have representative source prims at: + +.. code-block:: text - clone_cfg = TemplateCloneCfg( + /World/envs/env_0/Object + /World/envs/env_1/Object + /World/envs/env_2/Object + +These paths have the same leaf name because each variant will be cloned to +``/World/envs/env_{}/Object``, but their authored contents are different. For example, +``env_0/Object`` could be a cone, ``env_1/Object`` a cuboid, and ``env_2/Object`` a sphere. + +The plan maps those source rows to all environments: + +.. code-block:: python + + from isaaclab.cloner import make_clone_plan, sequential + + plan = make_clone_plan( + sources=[ + [ + "/World/envs/env_0/Object", + "/World/envs/env_1/Object", + "/World/envs/env_2/Object", + ] + ], + destinations=["/World/envs/env_{}/Object"], + num_clones=8, clone_strategy=sequential, device="cuda:0", ) - clone_from_template(stage, num_clones=128, template_clone_cfg=clone_cfg) - # env_0 gets Cuboid, env_1 gets Cone, env_2 gets Sphere, env_3 gets Cuboid, ... -When prototypes span multiple groups (e.g., different robots *and* different objects), -the cloner enumerates the Cartesian product of all groups and assigns combinations -using the selected strategy. + # source row used by env: 0, 1, 2, 0, 1, 2, 0, 1 +Direct code can use the plan exactly like the hand-written direct example: -Environment Positioning ------------------------ +.. code-block:: python + + physx_replicate(stage, plan.sources, plan.destinations, env_ids, plan.clone_mask, device="cuda:0") + usd_replicate(stage, plan.sources, plan.destinations, env_ids, plan.clone_mask) + +When variants span multiple groups, such as robot variants and object variants, +``make_clone_plan`` enumerates the Cartesian product of the groups and assigns one +combination per environment. Unused prototype rows may still appear in the plan with an +all-false mask row. + +.. _cloning-strategies: -Environments are arranged in a grid layout using :func:`~isaaclab.cloner.grid_transforms`: +Clone Strategies +~~~~~~~~~~~~~~~~ + +A clone strategy chooses prototype combinations for the environments: + +* :func:`~isaaclab.cloner.random` samples combinations randomly and is the default. +* :func:`~isaaclab.cloner.sequential` assigns combinations in round-robin order, which is + useful for reproducible tests and balanced coverage. + +Custom strategies are callables with this signature: .. code-block:: python - from isaaclab.cloner import grid_transforms + def my_strategy(combinations: torch.Tensor, num_clones: int, device: str) -> torch.Tensor: + ... - positions, orientations = grid_transforms( - N=128, # number of environments - spacing=2.0, # meters between neighbors - up_axis="Z", - device="cuda:0", - ) - # positions: (128, 3), orientations: (128, 4) identity quaternions +``combinations`` has shape ``[num_combinations, num_groups]`` and the return value must have +shape ``[num_clones, num_groups]``. + + +Common Workflow: ``InteractiveScene`` +------------------------------------- + +:class:`~isaaclab.scene.InteractiveScene` automates the direct cloning flow for task scenes. +It inspects scene configuration, builds a :class:`~isaaclab.cloner.ClonePlan`, rewrites +spawner paths to the representative sources, spawns those sources, runs physics and USD +replication, and filters inter-environment collisions for PhysX when configured. + +Put per-environment assets under ``{ENV_REGEX_NS}`` and global assets under normal USD +paths: + +.. code-block:: python + + import isaaclab.sim as sim_utils + from isaaclab.assets import AssetBaseCfg + from isaaclab.scene import InteractiveScene, InteractiveSceneCfg + from isaaclab.utils import configclass + from isaaclab_assets.robots.cartpole import CARTPOLE_CFG + + + @configclass + class MySceneCfg(InteractiveSceneCfg): + # Cloned once per environment. + robot = CARTPOLE_CFG.replace(prim_path="{ENV_REGEX_NS}/Robot") + + # Authored once globally, not cloned per environment. + light = AssetBaseCfg( + prim_path="/World/Light", + spawn=sim_utils.DistantLightCfg(intensity=3000.0), + ) + + + scene_cfg = MySceneCfg(num_envs=128, env_spacing=2.0, replicate_physics=True) + scene = InteractiveScene(cfg=scene_cfg) + +For heterogeneous scenes, use :class:`~isaaclab.sim.spawners.wrappers.MultiAssetSpawnerCfg` +or :class:`~isaaclab.sim.spawners.wrappers.MultiUsdFileCfg`. ``InteractiveScene`` assigns +representative source paths to the spawner and lets the clone strategy choose which +prototype each environment receives. See :doc:`multi_asset_spawning` for the asset +configuration details. -:class:`~isaaclab.scene.InteractiveScene` calls this automatically based on -``InteractiveSceneCfg.env_spacing``. +The most important scene options are on :class:`~isaaclab.scene.InteractiveSceneCfg`: +.. list-table:: + :header-rows: 1 + :widths: 25 15 60 -Collision Filtering -------------------- + * - Field + - Default + - When to change it + * - ``replicate_physics`` + - ``True`` + - Keep enabled for homogeneous environments and fast startup. Disable it when each + environment needs independently authored physics or USD randomization. + * - ``filter_collisions`` + - ``True`` + - Keep enabled for parallel RL so cloned environments do not collide with each other. + This is automatic for PhysX-backed scene cloning. + * - ``clone_in_fabric`` + - ``False`` + - Enables the PhysX Fabric cloning path for faster scene creation. Use USDRT for stage + inspection when Fabric cloning is enabled. -By default, assets in different environments can collide with each other. To prevent -cross-environment collisions (the typical setup for parallel RL), use -:func:`~isaaclab.cloner.filter_collisions`: + +Choosing an API +--------------- + +.. list-table:: + :header-rows: 1 + :widths: 25 45 30 + + * - Goal + - Recommended API + - Notes + * - Build a custom cloning pipeline + - :func:`~isaaclab.cloner.usd_replicate` and a backend physics replicate function + - Useful for tests, tooling, or advanced scene construction. + * - Build complex direct mappings + - :func:`~isaaclab.cloner.make_clone_plan` + - Produces the same ``sources``, ``destinations``, and ``clone_mask`` used by direct cloning. + * - Build normal task scenes + - :class:`~isaaclab.scene.InteractiveScene` + - Preferred path. Configure assets with ``{ENV_REGEX_NS}`` and let the scene clone them. + * - Randomize which asset each environment receives + - ``InteractiveScene`` with :class:`~isaaclab.sim.spawners.wrappers.MultiAssetSpawnerCfg` or + :class:`~isaaclab.sim.spawners.wrappers.MultiUsdFileCfg` + - See :doc:`multi_asset_spawning` for the asset configuration details. + * - Use Isaac Sim's ``GridCloner`` + - Isaac Sim API + - Isaac Lab's tested path is the ``isaaclab.cloner`` API described here. + + +Migrating From Template Cloning +------------------------------- + +The template-root discovery API has been removed. Replace +``clone_from_template(...)`` calls with explicit source prims plus +:func:`~isaaclab.cloner.make_clone_plan`, a backend physics replicate function, and +:func:`~isaaclab.cloner.usd_replicate`. Replace ``TemplateCloneCfg`` with +:class:`~isaaclab.cloner.CloneCfg` for execution settings such as clone strategy, +Fabric cloning, and backend replication. + + +Collision Filtering and Isolation +--------------------------------- + +Some prims, such as terrain, are intentionally shared across environments and should collide +with every environment. These are modeled as global collision paths. The workaround is only +the per-environment filtering: when cloning is fully isolated per world, cloned environments +should not collide with each other and no manual per-environment filter should be needed. +Some PhysX cloning paths still rely on USD collision groups for that isolation fallback. In +the scene workflow this is handled by ``InteractiveScene`` when ``filter_collisions=True`` +and the backend is PhysX. + +For direct PhysX usage, call :func:`~isaaclab.cloner.filter_collisions` after cloning if +per-environment isolation is not already provided by the cloning backend: .. code-block:: python @@ -221,47 +355,43 @@ cross-environment collisions (the typical setup for parallel RL), use stage=stage, physicsscene_path="/physicsScene", collision_root_path="/World/collisions", - prim_paths=[f"/World/envs/env_{i}" for i in range(128)], - global_paths=["/World/defaultGroundPlane"], # collides with all envs + prim_paths=[f"/World/envs/env_{i}" for i in range(num_envs)], + global_paths=["/World/ground"], ) .. note:: - Collision filtering uses PhysX collision groups and is only applicable to the PhysX backend. - The Newton backend handles per-environment isolation through its world system. - + Collision filtering uses PhysX collision groups. Newton handles per-environment isolation + through its own world system. -Physics Backend Replication ---------------------------- -Each physics backend has its own replication function that registers cloned prims with the -physics engine: +Backend and Option Notes +------------------------ -- **PhysX**: :func:`~isaaclab_physx.cloner.physx_replicate` -- Uses the PhysX replicator - interface for fast physics body registration. -- **Newton**: :func:`~isaaclab_newton.cloner.newton_physics_replicate` -- Builds a Newton - ``ModelBuilder`` with per-environment worlds, supporting heterogeneous spawning. +**Physics replication.** :class:`~isaaclab.scene.InteractiveScene` selects the backend +replication function automatically. Direct PhysX users call +:func:`~isaaclab_physx.cloner.physx_replicate`; Newton users call +:func:`~isaaclab_newton.cloner.newton_physics_replicate`. -These functions are set automatically when using :class:`~isaaclab.scene.InteractiveScene`. -For direct usage: - -.. code-block:: python +**``replicate_physics=False``.** Disable physics replication when environments need +independent authored USD or physics state, such as some scale, texture, or color +randomization workflows. Startup and physics parsing are slower because the backend cannot +assume every environment is a clone of the same source. - import torch - from isaaclab_physx.cloner import physx_replicate +**``copy_from_source``.** ``InteractiveScene`` calls +``clone_environments(copy_from_source=True)`` when ``replicate_physics=False``. This skips +backend physics replication and leaves physics parsing to the backend. Spawner-level +``copy_from_source`` is a separate setting used by spawn functions that clone from a source +path matched by a regex. - physx_replicate( - stage=stage, - sources=["/World/envs/env_0/Robot"], - destinations=["/World/envs/env_{}/Robot"], # {} is replaced with env index - env_ids=torch.arange(128), - mapping=torch.ones(1, 128, dtype=torch.bool), - device="cuda:0", - ) +**Fabric cloning.** ``clone_in_fabric=True`` applies to PhysX replication. It can reduce +scene-creation time for large PhysX scenes, especially when many replicated rigid bodies are +authored. Fabric-backed stage data must be inspected through USDRT rather than normal USD +APIs. See Also -------- -- :doc:`multi_asset_spawning` -- spawning different assets per environment -- :doc:`optimize_stage_creation` -- fabric cloning and stage-in-memory optimizations +* :doc:`multi_asset_spawning` -- configuring multi-asset and multi-USD spawners. +* :doc:`optimize_stage_creation` -- Fabric cloning and stage-in-memory optimizations. diff --git a/docs/source/overview/core-concepts/multi_backend_architecture.rst b/docs/source/overview/core-concepts/multi_backend_architecture.rst index 8fd0e326437f..7a0edce5516a 100644 --- a/docs/source/overview/core-concepts/multi_backend_architecture.rst +++ b/docs/source/overview/core-concepts/multi_backend_architecture.rst @@ -56,7 +56,7 @@ This pattern applies to all simulation components: - :class:`~isaaclab_physx.scene_data_providers.PhysxSceneDataProvider` - :class:`~isaaclab_newton.scene_data_providers.NewtonSceneDataProvider` * - Cloner - - :func:`~isaaclab.cloner.clone_from_template` + - :func:`~isaaclab.cloner.usd_replicate` - :func:`~isaaclab_physx.cloner.physx_replicate` - :func:`~isaaclab_newton.cloner.newton_physics_replicate` diff --git a/source/isaaclab/changelog.d/clone-plan-visualizer-cleanup.minor.rst b/source/isaaclab/changelog.d/clone-plan-visualizer-cleanup.minor.rst new file mode 100644 index 000000000000..c9ceb9405226 --- /dev/null +++ b/source/isaaclab/changelog.d/clone-plan-visualizer-cleanup.minor.rst @@ -0,0 +1,35 @@ +Added +^^^^^ + +* Added :class:`~isaaclab.cloner.ClonePlan` as the flat clone contract shared by + scene cloning, backend replication, and scene-data providers. +* Added :meth:`~isaaclab.sim.SimulationContext.get_clone_plan` and + :meth:`~isaaclab.sim.SimulationContext.set_clone_plan` for publishing the + scene's clone plan. +* Added :attr:`~isaaclab.scene.InteractiveScene.clone_plan` for consumers holding + a scene reference. + +Changed +^^^^^^^ + +* **Breaking:** Changed scene-data providers to build visualizer backend models + from :meth:`~isaaclab.sim.SimulationContext.get_clone_plan` instead of a + clone-time visualizer artifact. Use the published + :class:`~isaaclab.cloner.ClonePlan` for custom scene-data integrations. + +Removed +^^^^^^^ + +* **Breaking:** Removed + :attr:`~isaaclab.cloner.TemplateCloneCfg.visualizer_clone_fn`, + :func:`~isaaclab.cloner.resolve_visualizer_clone_fn`, and + :class:`~isaaclab.physics.scene_data_requirements.VisualizerPrebuiltArtifacts`. + Use the :class:`~isaaclab.cloner.ClonePlan` published through + :meth:`~isaaclab.sim.SimulationContext.get_clone_plan` instead. +* **Breaking:** Removed + :meth:`~isaaclab.sim.SimulationContext.get_scene_data_visualizer_prebuilt_artifact`, + :meth:`~isaaclab.sim.SimulationContext.set_scene_data_visualizer_prebuilt_artifact`, + and + :meth:`~isaaclab.sim.SimulationContext.clear_scene_data_visualizer_prebuilt_artifact`. + Use :meth:`~isaaclab.sim.SimulationContext.get_clone_plan` / + :meth:`~isaaclab.sim.SimulationContext.set_clone_plan` instead. diff --git a/source/isaaclab/changelog.d/octi-cloner_ordering.major.rst b/source/isaaclab/changelog.d/octi-cloner_ordering.major.rst new file mode 100644 index 000000000000..fd0906e5cd66 --- /dev/null +++ b/source/isaaclab/changelog.d/octi-cloner_ordering.major.rst @@ -0,0 +1,29 @@ +Added +^^^^^ + +* Added explicit ``spawn_paths`` support to multi-asset spawners so scene + planning can spawn representative heterogeneous sources directly. + +Changed +^^^^^^^ + +* **Breaking:** Changed :class:`~isaaclab.scene.InteractiveScene` to build clone + plans directly from asset configuration, spawn representative sources in their + selected environments, and replicate from those sources instead of spawning and + discovering prototypes under ``/World/template``. +* **Breaking:** Replaced ``TemplateCloneCfg`` with + :class:`~isaaclab.cloner.CloneCfg` for clone execution settings. +* **Breaking:** Changed :func:`~isaaclab.cloner.make_clone_plan` to return a + :class:`~isaaclab.cloner.ClonePlan` object directly. +* **Breaking:** Changed clone plan publication to use + :meth:`~isaaclab.sim.SimulationContext.get_clone_plan` and + :meth:`~isaaclab.sim.SimulationContext.set_clone_plan` for the single scene + clone plan. + +Removed +^^^^^^^ + +* **Breaking:** Removed :func:`~isaaclab.cloner.clone_from_template`. Use + :func:`~isaaclab.cloner.make_clone_plan`, + :func:`~isaaclab.cloner.usd_replicate`, and backend physics replication + functions for direct cloning workflows. diff --git a/source/isaaclab/isaaclab/cloner/__init__.pyi b/source/isaaclab/isaaclab/cloner/__init__.pyi index 8319388a8108..1ee123e7cf56 100644 --- a/source/isaaclab/isaaclab/cloner/__init__.pyi +++ b/source/isaaclab/isaaclab/cloner/__init__.pyi @@ -4,11 +4,10 @@ # SPDX-License-Identifier: BSD-3-Clause __all__ = [ + "CloneCfg", "ClonePlan", - "TemplateCloneCfg", "random", "sequential", - "clone_from_template", "disabled_fabric_change_notifies", "filter_collisions", "grid_transforms", @@ -17,10 +16,9 @@ __all__ = [ ] from .clone_plan import ClonePlan -from .cloner_cfg import TemplateCloneCfg +from .cloner_cfg import CloneCfg from .cloner_strategies import random, sequential from .cloner_utils import ( - clone_from_template, disabled_fabric_change_notifies, filter_collisions, grid_transforms, diff --git a/source/isaaclab/isaaclab/cloner/clone_plan.py b/source/isaaclab/isaaclab/cloner/clone_plan.py index 4a765463b32d..9dee97c68d55 100644 --- a/source/isaaclab/isaaclab/cloner/clone_plan.py +++ b/source/isaaclab/isaaclab/cloner/clone_plan.py @@ -5,35 +5,29 @@ from __future__ import annotations -from dataclasses import dataclass, field +from dataclasses import dataclass import torch -@dataclass(frozen=True) +@dataclass(frozen=True, eq=False) class ClonePlan: - """Per-group mapping from prototype prims to per-environment clones. - - Produced by :func:`~isaaclab.cloner.clone_from_template` for each prototype group it - discovers under the template root. Lets downstream consumers (e.g. mesh samplers, - ray-cast sensors) read prototype geometry once and scatter to environments via - :attr:`clone_mask` instead of walking per-env USD paths. - - Attributes are population-time invariants and the dataclass is frozen. Hash and - equality operate on :attr:`dest_template` only (the natural identity — it is the key - in :attr:`SimulationContext.get_clone_plans`); the mutable list/tensor fields are - excluded since ``torch.Tensor`` is not hashable and structural equality is rarely the - semantics consumers want. + """Flat cloning source of truth. + + Produced by scene planning after representative source prims are assigned. The + three fields are the same flat replication contract consumed by USD, physics, + and downstream scene-data providers: each source path maps to the destination + template at the same index, and :attr:`clone_mask` selects the environments + populated from that source. """ - dest_template: str - """Destination path template for this group, e.g. ``"/World/envs/env_{}/Object"``.""" + sources: tuple[str, ...] + """Source prim paths used for replication.""" - prototype_paths: list[str] = field(hash=False, compare=False) - """Prototype prim paths in this group, e.g. - ``["/World/template/Object/proto_asset_0", "/World/template/Object/proto_asset_1"]``.""" + destinations: tuple[str, ...] + """Destination path templates, one per source path.""" - clone_mask: torch.Tensor = field(hash=False, compare=False) - """Boolean tensor of shape ``[num_prototypes_in_group, num_envs]``; + clone_mask: torch.Tensor + """Boolean tensor of shape ``[len(sources), num_envs]``; ``clone_mask[i, j]`` is ``True`` iff env ``j`` was populated from - :attr:`prototype_paths` ``[i]``. Each column sums to exactly one.""" + :attr:`sources` ``[i]``.""" diff --git a/source/isaaclab/isaaclab/cloner/cloner_cfg.py b/source/isaaclab/isaaclab/cloner/cloner_cfg.py index 19decec0c011..369f70e33520 100644 --- a/source/isaaclab/isaaclab/cloner/cloner_cfg.py +++ b/source/isaaclab/isaaclab/cloner/cloner_cfg.py @@ -11,52 +11,14 @@ @configclass -class TemplateCloneCfg: - """Configuration for template-based cloning. +class CloneCfg: + """Configuration for environment replication. - This configuration is consumed by :func:`~isaaclab.scene.cloner.clone_from_template` to - replicate one or more "prototype" prims authored under a template root into multiple - per-environment destinations. It supports both USD-spec replication and PhysX replication - and allows choosing between random or round-robin prototype assignment across environments. - - The cloning flow is: - - 1. Discover prototypes under :attr:`template_root` whose base name starts with - :attr:`template_prototype_identifier` (for example, ``proto_asset_0``, ``proto_asset_1``). - 2. Build a per-prototype mapping to environments according to - :attr:`random_heterogeneous_cloning` (random) or modulo assignment (deterministic). - 3. Stamp the selected prototypes to destinations derived from :attr:`clone_regex`. - 4. Optionally perform PhysX replication for the same mapping. - - Example - ------- - - .. code-block:: python - - from isaaclab.cloner import TemplateCloneCfg, clone_from_template - from isaaclab.sim.utils.stage import get_current_stage - - stage = get_current_stage() - cfg = TemplateCloneCfg( - num_clones=128, - template_root="/World/template", - template_prototype_identifier="proto_asset", - clone_regex="/World/envs/env_.*", - clone_usd=True, - clone_physics=True, - random_heterogeneous_cloning=False, # use round-robin mapping - device="cpu", - ) - - clone_from_template(stage, num_clones=cfg.num_clones, template_clone_cfg=cfg) + The scene builds a :class:`~isaaclab.cloner.ClonePlan` directly from asset + configuration, spawns the representative source prims, and then uses this + configuration to dispatch USD and physics replication for that plan. """ - template_root: str = "/World/template" - """Root path under which template prototypes are authored.""" - - template_prototype_identifier: str = "proto_asset" - """Name prefix used to identify prototype prims under :attr:`template_root`.""" - clone_regex: str = "/World/envs/env_.*" """Destination template for per-environment paths. diff --git a/source/isaaclab/isaaclab/cloner/cloner_utils.py b/source/isaaclab/isaaclab/cloner/cloner_utils.py index 717d020a90ce..337fad42f45f 100644 --- a/source/isaaclab/isaaclab/cloner/cloner_utils.py +++ b/source/isaaclab/isaaclab/cloner/cloner_utils.py @@ -9,20 +9,13 @@ import itertools import logging import math -from collections.abc import Iterator -from typing import TYPE_CHECKING +from collections.abc import Iterator, Sequence import torch from pxr import Gf, Sdf, Usd, UsdGeom, UsdUtils, Vt -import isaaclab.sim as sim_utils - from . import _fabric_notices - -if TYPE_CHECKING: - from .cloner_cfg import TemplateCloneCfg - from .clone_plan import ClonePlan logger = logging.getLogger(__name__) @@ -105,118 +98,13 @@ def disabled_fabric_change_notifies(stage: Usd.Stage, *, restore: bool = True) - bindings.set_enable(fabric_id, True) -def clone_from_template( - stage: Usd.Stage, num_clones: int, template_clone_cfg: TemplateCloneCfg -) -> dict[str, ClonePlan]: - """Clone assets from a template root into per-environment destinations. - - This utility discovers prototype prims under ``cfg.template_root`` whose names start with - ``cfg.template_prototype_identifier``, builds a per-prototype mapping across - ``num_clones`` environments (random or modulo), and then performs USD and/or PhysX replication - according to the flags in ``cfg``. - - Args: - stage: The USD stage to author into. - num_clones: Number of environments to clone to (typically equals ``cfg.num_clones``). - template_clone_cfg: Configuration describing template location, destination pattern, - and replication/mapping behavior. - - Returns: - Mapping from each group's destination template (e.g. ``"/World/envs/env_{}/Object"``) - to its :class:`ClonePlan`. Empty when no prototype groups are discovered. - - Note: - This function suspends the Fabric USD notice listener for the duration of the call - and **leaves it disabled on return**. It is intended to be invoked from a scene-init - path that is followed by :meth:`isaaclab.sim.SimulationContext.reset`, whose Fabric - resync naturally recovers the listener state. Callers that bypass that reset - contract (ad-hoc tooling, unit tests on a bare stage) should re-enable Fabric - notices themselves or wrap the call in - :func:`disabled_fabric_change_notifies` with ``restore=True``. - """ - cfg: TemplateCloneCfg = template_clone_cfg - plans: dict[str, ClonePlan] = {} - # Suspend Fabric's USD notice listener for the duration of bulk authoring. ``restore=False`` - # because clone_from_template is only called at scene-init time, which is followed by - # ``SimulationContext.reset`` — that reset path does the Fabric resync naturally, and - # re-enabling here would trigger a redundant ``forceMinimalPopulate`` batch. - with disabled_fabric_change_notifies(stage, restore=False): - world_indices = torch.arange(num_clones, device=cfg.device) - clone_path_fmt = cfg.clone_regex.replace(".*", "{}") - prototype_id = cfg.template_prototype_identifier - prototypes = sim_utils.get_all_matching_child_prims( - cfg.template_root, - predicate=lambda prim: str(prim.GetPath()).split("/")[-1].startswith(prototype_id), - ) - if len(prototypes) > 0: - # Canonicalize prototype-root order. Some simulation/visualization backends might apply order-dependent - # processing, so varying USD traversal or set iteration order can change outputs noticeably. Sorting here - # removes that nondeterminism at the source (group order feeds ``make_clone_plan`` and downstream - # replication), which matters for run-to-run reproducibility across IsaacLab's multi-backend stack. - prototype_roots = sorted({"/".join(str(prototype.GetPath()).split("/")[:-1]) for prototype in prototypes}) - - # discover prototypes per root then make a clone plan - src: list[list[str]] = [] - dest: list[str] = [] - - for prototype_root in prototype_roots: - protos = sim_utils.find_matching_prim_paths(f"{prototype_root}/.*") - protos = [proto for proto in protos if proto.split("/")[-1].startswith(prototype_id)] - src.append(protos) - dest.append(prototype_root.replace(cfg.template_root, clone_path_fmt)) - - src_paths, dest_paths, clone_masking = make_clone_plan( - src, dest, num_clones, cfg.clone_strategy, cfg.device - ) - - # Per-group plans: slice ``clone_masking`` along the prototype axis using cumulative - # group sizes — each group's mask rows are contiguous in the ``[total_protos, num_envs]`` - # tensor that ``make_clone_plan`` produced. - offsets = [0, *itertools.accumulate(len(g) for g in src)] - plans = { - d: ClonePlan(dest_template=d, prototype_paths=list(ps), clone_mask=clone_masking[lo:hi]) - for ps, d, lo, hi in zip(src, dest, offsets, offsets[1:]) - } - - # Spawn the first instance of clones from prototypes, then deactivate the prototypes, those first - # instances will be served as sources for usd and physics replication. - proto_idx = clone_masking.to(torch.int32).argmax(dim=1) - proto_mask = torch.zeros_like(clone_masking) - proto_mask.scatter_(1, proto_idx.view(-1, 1).to(torch.long), clone_masking.any(dim=1, keepdim=True)) - usd_replicate(stage, src_paths, dest_paths, world_indices, proto_mask) - stage.GetPrimAtPath(cfg.template_root).SetActive(False) - get_pos = lambda path: stage.GetPrimAtPath(path).GetAttribute("xformOp:translate").Get() # noqa: E731 - positions = torch.tensor([get_pos(clone_path_fmt.format(i)) for i in world_indices]) - # Heterogeneous default: emit per-prototype (sources, destinations, mask) and trust - # env_0..N's existing xforms (proto-spawn above already placed them, so don't - # re-author). When every env happens to pick prototype 0, collapse below to a - # single env_0 → all-envs copy and re-author positions (the destination subtree - # replaces env_1..N's prior xform). - sources = [tpl.format(int(idx)) for tpl, idx in zip(dest_paths, proto_idx.tolist())] - usd_positions: torch.Tensor | None = None - if torch.all(proto_idx == 0): - sources = [clone_path_fmt.format(0)] - dest_paths = [clone_path_fmt] - clone_masking = clone_masking.new_ones(1, num_clones) - usd_positions = positions - - if cfg.clone_physics and cfg.physics_clone_fn is not None: - cfg.physics_clone_fn( - stage, sources, dest_paths, world_indices, clone_masking, positions=positions, device=cfg.device - ) - if cfg.clone_usd: - usd_replicate(stage, sources, dest_paths, world_indices, clone_masking, positions=usd_positions) - - return plans - - def make_clone_plan( - sources: list[list[str]], - destinations: list[str], + sources: Sequence[Sequence[str]], + destinations: Sequence[str], num_clones: int, clone_strategy: callable, device: str = "cpu", -) -> tuple[list[str], list[str], torch.Tensor]: +) -> ClonePlan: """Construct a cloning plan mapping prototype prims to per-environment destinations. The plan enumerates all combinations of prototypes, selects a combination per environment using ``clone_strategy``, @@ -231,14 +119,20 @@ def make_clone_plan( device: Torch device for tensors in the plan. Defaults to ``"cpu"``. Returns: - tuple: ``(src, dest, masking)`` where ``src`` and ``dest`` are flattened lists of prototype and - destination paths, and ``masking`` is a ``[num_src, num_clones]`` boolean tensor with True - when source ``src[i]`` is used for clone ``j``. + A :class:`ClonePlan` whose ``sources`` and ``destinations`` are flattened per-source rows and + whose ``clone_mask`` is a ``[num_src, num_clones]`` boolean tensor. """ - # 1) Flatten into src and dest lists - src = [p for group in sources for p in group] - dest = [dst for dst, group in zip(destinations, sources) for _ in group] + if len(sources) != len(destinations): + raise ValueError(f"Expected one destination per source group, got {len(destinations)} and {len(sources)}.") + if not sources: + raise ValueError("Expected at least one source group.") group_sizes = [len(group) for group in sources] + if any(size == 0 for size in group_sizes): + raise ValueError("Source groups must not be empty.") + + # 1) Flatten into src and dest lists + src = tuple(p for group in sources for p in group) + dest = tuple(dst for dst, group in zip(destinations, sources) for _ in group) # 2) Enumerate all combinations of "one prototype per group" # all_combos: list of tuples (g0_idx, g1_idx, ..., g_{G-1}_idx) @@ -256,13 +150,13 @@ def make_clone_plan( masking = torch.zeros((sum(group_sizes), num_clones), dtype=torch.bool, device=device) masking[rows, cols] = True - return src, dest, masking + return ClonePlan(sources=src, destinations=dest, clone_mask=masking) def usd_replicate( stage: Usd.Stage, - sources: list[str], - destinations: list[str], + sources: Sequence[str], + destinations: Sequence[str], env_ids: torch.Tensor, mask: torch.Tensor | None = None, positions: torch.Tensor | None = None, diff --git a/source/isaaclab/isaaclab/scene/interactive_scene.py b/source/isaaclab/isaaclab/scene/interactive_scene.py index ce744fe4bffe..ae39e3daa719 100644 --- a/source/isaaclab/isaaclab/scene/interactive_scene.py +++ b/source/isaaclab/isaaclab/scene/interactive_scene.py @@ -159,7 +159,7 @@ def __init__(self, cfg: InteractiveSceneCfg): # prepare cloner for environment replication self.env_prim_paths = [f"{self.env_ns}/env_{i}" for i in range(self.cfg.num_envs)] - self.cloner_cfg = cloner.TemplateCloneCfg( + self.cloner_cfg = cloner.CloneCfg( clone_regex=self.env_regex_ns, clone_in_fabric=self.cfg.clone_in_fabric, device=self.device, @@ -172,7 +172,6 @@ def __init__(self, cfg: InteractiveSceneCfg): # create source prim self.stage.DefinePrim(self.env_prim_paths[0], "Xform") - self.stage.DefinePrim(self.cloner_cfg.template_root, "Xform") self.env_fmt = self.env_regex_ns.replace(".*", "{}") # allocate env indices self._ALL_INDICES = torch.arange(self.cfg.num_envs, dtype=torch.long, device=self.device) @@ -195,7 +194,14 @@ def __init__(self, cfg: InteractiveSceneCfg): self._global_prim_paths = list() has_scene_cfg_entities = self._is_scene_setup_from_cfg() if has_scene_cfg_entities: + self._clone_plan = self._build_clone_plan_from_cfg() self._add_entities_from_cfg() + else: + self._clone_plan = cloner.ClonePlan( + sources=(self.env_fmt.format(0),), + destinations=(self.env_fmt,), + clone_mask=torch.ones((1, self.num_envs), device=self.device, dtype=torch.bool), + ) # Aggregate scene-data requirements from declared visualizers and constructed sensors, # then publish to ``SimulationContext`` so downstream providers (constructed later by @@ -209,6 +215,84 @@ def __init__(self, cfg: InteractiveSceneCfg): if self.cfg.filter_collisions and "physx" in self.physics_backend: self.filter_collisions(self._global_prim_paths) + def _build_clone_plan_from_cfg(self) -> cloner.ClonePlan | None: + """Build a clone plan from scene cfg spawn variants and write planned spawn paths. + + Returns ``None`` when the cfg has no env-scoped spawned assets. + """ + + def num_variants(spawn_cfg) -> int: + if isinstance(spawn_cfg, sim_utils.MultiAssetSpawnerCfg): + return len(spawn_cfg.assets_cfg) + if isinstance(spawn_cfg, sim_utils.MultiUsdFileCfg): + return 1 if isinstance(spawn_cfg.usd_path, str) else len(spawn_cfg.usd_path) + return 1 + + def set_spawn_paths(spawn_cfg, paths: list[str | None]) -> None: + if isinstance(spawn_cfg, (sim_utils.MultiAssetSpawnerCfg, sim_utils.MultiUsdFileCfg)): + spawn_cfg.spawn_paths = paths + else: + active = [path for path in paths if path is not None] + if len(active) != 1: + raise ValueError("Single spawner expects exactly one planned source path.") + spawn_cfg.spawn_path = active[0] + + cfg_fields = InteractiveSceneCfg.__dataclass_fields__ + items = [(k, v) for k, v in self.cfg.__dict__.items() if k not in cfg_fields and v is not None] + ordered_items = [item for item in items if not isinstance(item[1], SensorBaseCfg)] + ordered_items += [item for item in items if isinstance(item[1], SensorBaseCfg)] + + # One group is one prim path template plus its spawn variants. + groups = [] + for _, asset_cfg in ordered_items: + cfgs = asset_cfg.rigid_objects.values() if isinstance(asset_cfg, RigidObjectCollectionCfg) else [asset_cfg] + for cfg in (cfg for cfg in cfgs if hasattr(cfg, "prim_path")): + prim_path = cfg.prim_path.format(ENV_REGEX_NS=self.env_regex_ns) + if not hasattr(cfg, "spawn") or cfg.spawn is None or self.env_ns not in prim_path: + continue + if (count := num_variants(cfg.spawn)) <= 0: + raise ValueError(f"Spawner at '{prim_path}' must have at least one variant.") + groups.append((cfg.spawn, prim_path.replace(self.env_regex_ns, self.env_fmt), count)) + + if not groups: + return None + + # Homogeneous scenes still spawn sources at env_0, but publish the simpler env-root plan. + if all(count == 1 for _, _, count in groups): + for spawn_cfg, destination, _ in groups: + set_spawn_paths(spawn_cfg, [destination.format(0)]) + return cloner.ClonePlan( + sources=(self.env_fmt.format(0),), + destinations=(self.env_fmt,), + clone_mask=torch.ones((1, self.num_envs), device=self.device, dtype=torch.bool), + ) + + plan = cloner.make_clone_plan( + [[destination.format(i) for i in range(count)] for _, destination, count in groups], + [destination for _, destination, _ in groups], + self.num_envs, + self.cloner_cfg.clone_strategy, + self.device, + ) + + # Move each planned source row to the first environment that actually uses it. + row = 0 + sources = list(plan.sources) + for spawn_cfg, destination, count in groups: + mask = plan.clone_mask[row : row + count] + env_ids = mask.to(torch.int).argmax(dim=1).tolist() + active = mask.any(dim=1).tolist() + paths = [destination.format(env_id) if is_active else None for env_id, is_active in zip(env_ids, active)] + for i, path in zip(range(row, row + count), paths): + if path is not None: + sources[i] = path + set_spawn_paths(spawn_cfg, paths) + row += count + + plan = cloner.ClonePlan(sources=tuple(sources), destinations=plan.destinations, clone_mask=plan.clone_mask) + logger.debug("Built heterogeneous ClonePlan with %d source rows.", len(plan.sources)) + return plan + def clone_environments(self, copy_from_source: bool = False): """Creates clones of the environment ``/World/envs/env_0``. @@ -217,52 +301,44 @@ def clone_environments(self, copy_from_source: bool = False): If True, clones are independent copies of the source prim and won't reflect its changes (start-up time may increase). Defaults to False. """ + plan = self._clone_plan + assert self.sim is not None + if plan is None: + self.sim.set_clone_plan(None) + return + # PhysX-only: set env id bit count for replicated physics. Newton handles env separation in its own API. # Intentionally matches both physx and ovphysx (both are PhysX-based) if self.cfg.replicate_physics and "physx" in self.physics_backend: prim = self.stage.GetPrimAtPath("/physicsScene") prim.CreateAttribute("physxScene:envIdInBoundsBitCount", Sdf.ValueTypeNames.Int).Set(4) - # Suspend Fabric's USD notice listener around bulk authoring (re-entrant with the inner - # call inside :func:`clone_from_template`). ``restore=False`` because the downstream - # ``SimulationContext.reset`` does the Fabric resync — re-enabling here would batch-resync - # everything we just authored, which is slower than the unsuppressed baseline. + # Suspend Fabric's USD notice listener around bulk authoring. ``restore=False`` because the downstream + # ``SimulationContext.reset`` does the Fabric resync — re-enabling here would batch-resync everything + # we just authored, which is slower than the unsuppressed baseline. with cloner.disabled_fabric_change_notifies(self.stage, restore=False): - if self._is_scene_setup_from_cfg(): - self.cloner_cfg.clone_physics = not copy_from_source - plans = cloner.clone_from_template( - self.stage, num_clones=self.num_envs, template_clone_cfg=self.cloner_cfg + replicate_args = (plan.sources, plan.destinations, self._ALL_INDICES, plan.clone_mask) + + if not copy_from_source and self.cloner_cfg.physics_clone_fn is not None: + self.cloner_cfg.physics_clone_fn( + self.stage, + *replicate_args, + positions=self._default_env_origins, + device=self.cloner_cfg.device, ) - else: - mapping = torch.ones((1, self.num_envs), device=self.device, dtype=torch.bool) - replicate_args = ( - [self.env_fmt.format(0)], - [self.env_fmt], - self._ALL_INDICES, - mapping, + if self.cloner_cfg.clone_usd: + is_env_root_plan = ( + len(plan.sources) == 1 + and plan.sources[0] == self.env_fmt.format(0) + and plan.destinations == (self.env_fmt,) ) + usd_positions = self._default_env_origins if is_env_root_plan else None + cloner.usd_replicate(self.stage, *replicate_args, positions=usd_positions) - if not copy_from_source and self.cloner_cfg.physics_clone_fn is not None: - self.cloner_cfg.physics_clone_fn( - self.stage, *replicate_args, positions=self._default_env_origins, device=self.cloner_cfg.device - ) - if self.cloner_cfg.clone_usd: - cloner.usd_replicate(self.stage, *replicate_args, positions=self._default_env_origins) - # Synthesize a single trivial ClonePlan so consumers (scene data providers, - # pointcloud samplers, etc.) get a uniform interface regardless of whether - # the scene was authored via prototypes or by hand under env_0. - plans = { - self.env_fmt: cloner.ClonePlan( - dest_template=self.env_fmt, - prototype_paths=[self.env_fmt.format(0)], - clone_mask=mapping, - ) - } - - # Publish to ``SimulationContext`` (the canonical owner). The :attr:`clone_plans` - # property below forwards reads back through ``sim.get_clone_plans()`` so consumers - # holding a scene reference still see the published plans without a duplicate cache. - self.sim.set_clone_plans(plans) + # Publish to ``SimulationContext`` (the canonical owner). The :attr:`clone_plan` + # property below forwards reads back through ``sim.get_clone_plan()`` so consumers + # holding a scene reference still see the published plan without a duplicate cache. + self.sim.set_clone_plan(plan) def _aggregate_scene_data_requirements(self, visualizer_types=()) -> None: """Aggregate scene-data requirements from visualizers and sensor renderers. @@ -427,16 +503,14 @@ def surface_grippers(self) -> dict[str, SurfaceGripper]: return self._surface_grippers @property - def clone_plans(self) -> dict[str, cloner.ClonePlan]: - """Per-group clone plans produced by :meth:`clone_environments`. - - Forwards to :meth:`SimulationContext.get_clone_plans`, which is the canonical owner. - Keyed by each group's destination path template - (e.g. ``"/World/envs/env_{}/Object"``); the value records the prototype prim paths - and the per-env prototype assignment mask. Empty until :meth:`clone_environments` - runs, and (for the cfg path) empty when the scene cfg has no template prototypes. + def clone_plan(self) -> cloner.ClonePlan | None: + """Clone plan produced by :meth:`clone_environments`. + + Forwards to :meth:`SimulationContext.get_clone_plan`, which is the canonical owner. + The plan records the source paths, destination templates, and the per-env source + assignment mask. ``None`` until :meth:`clone_environments` runs. """ - return self.sim.get_clone_plans() + return self.sim.get_clone_plan() @property def extras(self) -> dict[str, FrameView]: @@ -772,30 +846,20 @@ def _add_entities_from_cfg(self): # noqa: C901 ] for asset_name, asset_cfg in ordered_items: - # Resolve old-style preset wrappers: configclass with a ``presets`` dict and a ``'default'`` key. - # These are multi-backend selector objects (e.g. VelocityEnvContactSensorCfg) that hold several - # alternative asset configs in a dict and are not themselves asset configs. - if hasattr(asset_cfg, "presets") and isinstance(asset_cfg.presets, dict) and "default" in asset_cfg.presets: - asset_cfg = asset_cfg.presets["default"] - setattr(self.cfg, asset_name, asset_cfg) # resolve prim_path with env regex if hasattr(asset_cfg, "prim_path"): asset_cfg.prim_path = asset_cfg.prim_path.format(ENV_REGEX_NS=self.env_regex_ns) # set spawn_path on spawner if cloning is needed if hasattr(asset_cfg, "spawn") and asset_cfg.spawn is not None: - if hasattr(asset_cfg, "prim_path") and self.env_ns in asset_cfg.prim_path: - template_base = asset_cfg.prim_path.replace(self.env_regex_ns, self.cloner_cfg.template_root) - proto_id = self.cloner_cfg.template_prototype_identifier - if isinstance(asset_cfg, SensorBaseCfg): - # Sensor may be nested under a proto_asset_N prim (e.g. a camera on a robot - # link). Search for the actual template location so spawning succeeds even - # though the parent asset lives at template_root//proto_asset_0/... - asset_cfg.spawn.spawn_path = self._resolve_sensor_template_spawn_path(template_base, proto_id) - else: - asset_cfg.spawn.spawn_path = f"{template_base}/{proto_id}_.*" - else: - # No cloning - spawn directly at prim_path + is_multi_spawner = isinstance( + asset_cfg.spawn, (sim_utils.MultiAssetSpawnerCfg, sim_utils.MultiUsdFileCfg) + ) + if self.env_ns not in asset_cfg.prim_path: asset_cfg.spawn.spawn_path = asset_cfg.prim_path + elif is_multi_spawner and not asset_cfg.spawn.spawn_paths: + raise RuntimeError(f"Clone planning did not assign spawn_paths for '{asset_cfg.prim_path}'.") + elif not is_multi_spawner and asset_cfg.spawn.spawn_path is None: + raise RuntimeError(f"Clone planning did not assign spawn_path for '{asset_cfg.prim_path}'.") # create asset if isinstance(asset_cfg, TerrainImporterCfg): # terrains are special entities since they define environment origins @@ -813,14 +877,19 @@ def _add_entities_from_cfg(self): # noqa: C901 rigid_object_cfg.prim_path = rigid_object_cfg.prim_path.format(ENV_REGEX_NS=self.env_regex_ns) # set spawn_path on spawner if cloning is needed if hasattr(rigid_object_cfg, "spawn") and rigid_object_cfg.spawn is not None: - if self.env_ns in rigid_object_cfg.prim_path: - spawn_tmpl = rigid_object_cfg.prim_path.replace( - self.env_regex_ns, self.cloner_cfg.template_root - ) - proto_id = self.cloner_cfg.template_prototype_identifier - rigid_object_cfg.spawn.spawn_path = f"{spawn_tmpl}/{proto_id}_.*" - else: + is_multi_spawner = isinstance( + rigid_object_cfg.spawn, (sim_utils.MultiAssetSpawnerCfg, sim_utils.MultiUsdFileCfg) + ) + if self.env_ns not in rigid_object_cfg.prim_path: rigid_object_cfg.spawn.spawn_path = rigid_object_cfg.prim_path + elif is_multi_spawner and not rigid_object_cfg.spawn.spawn_paths: + raise RuntimeError( + f"Clone planning did not assign spawn_paths for '{rigid_object_cfg.prim_path}'." + ) + elif not is_multi_spawner and rigid_object_cfg.spawn.spawn_path is None: + raise RuntimeError( + f"Clone planning did not assign spawn_path for '{rigid_object_cfg.prim_path}'." + ) self._rigid_object_collections[asset_name] = asset_cfg.class_type(asset_cfg) for rigid_object_cfg in asset_cfg.rigid_objects.values(): if hasattr(rigid_object_cfg, "collision_group") and rigid_object_cfg.collision_group == -1: @@ -882,39 +951,3 @@ def _add_entities_from_cfg(self): # noqa: C901 if hasattr(asset_cfg, "collision_group") and asset_cfg.collision_group == -1: asset_paths = sim_utils.find_matching_prim_paths(asset_cfg.prim_path) self._global_prim_paths += asset_paths - - def _resolve_sensor_template_spawn_path(self, template_base: str, proto_id: str) -> str: - """Resolve the actual template spawn path for a sensor nested under a proto_asset prim. - - Sensors parented to robot links live inside ``proto_asset_0`` rather than directly under - the template root. For example, a wrist camera at - ``/World/template/Robot/panda_hand/wrist_cam`` is actually spawned at - ``/World/template/Robot/proto_asset_0/panda_hand/wrist_cam``. - - This method inserts a ``proto_id_.*`` wildcard one level below the template root and - searches for the concrete parent prim so the camera spawner can find it. - - Args: - template_base: Template path derived by replacing the env regex with the template root. - Example: ``/World/template/Robot/panda_hand/wrist_cam``. - proto_id: Prototype identifier prefix (e.g. ``proto_asset``). - - Returns: - Concrete spawn path (e.g. ``/World/template/Robot/proto_asset_0/panda_hand/wrist_cam``) - if the parent is found, otherwise ``template_base/proto_id_.*`` as a fallback. - """ - template_root = self.cloner_cfg.template_root - # rel = e.g. "Robot/panda_hand/wrist_cam" - rel = template_base[len(template_root) + 1 :] - # asset = "Robot", remainder = "panda_hand/wrist_cam" - asset, _, remainder = rel.partition("/") - if not remainder: - return f"{template_base}/{proto_id}_.*" - - # parent = "panda_hand", leaf = "wrist_cam" - parent, _, leaf = remainder.rpartition("/") - search = ( - f"{template_root}/{asset}/{proto_id}_.*/{parent}" if parent else f"{template_root}/{asset}/{proto_id}_.*" - ) - found = sim_utils.find_matching_prim_paths(search) - return f"{found[0]}/{leaf}" if found else f"{template_base}/{proto_id}_.*" diff --git a/source/isaaclab/isaaclab/sim/simulation_context.py b/source/isaaclab/isaaclab/sim/simulation_context.py index d5ef6f64e9c5..121b01fdb622 100644 --- a/source/isaaclab/isaaclab/sim/simulation_context.py +++ b/source/isaaclab/isaaclab/sim/simulation_context.py @@ -176,11 +176,10 @@ def __init__(self, cfg: SimulationCfg | None = None): self._scene_data_provider: BaseSceneDataProvider | None = None self._visualizers: list[BaseVisualizer] = [] self._scene_data_requirements = SceneDataRequirement() - # Per-group clone plans published by InteractiveScene after cloning. Providers (e.g. - # the Newton visualizer model rebuilder on a PhysX backend) consume these to derive - # their own backend args. Empty dict until :meth:`InteractiveScene.clone_environments` - # runs. - self._clone_plans: dict[str, ClonePlan] = {} + # Clone plan published by InteractiveScene after cloning. Providers (e.g. the + # Newton visualizer model rebuilder on a PhysX backend) consume this to derive + # their own backend args. None until :meth:`InteractiveScene.clone_environments` runs. + self._clone_plan: ClonePlan | None = None self._visualizer_step_counter = 0 # Default visualization dt used before/without visualizer initialization. physics_dt = getattr(self.cfg.physics, "dt", None) @@ -635,18 +634,18 @@ def update_scene_data_requirements(self, requirements: SceneDataRequirement) -> """Update scene-data requirements.""" self._scene_data_requirements = requirements - def get_clone_plans(self) -> dict[str, ClonePlan]: - """Return per-group clone plans published by the scene, keyed by destination template. + def get_clone_plan(self) -> ClonePlan | None: + """Return the clone plan published by the scene. Set by :meth:`InteractiveScene.clone_environments` after replication. Consumed by scene data providers that build backend models (e.g. Newton visualizer model on a - PhysX backend) from the same plan the cloner used. Empty dict until the scene clones. + PhysX backend) from the same plan the cloner used. ``None`` until the scene clones. """ - return self._clone_plans + return self._clone_plan - def set_clone_plans(self, plans: dict[str, ClonePlan]) -> None: - """Set the cloner's per-group clone-plan map.""" - self._clone_plans = plans + def set_clone_plan(self, plan: ClonePlan | None) -> None: + """Set the cloner's clone plan.""" + self._clone_plan = plan @property def visualizers(self) -> list[BaseVisualizer]: diff --git a/source/isaaclab/isaaclab/sim/spawners/wrappers/wrappers.py b/source/isaaclab/isaaclab/sim/spawners/wrappers/wrappers.py index 285dd0373063..f6f087cfa129 100644 --- a/source/isaaclab/isaaclab/sim/spawners/wrappers/wrappers.py +++ b/source/isaaclab/isaaclab/sim/spawners/wrappers/wrappers.py @@ -31,9 +31,6 @@ def spawn_multi_asset( Assets are created in the order they appear in ``cfg.assets_cfg`` using the base name in ``prim_path``, which must contain ``.*`` (for example, ``/World/Env_0/asset_.*`` spawns ``asset_0``, ``asset_1``, ...). - The prefix portion of ``prim_path`` may also include ``.*`` (for example, ``/World/env_.*/asset_.*``); - in this case, assets are spawned under the first match (``env_0``) and that structure is cloned to - other matching environments by the scene's cloner. Args: prim_path: The prim path to spawn the assets. @@ -46,21 +43,33 @@ def spawn_multi_asset( Returns: The created prim at the first prim path. """ - split_path = prim_path.split("/") - prefix_path, base_name = "/".join(split_path[:-1]), split_path[-1] - if ".*" not in base_name: - raise ValueError( - f" The base name '{base_name}' in the prim path '{prim_path}' must contain '.*' to indicate" - " the path each individual multiple-asset to be spawned." - ) + if cfg.spawn_paths is not None: + if len(cfg.spawn_paths) != len(cfg.assets_cfg): + raise ValueError( + f"Expected spawn_paths to match assets_cfg length, got {len(cfg.spawn_paths)} and" + f" {len(cfg.assets_cfg)}." + ) + asset_prim_paths = list(cfg.spawn_paths) + else: + split_path = prim_path.split("/") + prefix_path, base_name = "/".join(split_path[:-1]), split_path[-1] + if ".*" not in base_name: + raise ValueError( + f" The base name '{base_name}' in the prim path '{prim_path}' must contain '.*' to indicate" + " the path each individual multiple-asset to be spawned." + ) + asset_prim_paths = [f"{prefix_path}/{base_name.replace('.*', str(i))}" for i in range(len(cfg.assets_cfg))] + if cfg.random_choice: logger.warning( "`random_choice` parameter in `spawn_multi_asset` is deprecated, and nothing will happen. " "Use `isaaclab.scene.interactive_scene_cfg.InteractiveSceneCfg.random_heterogeneous_cloning` instead." ) - proto_prim_paths = list() - for index, asset_cfg in enumerate(cfg.assets_cfg): + spawned_prim_paths: list[str] = [] + for asset_prim_path, asset_cfg in zip(asset_prim_paths, cfg.assets_cfg): + if asset_prim_path is None: + continue # append semantic tags if specified if cfg.semantic_tags is not None: if asset_cfg.semantic_tags is None: @@ -74,19 +83,18 @@ def spawn_multi_asset( if hasattr(asset_cfg, attr_name) and attr_value is not None: setattr(asset_cfg, attr_name, attr_value) - proto_prim_path = f"{prefix_path}/{base_name.replace('.*', str(index))}" asset_cfg.func( - proto_prim_path, + asset_prim_path, asset_cfg, translation=translation, orientation=orientation, clone_in_fabric=clone_in_fabric, replicate_physics=replicate_physics, ) - # append to proto prim paths - proto_prim_paths.append(proto_prim_path) - - return sim_utils.find_first_matching_prim(proto_prim_paths[0]) + spawned_prim_paths.append(asset_prim_path) + if not spawned_prim_paths: + raise ValueError("No assets were spawned. At least one spawn path must be active.") + return sim_utils.find_first_matching_prim(spawned_prim_paths[0]) def spawn_multi_usd_file( @@ -126,13 +134,13 @@ def spawn_multi_usd_file( usd_template_cfg = UsdFileCfg() for attr_name, attr_value in cfg.__dict__.items(): # skip names we know are not present - if attr_name in ["func", "usd_path", "random_choice", "spawn_path"]: + if attr_name in ["func", "usd_path", "random_choice", "spawn_path", "spawn_paths"]: continue # set the attribute into the template setattr(usd_template_cfg, attr_name, attr_value) # create multi asset configuration of USD files - multi_asset_cfg = MultiAssetSpawnerCfg(assets_cfg=[]) + multi_asset_cfg = MultiAssetSpawnerCfg(assets_cfg=[], spawn_paths=cfg.spawn_paths) for usd_path in usd_paths: usd_cfg = usd_template_cfg.replace(usd_path=usd_path) multi_asset_cfg.assets_cfg.append(usd_cfg) diff --git a/source/isaaclab/isaaclab/sim/spawners/wrappers/wrappers_cfg.py b/source/isaaclab/isaaclab/sim/spawners/wrappers/wrappers_cfg.py index d9b7d9ed0c35..e335393f7d94 100644 --- a/source/isaaclab/isaaclab/sim/spawners/wrappers/wrappers_cfg.py +++ b/source/isaaclab/isaaclab/sim/spawners/wrappers/wrappers_cfg.py @@ -49,6 +49,14 @@ class MultiAssetSpawnerCfg(RigidObjectSpawnerCfg, DeformableObjectSpawnerCfg): assets_cfg: list[SpawnerCfg] = MISSING """List of asset configurations to spawn.""" + spawn_paths: list[str | None] | None = None + """Optional concrete spawn paths, one per asset configuration. + + When set, :func:`spawn_multi_asset` uses these paths instead of deriving + sibling paths from the input ``prim_path``. Entries set to ``None`` are + skipped. + """ + random_choice: bool = True """ This parameter is ignored. See :attr:`isaaclab.scene.interactive_scene_cfg.InteractiveSceneCfg.random_heterogeneous_cloning` for details. @@ -77,6 +85,14 @@ class MultiUsdFileCfg(UsdFileCfg): usd_path: str | list[str] = MISSING """Path or a list of paths to the USD files to spawn asset from.""" + spawn_paths: list[str | None] | None = None + """Optional concrete spawn paths, one per USD path. + + When set, :func:`spawn_multi_usd_file` uses these paths instead of deriving + sibling paths from the input ``prim_path``. Entries set to ``None`` are + skipped. + """ + random_choice: bool = True """Whether to randomly select an asset configuration. Default is True. diff --git a/source/isaaclab/test/scene/test_interactive_scene.py b/source/isaaclab/test/scene/test_interactive_scene.py index 390129b9e4f2..626e4d8e44df 100644 --- a/source/isaaclab/test/scene/test_interactive_scene.py +++ b/source/isaaclab/test/scene/test_interactive_scene.py @@ -20,7 +20,7 @@ import isaaclab.sim as sim_utils from isaaclab.actuators import ImplicitActuatorCfg -from isaaclab.assets import ArticulationCfg, RigidObjectCfg +from isaaclab.assets import ArticulationCfg, RigidObjectCfg, RigidObjectCollectionCfg from isaaclab.physics.scene_data_requirements import SceneDataRequirement from isaaclab.scene import InteractiveScene, InteractiveSceneCfg from isaaclab.sim import build_simulation_context @@ -130,14 +130,8 @@ def test_reset_to_env_ids_input_types(device, setup_scene): assert_state_equal(prev_state, scene.get_state()) -def test_clone_environments_non_cfg_publishes_clone_plans(monkeypatch: pytest.MonkeyPatch): - """Non-cfg clone path must dispatch physics + USD replicate and publish a ``ClonePlan``. - - Replaces the old test that asserted a per-call visualizer clone callback was invoked. The - visualizer-fn callback was removed in favor of providers reading - :meth:`SimulationContext.get_clone_plans`; this test asserts the new contract: even - without prototype templates, the scene synthesizes a single trivial ClonePlan. - """ +def test_clone_environments_executes_env_root_plan_with_positions(monkeypatch: pytest.MonkeyPatch): + """Env-root plans replicate the whole environment and keep grid positions.""" from isaaclab.cloner import ClonePlan scene = object.__new__(InteractiveScene) @@ -146,24 +140,27 @@ def test_clone_environments_non_cfg_publishes_clone_plans(monkeypatch: pytest.Mo scene.physics_backend = "physx" scene._sensors = {} - set_plans_calls: list = [] - sim_state: dict = {"plans": {}} + set_plan_calls: list = [] + sim_state: dict = {"plan": None} - def _set_clone_plans(plans): - sim_state["plans"] = plans - set_plans_calls.append(plans) + def _set_clone_plan(plan): + sim_state["plan"] = plan + set_plan_calls.append(plan) scene.sim = SimpleNamespace( get_scene_data_requirements=lambda: SceneDataRequirement(), update_scene_data_requirements=lambda requirements: None, - set_clone_plans=_set_clone_plans, - get_clone_plans=lambda: sim_state["plans"], + set_clone_plan=_set_clone_plan, + get_clone_plan=lambda: sim_state["plan"], ) scene.env_fmt = "/World/envs/env_{}" scene._ALL_INDICES = torch.arange(3, dtype=torch.long) scene._default_env_origins = torch.zeros((3, 3), dtype=torch.float32) - scene._is_scene_setup_from_cfg = lambda: False - + scene._clone_plan = ClonePlan( + sources=(scene.env_fmt.format(0),), + destinations=(scene.env_fmt,), + clone_mask=torch.ones((1, scene.num_envs), dtype=torch.bool), + ) # Avoid binding this unit test to global SimulationContext singleton state. monkeypatch.setattr(InteractiveScene, "device", property(lambda self: "cpu")) @@ -198,24 +195,237 @@ def _usd_replicate(stage, *args, **kwargs): mapping = physics_calls[0][1][3] assert mapping.dtype == torch.bool assert mapping.shape == (1, scene.num_envs) - # Plans are published once per clone, regardless of physics/usd flag combinations. - assert len(set_plans_calls) == 1 - plans = set_plans_calls[-1] - assert set(plans.keys()) == {scene.env_fmt} - plan = plans[scene.env_fmt] + assert physics_calls[0][2]["positions"] is scene._default_env_origins + assert usd_calls[0][2]["positions"] is scene._default_env_origins + assert len(set_plan_calls) == 1 + plan = set_plan_calls[-1] assert isinstance(plan, ClonePlan) - assert plan.dest_template == scene.env_fmt - assert plan.prototype_paths == [scene.env_fmt.format(0)] + assert plan.sources == (scene.env_fmt.format(0),) + assert plan.destinations == (scene.env_fmt,) assert plan.clone_mask.shape == (1, scene.num_envs) - assert scene.clone_plans is plans + assert scene.clone_plan is plan physics_calls.clear() usd_calls.clear() - set_plans_calls.clear() + set_plan_calls.clear() scene.clone_environments(copy_from_source=True) assert len(physics_calls) == 0 assert len(usd_calls) == 1 - assert len(set_plans_calls) == 1 + assert len(set_plan_calls) == 1 + + +def test_clone_environments_skips_replication_without_plan(): + """Direct-path cfg scenes publish no plan and do not dispatch cloners.""" + scene = object.__new__(InteractiveScene) + scene._clone_plan = None + set_plan_calls = [] + scene.sim = SimpleNamespace(set_clone_plan=set_plan_calls.append) + + scene.clone_environments(copy_from_source=False) + + assert set_plan_calls == [None] + + +def test_clone_environments_executes_asset_level_plan_without_usd_positions(monkeypatch: pytest.MonkeyPatch): + """Asset-level plans preserve env-root transforms by skipping USD positions.""" + from isaaclab.cloner import ClonePlan + + scene = object.__new__(InteractiveScene) + scene.cfg = SimpleNamespace(replicate_physics=False, num_envs=2) + scene.stage = object() + scene.physics_backend = "physx" + scene._sensors = {} + scene.env_fmt = "/World/envs/env_{}" + scene._ALL_INDICES = torch.arange(2, dtype=torch.long) + scene._default_env_origins = torch.ones((2, 3), dtype=torch.float32) + scene._clone_plan = ClonePlan( + sources=("/World/envs/env_0/Object", "/World/envs/env_1/Object"), + destinations=("/World/envs/env_{}/Object", "/World/envs/env_{}/Object"), + clone_mask=torch.tensor([[True, False], [False, True]], dtype=torch.bool), + ) + + set_plan_calls: list = [] + scene.sim = SimpleNamespace(set_clone_plan=set_plan_calls.append) + monkeypatch.setattr(InteractiveScene, "device", property(lambda self: "cpu")) + + @contextlib.contextmanager + def _noop_fabric_notices(stage, *, restore=True): + yield + + monkeypatch.setattr("isaaclab.scene.interactive_scene.cloner.disabled_fabric_change_notifies", _noop_fabric_notices) + monkeypatch.setattr( + "isaaclab.scene.interactive_scene.cloner.usd_replicate", + lambda *args, **kwargs: usd_calls.append((args, kwargs)), + ) + + physics_calls = [] + usd_calls = [] + scene.cloner_cfg = SimpleNamespace( + device="cpu", + physics_clone_fn=lambda *args, **kwargs: physics_calls.append((args, kwargs)), + clone_usd=True, + ) + + scene.clone_environments(copy_from_source=False) + + assert len(physics_calls) == 1 + assert physics_calls[0][1]["positions"] is scene._default_env_origins + assert len(usd_calls) == 1 + assert usd_calls[0][1]["positions"] is None + assert set_plan_calls == [scene._clone_plan] + + +def test_build_clone_plan_from_cfg_plans_multi_and_single_spawners(monkeypatch: pytest.MonkeyPatch): + """Heterogeneous planning writes source paths for multi and single spawners.""" + from isaaclab.cloner import sequential + + scene = object.__new__(InteractiveScene) + scene.cfg = SimpleNamespace( + num_envs=4, + object=SimpleNamespace( + prim_path="{ENV_REGEX_NS}/Object", + spawn=sim_utils.MultiAssetSpawnerCfg( + assets_cfg=[ + sim_utils.ConeCfg(radius=0.1, height=0.2), + sim_utils.SphereCfg(radius=0.1), + ] + ), + ), + robot=SimpleNamespace( + prim_path="{ENV_REGEX_NS}/Robot", + spawn=sim_utils.CuboidCfg(size=(0.1, 0.1, 0.1)), + ), + ) + scene.env_fmt = "/World/envs/env_{}" + scene.cloner_cfg = SimpleNamespace(clone_strategy=sequential) + monkeypatch.setattr(InteractiveScene, "device", property(lambda self: "cpu")) + + plan = scene._build_clone_plan_from_cfg() + + assert plan is not None + assert plan.sources == ( + "/World/envs/env_0/Object", + "/World/envs/env_1/Object", + "/World/envs/env_0/Robot", + ) + assert plan.destinations == ( + "/World/envs/env_{}/Object", + "/World/envs/env_{}/Object", + "/World/envs/env_{}/Robot", + ) + assert scene.cfg.object.spawn.spawn_paths == ["/World/envs/env_0/Object", "/World/envs/env_1/Object"] + assert scene.cfg.robot.spawn.spawn_path == "/World/envs/env_0/Robot" + assert scene.cfg.object.prim_path == "{ENV_REGEX_NS}/Object" + assert scene.cfg.robot.prim_path == "{ENV_REGEX_NS}/Robot" + assert torch.equal(plan.clone_mask.to(torch.int).argmax(dim=0).cpu(), torch.tensor([0, 1, 0, 1])) + + +def test_build_clone_plan_from_cfg_defaults_to_env0_plan(monkeypatch: pytest.MonkeyPatch): + """Homogeneous cfg scenes use the default env_0-to-all ClonePlan.""" + from isaaclab.cloner import sequential + + scene = object.__new__(InteractiveScene) + scene.cfg = SimpleNamespace( + num_envs=3, + robot=SimpleNamespace( + prim_path="{ENV_REGEX_NS}/Robot", + spawn=sim_utils.CuboidCfg(size=(0.1, 0.1, 0.1)), + ), + ) + scene.env_fmt = "/World/envs/env_{}" + scene.cloner_cfg = SimpleNamespace(clone_strategy=sequential) + monkeypatch.setattr(InteractiveScene, "device", property(lambda self: "cpu")) + + plan = scene._build_clone_plan_from_cfg() + + assert plan is not None + assert plan.sources == ("/World/envs/env_0",) + assert plan.destinations == (scene.env_fmt,) + assert plan.clone_mask.shape == (1, scene.num_envs) + assert scene.cfg.robot.spawn.spawn_path == "/World/envs/env_0/Robot" + + +def test_build_clone_plan_from_cfg_returns_none_without_env_scoped_groups(monkeypatch: pytest.MonkeyPatch): + """Direct-path cfg scenes should not force env-root replication.""" + from isaaclab.cloner import sequential + + scene = object.__new__(InteractiveScene) + scene.cfg = SimpleNamespace( + num_envs=1, + robot=SimpleNamespace( + prim_path="/World/Robot", + spawn=sim_utils.CuboidCfg(size=(0.1, 0.1, 0.1)), + ), + ) + scene.env_fmt = "/World/envs/env_{}" + scene.cloner_cfg = SimpleNamespace(clone_strategy=sequential) + monkeypatch.setattr(InteractiveScene, "device", property(lambda self: "cpu")) + + assert scene._build_clone_plan_from_cfg() is None + assert scene.cfg.robot.spawn.spawn_path is None + + +def test_build_clone_plan_from_cfg_sets_collection_member_paths(monkeypatch: pytest.MonkeyPatch): + """Rigid object collection members are planned independently.""" + from isaaclab.cloner import sequential + + scene = object.__new__(InteractiveScene) + cube_cfg = RigidObjectCfg( + prim_path="{ENV_REGEX_NS}/Cube", + spawn=sim_utils.CuboidCfg(size=(0.1, 0.1, 0.1)), + ) + shape_cfg = RigidObjectCfg( + prim_path="{ENV_REGEX_NS}/Shape", + spawn=sim_utils.MultiAssetSpawnerCfg( + assets_cfg=[sim_utils.ConeCfg(radius=0.1, height=0.2), sim_utils.SphereCfg(radius=0.1)] + ), + ) + scene.cfg = SimpleNamespace( + num_envs=4, + objects=RigidObjectCollectionCfg(rigid_objects={"cube": cube_cfg, "shape": shape_cfg}), + ) + scene.env_fmt = "/World/envs/env_{}" + scene.cloner_cfg = SimpleNamespace(clone_strategy=sequential) + monkeypatch.setattr(InteractiveScene, "device", property(lambda self: "cpu")) + + plan = scene._build_clone_plan_from_cfg() + + assert plan is not None + planned_cube = scene.cfg.objects.rigid_objects["cube"] + planned_shape = scene.cfg.objects.rigid_objects["shape"] + assert planned_cube.spawn.spawn_path == "/World/envs/env_0/Cube" + assert planned_shape.spawn.spawn_paths == ["/World/envs/env_0/Shape", "/World/envs/env_1/Shape"] + assert "/World/envs/env_{}/Cube" in plan.destinations + assert "/World/envs/env_{}/Shape" in plan.destinations + + +def test_build_clone_plan_from_cfg_marks_unused_variants(monkeypatch: pytest.MonkeyPatch): + """Unused variants keep a mask row but do not get spawned.""" + from isaaclab.cloner import sequential + + scene = object.__new__(InteractiveScene) + scene.cfg = SimpleNamespace( + num_envs=2, + object=SimpleNamespace( + prim_path="{ENV_REGEX_NS}/Object", + spawn=sim_utils.MultiAssetSpawnerCfg( + assets_cfg=[ + sim_utils.ConeCfg(radius=0.1, height=0.2), + sim_utils.CuboidCfg(size=(0.1, 0.1, 0.1)), + sim_utils.SphereCfg(radius=0.1), + ] + ), + ), + ) + scene.env_fmt = "/World/envs/env_{}" + scene.cloner_cfg = SimpleNamespace(clone_strategy=sequential) + monkeypatch.setattr(InteractiveScene, "device", property(lambda self: "cpu")) + + plan = scene._build_clone_plan_from_cfg() + + assert plan is not None + assert scene.cfg.object.spawn.spawn_paths == ["/World/envs/env_0/Object", "/World/envs/env_1/Object", None] + assert plan.clone_mask[2].sum() == 0 def test_aggregate_scene_data_requirements_merges_visualizers_and_renderers(monkeypatch: pytest.MonkeyPatch): diff --git a/source/isaaclab/test/sim/test_cloner.py b/source/isaaclab/test/sim/test_cloner.py index 1f8af90387b5..1f526ac74584 100644 --- a/source/isaaclab/test/sim/test_cloner.py +++ b/source/isaaclab/test/sim/test_cloner.py @@ -20,7 +20,7 @@ from pxr import UsdGeom import isaaclab.sim as sim_utils -from isaaclab.cloner import ClonePlan, TemplateCloneCfg, clone_from_template, sequential, usd_replicate +from isaaclab.cloner import make_clone_plan, sequential, usd_replicate from isaaclab.sim import build_simulation_context pytestmark = pytest.mark.isaacsim_ci @@ -221,56 +221,20 @@ def test_clone_decorator_wildcard_patterns( ) -def test_clone_from_template_returns_clone_plan(sim): - """clone_from_template exposes per-group ClonePlan dicts with prototype-to-env masks. - - Builds two USD prototypes under one group, clones across four envs with the deterministic - sequential strategy, and asserts the returned dict has one entry keyed by the group's - destination template, with a ``[2, 4]`` boolean mask whose columns sum to one. - """ - num_clones = 4 - cfg = TemplateCloneCfg(device=sim.cfg.device, clone_strategy=sequential, clone_physics=False) - - sim_utils.create_prim(cfg.template_root, "Xform") - sim_utils.create_prim(f"{cfg.template_root}/Object", "Xform") - sim_utils.create_prim(f"{cfg.template_root}/Object/proto_asset_0", "Xform") - sim_utils.create_prim(f"{cfg.template_root}/Object/proto_asset_1", "Xform") - sim_utils.create_prim("/World/envs", "Xform") - for i in range(num_clones): - sim_utils.create_prim(f"/World/envs/env_{i}", "Xform", translation=(0, 0, 0)) +def test_make_clone_plan_returns_flat_source_rows(sim): + """make_clone_plan exposes the flat source-to-env mask used by scene cloning.""" + plan = make_clone_plan( + [["/World/envs/env_0/Object", "/World/envs/env_1/Object"]], + ["/World/envs/env_{}/Object"], + num_clones=4, + clone_strategy=sequential, + device=sim.cfg.device, + ) - stage = sim_utils.get_current_stage() - plans = clone_from_template(stage, num_clones=num_clones, template_clone_cfg=cfg) - - assert isinstance(plans, dict) - assert list(plans.keys()) == ["/World/envs/env_{}/Object"] - plan = plans["/World/envs/env_{}/Object"] - assert isinstance(plan, ClonePlan) - assert plan.dest_template == "/World/envs/env_{}/Object" - assert sorted(plan.prototype_paths) == [ - "/World/template/Object/proto_asset_0", - "/World/template/Object/proto_asset_1", - ] - assert plan.clone_mask.shape == (2, num_clones) + assert plan.sources == ("/World/envs/env_0/Object", "/World/envs/env_1/Object") + assert plan.destinations == ("/World/envs/env_{}/Object", "/World/envs/env_{}/Object") + assert plan.clone_mask.shape == (2, 4) assert plan.clone_mask.dtype == torch.bool - # Each env gets exactly one prototype (column-sum invariant) assert torch.all(plan.clone_mask.sum(dim=0) == 1) - # Sequential strategy assigns env i → prototype (i % num_protos) - actual_proto_idx = plan.clone_mask.to(torch.int).argmax(dim=0).cpu() - assert torch.equal(actual_proto_idx, torch.tensor([0, 1, 0, 1])) - - -def test_clone_from_template_returns_empty_dict_when_no_prototypes(sim): - """clone_from_template returns an empty dict when no prototypes match the identifier.""" - num_clones = 2 - cfg = TemplateCloneCfg(device=sim.cfg.device, clone_strategy=sequential, clone_physics=False) - - sim_utils.create_prim(cfg.template_root, "Xform") - sim_utils.create_prim("/World/envs", "Xform") - for i in range(num_clones): - sim_utils.create_prim(f"/World/envs/env_{i}", "Xform", translation=(0, 0, 0)) - - stage = sim_utils.get_current_stage() - plans = clone_from_template(stage, num_clones=num_clones, template_clone_cfg=cfg) - - assert plans == {} + actual_source_idx = plan.clone_mask.to(torch.int).argmax(dim=0).cpu() + assert torch.equal(actual_source_idx, torch.tensor([0, 1, 0, 1])) diff --git a/source/isaaclab/test/sim/test_physx_scene_data_provider_visualizer_contract.py b/source/isaaclab/test/sim/test_physx_scene_data_provider_visualizer_contract.py index 979d66cc4a7e..d8e640c394f8 100644 --- a/source/isaaclab/test/sim/test_physx_scene_data_provider_visualizer_contract.py +++ b/source/isaaclab/test/sim/test_physx_scene_data_provider_visualizer_contract.py @@ -78,35 +78,33 @@ def test_get_newton_model_returns_model_when_sync_enabled(stub_provider): assert stub_provider.get_newton_model() == "full-model" -def test_build_from_clone_plans_populates_provider_state(stub_provider, newton_stub): - """Building from per-group clone plans sets model, state, and rigid-body paths. +def test_build_from_clone_plan_populates_provider_state(stub_provider, newton_stub): + """Building from a flat clone plan sets model, state, and rigid-body paths. - Asserts the provider derives its own (sources, destinations, mask) from the plans - without consulting any auxiliary spec object: representative source paths are recovered - from ``dest_template.format()``, masks are concatenated - along the prototype axis, and per-env positions are read from stage xforms. + Asserts the provider consumes the single source-of-truth ``(sources, + destinations, mask)`` contract directly and reads per-env positions from stage + xforms. """ newton_stub.model = SimpleNamespace( body_label=["/World/envs/env_0/Object/A"], articulation_label=["/World/envs/env_0/Robot"], ) - plans = { - "/World/envs/env_{}/Object": ClonePlan( - dest_template="/World/envs/env_{}/Object", - prototype_paths=["/World/template/Object/proto_0", "/World/template/Object/proto_1"], - # proto 0 → env 0, 2 ; proto 1 → env 1, 3 - clone_mask=torch.tensor([[True, False, True, False], [False, True, False, True]], dtype=torch.bool), + plan = ClonePlan( + sources=( + "/World/envs/env_0/Object", + "/World/envs/env_1/Object", + "/World/envs/env_0/Robot", ), - "/World/envs/env_{}/Robot": ClonePlan( - dest_template="/World/envs/env_{}/Robot", - prototype_paths=["/World/template/Robot/proto_0"], - clone_mask=torch.ones((1, 4), dtype=torch.bool), + destinations=("/World/envs/env_{}/Object", "/World/envs/env_{}/Object", "/World/envs/env_{}/Robot"), + # object 0 -> env 0, 2 ; object 1 -> env 1, 3 ; robot -> all envs + clone_mask=torch.tensor( + [[True, False, True, False], [False, True, False, True], [True, True, True, True]], dtype=torch.bool ), - } - stub_provider._simulation_context = SimpleNamespace(get_clone_plans=lambda: plans) + ) + stub_provider._simulation_context = SimpleNamespace(get_clone_plan=lambda: plan) stub_provider._stage = _silent_stage() - stub_provider._build_newton_model_from_clone_plans() + stub_provider._build_newton_model_from_clone_plan() assert stub_provider._newton_model is newton_stub.model assert stub_provider._newton_state is newton_stub.state_obj @@ -116,7 +114,6 @@ def test_build_from_clone_plans_populates_provider_state(stub_provider, newton_s assert stub_provider._last_newton_model_build_source == "built" kw = newton_stub.calls[-1] - # Source recovery picks the first-env user per prototype. assert kw["sources"] == [ "/World/envs/env_0/Object", "/World/envs/env_1/Object", @@ -127,41 +124,35 @@ def test_build_from_clone_plans_populates_provider_state(stub_provider, newton_s assert kw["positions"].shape == (4, 3) -def test_build_from_clone_plans_missing_sets_error_state(stub_provider): - """When no clone plans are published, model/state stay unset.""" - stub_provider._simulation_context = SimpleNamespace(get_clone_plans=lambda: {}) +def test_build_from_clone_plan_missing_sets_error_state(stub_provider): + """When no clone plan is published, model/state stay unset.""" + stub_provider._simulation_context = SimpleNamespace(get_clone_plan=lambda: None) stub_provider._stage = object() - stub_provider._build_newton_model_from_clone_plans() + stub_provider._build_newton_model_from_clone_plan() assert stub_provider._last_newton_model_build_source == "missing" assert stub_provider._newton_model is None assert stub_provider._newton_state is None -def test_build_from_clone_plans_skips_unused_prototype_rows(stub_provider, newton_stub): - """A prototype row with no assigned env (all-False mask row) is dropped, not raised on. +def test_build_from_clone_plan_skips_unused_source_rows(stub_provider, newton_stub): + """A source row with no assigned env (all-False mask row) is dropped, not raised on. When ``num_prototypes > num_envs`` under a sequential strategy (or any strategy that - leaves some prototypes unused), ``clone_mask[row].nonzero()[0]`` would otherwise raise - ``IndexError``. The provider must filter unused rows out of sources/destinations/mask. + leaves some prototypes unused), the provider must filter unused rows out of + sources/destinations/mask. """ # 3 prototypes, 2 envs, sequential: env 0 → proto 0, env 1 → proto 1, proto 2 unused. - plans = { - "/World/envs/env_{}/Object": ClonePlan( - dest_template="/World/envs/env_{}/Object", - prototype_paths=[ - "/World/template/Object/proto_0", - "/World/template/Object/proto_1", - "/World/template/Object/proto_2", - ], - clone_mask=torch.tensor([[True, False], [False, True], [False, False]], dtype=torch.bool), - ) - } - stub_provider._simulation_context = SimpleNamespace(get_clone_plans=lambda: plans) + plan = ClonePlan( + sources=("/World/envs/env_0/Object", "/World/envs/env_1/Object", "/World/envs/env_0/Object"), + destinations=("/World/envs/env_{}/Object",) * 3, + clone_mask=torch.tensor([[True, False], [False, True], [False, False]], dtype=torch.bool), + ) + stub_provider._simulation_context = SimpleNamespace(get_clone_plan=lambda: plan) stub_provider._stage = _silent_stage() - stub_provider._build_newton_model_from_clone_plans() + stub_provider._build_newton_model_from_clone_plan() assert stub_provider._last_newton_model_build_source == "built" kw = newton_stub.calls[-1] @@ -170,8 +161,8 @@ def test_build_from_clone_plans_skips_unused_prototype_rows(stub_provider, newto assert kw["mapping"].shape == (2, 2) -def test_build_from_clone_plans_uses_dest_template_for_env_lookup(stub_provider, newton_stub): - """Env-origin lookup uses the per-plan ``dest_template`` prefix, not a hardcoded path. +def test_build_from_clone_plan_uses_destination_template_for_env_lookup(stub_provider, newton_stub): + """Env-origin lookup uses the plan's destination prefix, not a hardcoded path. A scene with a non-default env path (``/Stage/scenes/env_``) should still have its xform translates read correctly. Replaces the prior hardcoded ``/World/envs/env_``. @@ -182,40 +173,27 @@ def _get_prim(path): visited.append(path) return SimpleNamespace(IsValid=lambda: False) - plans = { - "/Stage/scenes/env_{}/Object": ClonePlan( - dest_template="/Stage/scenes/env_{}/Object", - prototype_paths=["/Stage/template/Object/proto_0"], - clone_mask=torch.ones((1, 3), dtype=torch.bool), - ) - } - stub_provider._simulation_context = SimpleNamespace(get_clone_plans=lambda: plans) + plan = ClonePlan( + sources=("/Stage/scenes/env_0/Object",), + destinations=("/Stage/scenes/env_{}/Object",), + clone_mask=torch.ones((1, 3), dtype=torch.bool), + ) + stub_provider._simulation_context = SimpleNamespace(get_clone_plan=lambda: plan) stub_provider._stage = SimpleNamespace(GetPrimAtPath=_get_prim) - stub_provider._build_newton_model_from_clone_plans() + stub_provider._build_newton_model_from_clone_plan() assert {f"/Stage/scenes/env_{i}" for i in range(3)} <= set(visited) assert not any(p.startswith("/World/envs/") for p in visited) -def test_clone_plan_is_hashable_with_unhashable_fields(): - """``ClonePlan`` must hash despite carrying a tensor and a list. - - With ``field(hash=False)`` on the unhashable members, hashing operates on - ``dest_template`` only — the natural identity (it is the dict key in - :meth:`SimulationContext.get_clone_plans`). - """ - plan_a = ClonePlan( - dest_template="/World/envs/env_{}/Object", - prototype_paths=["/World/template/Object/proto_0"], +def test_clone_plan_carries_flat_replication_contract(): + """``ClonePlan`` contains only sources, destinations, and the clone mask.""" + plan = ClonePlan( + sources=("/World/envs/env_0/Object",), + destinations=("/World/envs/env_{}/Object",), clone_mask=torch.ones((1, 4), dtype=torch.bool), ) - plan_b = ClonePlan( - dest_template="/World/envs/env_{}/Object", - prototype_paths=["/World/template/Object/proto_99"], - clone_mask=torch.zeros((1, 4), dtype=torch.bool), - ) - assert isinstance(hash(plan_a), int) - # Equality folds in only dest_template, so two plans with the same destination compare - # equal regardless of prototype/mask differences. - assert plan_a == plan_b + assert plan.sources == ("/World/envs/env_0/Object",) + assert plan.destinations == ("/World/envs/env_{}/Object",) + assert plan.clone_mask.shape == (1, 4) diff --git a/source/isaaclab/test/sim/test_simulation_context_visualizers.py b/source/isaaclab/test/sim/test_simulation_context_visualizers.py index 3b7ca93dcfa3..1c40e21cb548 100644 --- a/source/isaaclab/test/sim/test_simulation_context_visualizers.py +++ b/source/isaaclab/test/sim/test_simulation_context_visualizers.py @@ -793,7 +793,7 @@ def _make_context_with_settings( ctx._visualizers = [] ctx._scene_data_provider = _FakeProvider() ctx._scene_data_requirements = None - ctx._clone_plans = {} + ctx._clone_plan = None ctx._visualizer_step_counter = 0 ctx._viz_dt = 0.01 ctx.get_setting = lambda name: settings.get(name) diff --git a/source/isaaclab/test/sim/test_spawn_wrappers.py b/source/isaaclab/test/sim/test_spawn_wrappers.py index c053a6362f4d..69ad8b105723 100644 --- a/source/isaaclab/test/sim/test_spawn_wrappers.py +++ b/source/isaaclab/test/sim/test_spawn_wrappers.py @@ -162,6 +162,41 @@ def test_spawn_multiple_shapes_with_individual_settings(sim): assert prim.GetAttribute("physics:mass").Get() in mass_variations +def test_spawn_multiple_shapes_with_explicit_spawn_paths(sim): + """Multi-asset spawner accepts planned per-variant source paths.""" + sim_utils.create_prim("/World/planned", "Xform", translation=(0, 0, 0)) + + cfg = sim_utils.MultiAssetSpawnerCfg( + assets_cfg=[ + sim_utils.ConeCfg(radius=0.3, height=0.6), + sim_utils.CuboidCfg(size=(0.3, 0.3, 0.3)), + sim_utils.SphereCfg(radius=0.3), + ], + spawn_paths=["/World/planned/apple", None, "/World/planned/banana"], + mass_props=sim_utils.MassPropertiesCfg(mass=1.0), + collision_props=sim_utils.CollisionPropertiesCfg(), + ) + + prim = cfg.func("/World/ignored_without_regex", cfg) + + assert str(prim.GetPath()) == "/World/planned/apple" + assert sim.stage.GetPrimAtPath("/World/planned/apple").IsValid() + assert not sim.stage.GetPrimAtPath("/World/planned/ignored").IsValid() + assert sim.stage.GetPrimAtPath("/World/planned/banana").IsValid() + assert sim.stage.GetPrimAtPath("/World/planned/apple").GetAttribute("physics:mass").Get() == 1.0 + + +def test_spawn_multiple_shapes_spawn_paths_length_mismatch(sim): + """Explicit multi-asset paths must align one-to-one with variants.""" + cfg = sim_utils.MultiAssetSpawnerCfg( + assets_cfg=[sim_utils.ConeCfg(radius=0.3, height=0.6), sim_utils.SphereCfg(radius=0.3)], + spawn_paths=["/World/planned/apple"], + ) + + with pytest.raises(ValueError, match="spawn_paths"): + cfg.func("/World/ignored_without_regex", cfg) + + """ Tests - Multiple USDs. """ diff --git a/source/isaaclab_newton/changelog.d/octi-cloner_ordering.rst b/source/isaaclab_newton/changelog.d/octi-cloner_ordering.rst new file mode 100644 index 000000000000..807d81e7c558 --- /dev/null +++ b/source/isaaclab_newton/changelog.d/octi-cloner_ordering.rst @@ -0,0 +1,5 @@ +Changed +^^^^^^^ + +* Changed rigid object collection spawning to honor planned ``spawn_path`` + values while falling back to ``prim_path`` for direct construction. diff --git a/source/isaaclab_newton/isaaclab_newton/assets/rigid_object_collection/rigid_object_collection.py b/source/isaaclab_newton/isaaclab_newton/assets/rigid_object_collection/rigid_object_collection.py index 8c499d75396c..b11415d48231 100644 --- a/source/isaaclab_newton/isaaclab_newton/assets/rigid_object_collection/rigid_object_collection.py +++ b/source/isaaclab_newton/isaaclab_newton/assets/rigid_object_collection/rigid_object_collection.py @@ -78,8 +78,9 @@ def __init__(self, cfg: RigidObjectCollectionCfg): for rigid_body_cfg in self.cfg.rigid_objects.values(): # spawn the asset if rigid_body_cfg.spawn is not None: + spawn_path = rigid_body_cfg.spawn.spawn_path or rigid_body_cfg.prim_path rigid_body_cfg.spawn.func( - rigid_body_cfg.prim_path, + spawn_path, rigid_body_cfg.spawn, translation=rigid_body_cfg.init_state.pos, orientation=rigid_body_cfg.init_state.rot, diff --git a/source/isaaclab_newton/isaaclab_newton/cloner/newton_replicate.py b/source/isaaclab_newton/isaaclab_newton/cloner/newton_replicate.py index 34cd35de4fa2..544756858d51 100644 --- a/source/isaaclab_newton/isaaclab_newton/cloner/newton_replicate.py +++ b/source/isaaclab_newton/isaaclab_newton/cloner/newton_replicate.py @@ -5,6 +5,8 @@ from __future__ import annotations +from collections.abc import Sequence + import torch import warp as wp from newton import ModelBuilder, solvers @@ -17,7 +19,7 @@ def _build_newton_builder_from_mapping( stage: Usd.Stage, - sources: list[str], + sources: Sequence[str], env_ids: torch.Tensor, mapping: torch.Tensor, positions: torch.Tensor | None = None, @@ -53,7 +55,7 @@ def _build_newton_builder_from_mapping( builder = NewtonManager.create_builder(up_axis=up_axis) stage_info = builder.add_usd( stage, - ignore_paths=["/World/envs"] + sources, + ignore_paths=["/World/envs", *sources], schema_resolvers=schema_resolvers, ) @@ -117,7 +119,11 @@ def _build_newton_builder_from_mapping( def _rename_builder_labels( - builder: ModelBuilder, sources: list[str], destinations: list[str], env_ids: torch.Tensor, mapping: torch.Tensor + builder: ModelBuilder, + sources: Sequence[str], + destinations: Sequence[str], + env_ids: torch.Tensor, + mapping: torch.Tensor, ) -> None: """Rename builder labels/keys from source roots to destination roots. @@ -149,8 +155,8 @@ def _rename_builder_labels( def newton_physics_replicate( stage: Usd.Stage, - sources: list[str], - destinations: list[str], + sources: Sequence[str], + destinations: Sequence[str], env_ids: torch.Tensor, mapping: torch.Tensor, positions: torch.Tensor | None = None, @@ -195,8 +201,8 @@ def newton_physics_replicate( def newton_visualizer_prebuild( stage: Usd.Stage, - sources: list[str], - destinations: list[str], + sources: Sequence[str], + destinations: Sequence[str], env_ids: torch.Tensor, mapping: torch.Tensor, positions: torch.Tensor | None = None, diff --git a/source/isaaclab_ovphysx/changelog.d/octi-cloner_ordering.skip b/source/isaaclab_ovphysx/changelog.d/octi-cloner_ordering.skip new file mode 100644 index 000000000000..e69de29bb2d1 diff --git a/source/isaaclab_ovphysx/isaaclab_ovphysx/cloner/ovphysx_replicate.py b/source/isaaclab_ovphysx/isaaclab_ovphysx/cloner/ovphysx_replicate.py index 7c46a6060b88..d89a45280a50 100644 --- a/source/isaaclab_ovphysx/isaaclab_ovphysx/cloner/ovphysx_replicate.py +++ b/source/isaaclab_ovphysx/isaaclab_ovphysx/cloner/ovphysx_replicate.py @@ -5,9 +5,9 @@ """OvPhysX replication hook for IsaacLab's cloning pipeline. -Called by :func:`isaaclab.cloner.clone_from_template` in place of the PhysX -or Newton replicators. Unlike those replicators, ovphysx.PhysX does not exist -yet at this point in the scene setup — it is created lazily on the first +Called from the scene cloning path in place of immediate PhysX or Newton +replication. Unlike those replicators, ovphysx.PhysX does not exist yet at +this point in the scene setup — it is created lazily on the first :meth:`~isaaclab_ovphysx.physics.OvPhysxManager.reset` call. This function records a *pending clone* on :class:`OvPhysxManager`. When @@ -20,6 +20,8 @@ from __future__ import annotations +from collections.abc import Sequence + import torch from pxr import Usd @@ -27,8 +29,8 @@ def ovphysx_replicate( stage: Usd.Stage, - sources: list[str], - destinations: list[str], + sources: Sequence[str], + destinations: Sequence[str], env_ids: torch.Tensor, mapping: torch.Tensor, positions: torch.Tensor | None = None, diff --git a/source/isaaclab_physx/changelog.d/octi-cloner_ordering.rst b/source/isaaclab_physx/changelog.d/octi-cloner_ordering.rst new file mode 100644 index 000000000000..807d81e7c558 --- /dev/null +++ b/source/isaaclab_physx/changelog.d/octi-cloner_ordering.rst @@ -0,0 +1,5 @@ +Changed +^^^^^^^ + +* Changed rigid object collection spawning to honor planned ``spawn_path`` + values while falling back to ``prim_path`` for direct construction. diff --git a/source/isaaclab_physx/isaaclab_physx/assets/rigid_object_collection/rigid_object_collection.py b/source/isaaclab_physx/isaaclab_physx/assets/rigid_object_collection/rigid_object_collection.py index 6d07ddbf1bc1..2031ded53b2f 100644 --- a/source/isaaclab_physx/isaaclab_physx/assets/rigid_object_collection/rigid_object_collection.py +++ b/source/isaaclab_physx/isaaclab_physx/assets/rigid_object_collection/rigid_object_collection.py @@ -81,8 +81,9 @@ def __init__(self, cfg: RigidObjectCollectionCfg): for rigid_body_cfg in self.cfg.rigid_objects.values(): # spawn the asset if rigid_body_cfg.spawn is not None: + spawn_path = rigid_body_cfg.spawn.spawn_path or rigid_body_cfg.prim_path rigid_body_cfg.spawn.func( - rigid_body_cfg.prim_path, + spawn_path, rigid_body_cfg.spawn, translation=rigid_body_cfg.init_state.pos, orientation=rigid_body_cfg.init_state.rot, diff --git a/source/isaaclab_physx/isaaclab_physx/cloner/physx_replicate.py b/source/isaaclab_physx/isaaclab_physx/cloner/physx_replicate.py index d90d413bffa2..dcc5cc6d9677 100644 --- a/source/isaaclab_physx/isaaclab_physx/cloner/physx_replicate.py +++ b/source/isaaclab_physx/isaaclab_physx/cloner/physx_replicate.py @@ -5,6 +5,8 @@ from __future__ import annotations +from collections.abc import Sequence + import torch from omni.physx import get_physx_replicator_interface @@ -13,8 +15,8 @@ def physx_replicate( stage: Usd.Stage, - sources: list[str], # e.g. ["/World/Template/A", "/World/Template/B"] - destinations: list[str], # e.g. ["/World/envs/env_{}/Robot", "/World/envs/env_{}/Object"] + sources: Sequence[str], # e.g. ["/World/Template/A", "/World/Template/B"] + destinations: Sequence[str], # e.g. ["/World/envs/env_{}/Robot", "/World/envs/env_{}/Object"] env_ids: torch.Tensor, # env_ids mapping: torch.Tensor, # (num_sources, num_envs) bool; True -> place sources[i] into world=j positions: torch.Tensor | None = None, diff --git a/source/isaaclab_physx/isaaclab_physx/scene_data_providers/physx_scene_data_provider.py b/source/isaaclab_physx/isaaclab_physx/scene_data_providers/physx_scene_data_provider.py index 9a88660da498..ec4c64d8f8c7 100644 --- a/source/isaaclab_physx/isaaclab_physx/scene_data_providers/physx_scene_data_provider.py +++ b/source/isaaclab_physx/isaaclab_physx/scene_data_providers/physx_scene_data_provider.py @@ -42,8 +42,7 @@ class PhysxSceneDataProvider(BaseSceneDataProvider): - body poses via PhysX tensor views, with FrameView fallback - camera poses & intrinsics - USD stage handles - - Newton model/state (built locally from the scene's per-group :class:`ClonePlan` map - when required) + - Newton model/state (built locally from the scene's :class:`ClonePlan` when required) """ # ---- Environment discovery / metadata ------------------------------------------------- @@ -129,7 +128,7 @@ def __init__(self, stage, simulation_context) -> None: self._last_newton_model_build_elapsed_ms: float | None = None if self._needs_newton_sync: - self._build_newton_model_from_clone_plans() + self._build_newton_model_from_clone_plan() self._setup_rigid_body_view() # ---- Newton model + PhysX view setup -------------------------------------------------- @@ -150,53 +149,55 @@ def _refresh_newton_model_if_needed(self) -> None: needs_rebuild = self._newton_model is None or self._newton_state is None needs_rebuild = needs_rebuild or (self._num_envs_at_last_newton_build != num_envs) if needs_rebuild: - self._build_newton_model_from_clone_plans() + self._build_newton_model_from_clone_plan() self._setup_rigid_body_view() - def _build_newton_model_from_clone_plans(self) -> None: - """Build Newton model and state from the scene's per-group :class:`ClonePlan` map. - - Reads plans :meth:`InteractiveScene.clone_environments` publishes on - :class:`SimulationContext`, derives the flat ``(sources, destinations, mask)`` shape - :func:`isaaclab_newton.cloner.newton_visualizer_prebuild` expects, and caches the - resulting model/state. Per-prototype source paths recover as - ``dest_template.format()``; per-env positions are - read off ``xformOp:translate`` on the env-level prims derived from the same template. - Pre-condition violations raise :class:`RuntimeError` (logged as ``"missing"``); - ``isaaclab_newton`` being absent (optional dep) maps to ``"missing"`` via the - import's own exception types; unexpected failures fall through to ``"error"``. + def _build_newton_model_from_clone_plan(self) -> None: + """Build Newton model and state from the scene's :class:`ClonePlan`. + + Reads the plan :meth:`InteractiveScene.clone_environments` publishes on + :class:`SimulationContext`, validates the flat ``(sources, destinations, mask)`` + shape :func:`isaaclab_newton.cloner.newton_visualizer_prebuild` expects, and + caches the resulting model/state. Per-env positions are read off + ``xformOp:translate`` on the env-level prims derived from the first destination + template. Pre-condition violations raise :class:`RuntimeError` (logged as + ``"missing"``); ``isaaclab_newton`` being absent (optional dep) maps to + ``"missing"`` via the import's own exception types; unexpected failures fall + through to ``"error"``. """ start_t = time.perf_counter() source = "missing" try: - plans = self._simulation_context.get_clone_plans() - if not plans: - raise RuntimeError("No clone plans on simulation context.") + plan = self._simulation_context.get_clone_plan() + if plan is None: + raise RuntimeError("No clone plan on simulation context.") from isaaclab_newton.cloner.newton_replicate import newton_visualizer_prebuild - # Flatten per-group plans into one (sources, destinations, mask) bundle. Source - # paths recover via ``dest_template.format()``; - # all-False rows are dropped (possible when ``num_prototypes > num_envs``). - plan_list = list(plans.values()) - num_envs = plan_list[0].clone_mask.size(1) - if any(p.clone_mask.size(1) != num_envs for p in plan_list): - raise RuntimeError(f"Clone plans disagree on num_envs: {[p.clone_mask.size(1) for p in plan_list]}") + if len(plan.sources) != len(plan.destinations): + raise RuntimeError( + f"Clone plan sources and destinations disagree: {len(plan.sources)} != {len(plan.destinations)}" + ) + if plan.clone_mask.dim() != 2 or plan.clone_mask.size(0) != len(plan.sources): + raise RuntimeError( + f"Clone plan mask shape {tuple(plan.clone_mask.shape)} does not match {len(plan.sources)} sources." + ) + + # Drop all-False rows (possible when ``num_prototypes > num_envs``). sources, destinations, mask_rows = [], [], [] - for p in plan_list: - for i in range(p.clone_mask.size(0)): - nz = p.clone_mask[i].nonzero(as_tuple=False) - if nz.numel() == 0: - continue - sources.append(p.dest_template.format(int(nz[0].item()))) - destinations.append(p.dest_template) - mask_rows.append(p.clone_mask[i : i + 1]) + for i, (source_path, destination) in enumerate(zip(plan.sources, plan.destinations)): + if not plan.clone_mask[i].any(): + continue + sources.append(source_path) + destinations.append(destination) + mask_rows.append(plan.clone_mask[i : i + 1]) if not sources: - raise RuntimeError("All clone-plan prototype rows are empty.") + raise RuntimeError("All clone-plan source rows are empty.") mask = torch.cat(mask_rows, dim=0) + num_envs = plan.clone_mask.size(1) # Env-level path template = dest_template up to the first ``{}``. Per-env world # positions: xformOp:translate read off each env prim; missing prims fall through. - env_path_template = plan_list[0].dest_template.split("{}")[0] + "{}" + env_path_template = destinations[0].split("{}")[0] + "{}" positions = torch.zeros((num_envs, 3), dtype=torch.float32, device=self._device) for i in range(num_envs): prim = self._stage.GetPrimAtPath(env_path_template.format(i)) @@ -239,7 +240,7 @@ def _build_newton_model_from_clone_plans(self) -> None: self._clear_newton_model_state() except Exception as exc: source = "error" - logger.error("[PhysxSceneDataProvider] Failed to build Newton model from clone plans: %s", exc) + logger.error("[PhysxSceneDataProvider] Failed to build Newton model from clone plan: %s", exc) self._clear_newton_model_state() finally: self._last_newton_model_build_elapsed_ms = (time.perf_counter() - start_t) * 1000.0 diff --git a/source/isaaclab_physx/test/sim/test_cloner.py b/source/isaaclab_physx/test/sim/test_cloner.py index 4bfba07d99e8..f90c740f17ed 100644 --- a/source/isaaclab_physx/test/sim/test_cloner.py +++ b/source/isaaclab_physx/test/sim/test_cloner.py @@ -21,10 +21,9 @@ import isaaclab.sim as sim_utils from isaaclab.cloner import ( - TemplateCloneCfg, _fabric_notices, - clone_from_template, disabled_fabric_change_notifies, + make_clone_plan, sequential, usd_replicate, ) @@ -242,19 +241,9 @@ def test_physx_replicate_heterogeneous_isolated_sources(sim, device): assert "/World/envs" in attach_excluded -def test_clone_from_template(sim): - """Clone prototypes via TemplateCloneCfg and clone_from_template and exercise both USD and PhysX. - - Steps: - - Create /World/template and /World/envs/env_0..env_31 - - Spawn three prototypes under /World/template/Object/proto_asset_.* - - Clone using TemplateCloneCfg with random_heterogeneous_cloning=False (modulo mapping) - - Verify modulo placement exists; then call sim.reset(), and create PhysX view - """ +def test_direct_clone_plan_multi_asset(sim): + """Clone representative env sources directly and exercise both USD and PhysX.""" num_clones = 32 - clone_cfg = TemplateCloneCfg(device=sim.cfg.device, clone_strategy=sequential) - sim_utils.create_prim(clone_cfg.template_root, "Xform") - sim_utils.create_prim(f"{clone_cfg.template_root}/Object", "Xform") sim_utils.create_prim("/World/envs", "Xform") for i in range(num_clones): sim_utils.create_prim(f"/World/envs/env_{i}", "Xform", translation=(0, 0, 0)) @@ -282,11 +271,22 @@ def test_clone_from_template(sim): mass_props=sim_utils.MassPropertiesCfg(mass=1.0), collision_props=sim_utils.CollisionPropertiesCfg(), ) - prim = cfg.func(f"{clone_cfg.template_root}/Object/{clone_cfg.template_prototype_identifier}_.*", cfg) + plan = make_clone_plan( + [[f"/World/envs/env_{i}/Object" for i in range(len(cfg.assets_cfg))]], + ["/World/envs/env_{}/Object"], + num_clones, + sequential, + sim.cfg.device, + ) + spawn_paths: list[str | None] = list(plan.sources) + cfg.spawn_paths = spawn_paths + prim = cfg.func("/World/unused", cfg) assert prim.IsValid() stage = sim_utils.get_current_stage() - clone_from_template(stage, num_clones=num_clones, template_clone_cfg=clone_cfg) + env_ids = torch.arange(num_clones, dtype=torch.long, device=sim.cfg.device) + physx_replicate(stage, plan.sources, plan.destinations, env_ids, plan.clone_mask, device=sim.cfg.device) + usd_replicate(stage, plan.sources, plan.destinations, env_ids, plan.clone_mask) primitive_prims = sim_utils.get_all_matching_child_prims( "/World/envs", predicate=lambda prim: prim.GetTypeName() in ["Cone", "Cube", "Sphere"] @@ -302,27 +302,38 @@ def test_clone_from_template(sim): assert primitive_prim.GetTypeName() == "Sphere" sim.reset() - object_view_regex = f"{clone_cfg.clone_regex}/Object".replace(".*", "*") physics_sim_view = sim.physics_manager.get_physics_sim_view() - physx_view = physics_sim_view.create_rigid_body_view(object_view_regex) + physx_view = physics_sim_view.create_rigid_body_view("/World/envs/env_*/Object") assert physx_view is not None def _run_colocation_collision_filter(sim, asset_cfg, expected_types, assert_count=False): """Shared harness for colocated collision filter checks across devices.""" num_clones = 32 - clone_cfg = TemplateCloneCfg(device=sim.cfg.device, clone_strategy=sequential) - sim_utils.create_prim(clone_cfg.template_root, "Xform") - sim_utils.create_prim(f"{clone_cfg.template_root}/Object", "Xform") sim_utils.create_prim("/World/envs", "Xform") for i in range(num_clones): sim_utils.create_prim(f"/World/envs/env_{i}", "Xform", translation=(0, 0, 0)) - prim = asset_cfg.func(f"{clone_cfg.template_root}/Object/{clone_cfg.template_prototype_identifier}_.*", asset_cfg) + num_variants = len(asset_cfg.assets_cfg) if isinstance(asset_cfg, sim_utils.MultiAssetSpawnerCfg) else 1 + plan = make_clone_plan( + [[f"/World/envs/env_{i}/Object" for i in range(num_variants)]], + ["/World/envs/env_{}/Object"], + num_clones, + sequential, + sim.cfg.device, + ) + if isinstance(asset_cfg, sim_utils.MultiAssetSpawnerCfg): + spawn_paths: list[str | None] = list(plan.sources) + asset_cfg.spawn_paths = spawn_paths + prim = asset_cfg.func("/World/unused", asset_cfg) + else: + prim = asset_cfg.func(plan.sources[0], asset_cfg) assert prim.IsValid() stage = sim_utils.get_current_stage() - clone_from_template(stage, num_clones=num_clones, template_clone_cfg=clone_cfg) + env_ids = torch.arange(num_clones, dtype=torch.long, device=sim.cfg.device) + physx_replicate(stage, plan.sources, plan.destinations, env_ids, plan.clone_mask, device=sim.cfg.device) + usd_replicate(stage, plan.sources, plan.destinations, env_ids, plan.clone_mask) primitive_prims = sim_utils.get_all_matching_child_prims( "/World/envs", predicate=lambda prim: prim.GetTypeName() in expected_types @@ -335,9 +346,8 @@ def _run_colocation_collision_filter(sim, asset_cfg, expected_types, assert_coun assert primitive_prim.GetTypeName() == expected_types[i % len(expected_types)] sim.reset() - object_view_regex = f"{clone_cfg.clone_regex}/Object".replace(".*", "*") physics_sim_view = sim.physics_manager.get_physics_sim_view() - physx_view = physics_sim_view.create_rigid_body_view(object_view_regex) + physx_view = physics_sim_view.create_rigid_body_view("/World/envs/env_*/Object") for _ in range(100): sim.step() transforms = wp.to_torch(physx_view.get_transforms()) From 4feb184efe2f67fff8a7e28664770484c6d264d8 Mon Sep 17 00:00:00 2001 From: "isaaclab-bot[bot]" <282401363+isaaclab-bot[bot]@users.noreply.github.com> Date: Mon, 11 May 2026 06:19:01 +0000 Subject: [PATCH 34/51] [CI][Auto Version Bump] Compile changelog fragments (schedule) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Bumped packages: - isaaclab: 4.8.2 → 5.0.0 - isaaclab_newton: 0.7.1 → 0.7.2 - isaaclab_physx: 0.6.2 → 0.6.3 --- .../clone-plan-visualizer-cleanup.minor.rst | 35 ----------- .../octi-cloner_ordering.major.rst | 29 ---------- source/isaaclab/config/extension.toml | 2 +- source/isaaclab/docs/CHANGELOG.rst | 58 +++++++++++++++++++ .../changelog.d/octi-cloner_ordering.rst | 5 -- source/isaaclab_newton/config/extension.toml | 2 +- source/isaaclab_newton/docs/CHANGELOG.rst | 10 ++++ .../changelog.d/octi-cloner_ordering.skip | 0 .../changelog.d/octi-cloner_ordering.rst | 5 -- source/isaaclab_physx/config/extension.toml | 2 +- source/isaaclab_physx/docs/CHANGELOG.rst | 10 ++++ 11 files changed, 81 insertions(+), 77 deletions(-) delete mode 100644 source/isaaclab/changelog.d/clone-plan-visualizer-cleanup.minor.rst delete mode 100644 source/isaaclab/changelog.d/octi-cloner_ordering.major.rst delete mode 100644 source/isaaclab_newton/changelog.d/octi-cloner_ordering.rst delete mode 100644 source/isaaclab_ovphysx/changelog.d/octi-cloner_ordering.skip delete mode 100644 source/isaaclab_physx/changelog.d/octi-cloner_ordering.rst diff --git a/source/isaaclab/changelog.d/clone-plan-visualizer-cleanup.minor.rst b/source/isaaclab/changelog.d/clone-plan-visualizer-cleanup.minor.rst deleted file mode 100644 index c9ceb9405226..000000000000 --- a/source/isaaclab/changelog.d/clone-plan-visualizer-cleanup.minor.rst +++ /dev/null @@ -1,35 +0,0 @@ -Added -^^^^^ - -* Added :class:`~isaaclab.cloner.ClonePlan` as the flat clone contract shared by - scene cloning, backend replication, and scene-data providers. -* Added :meth:`~isaaclab.sim.SimulationContext.get_clone_plan` and - :meth:`~isaaclab.sim.SimulationContext.set_clone_plan` for publishing the - scene's clone plan. -* Added :attr:`~isaaclab.scene.InteractiveScene.clone_plan` for consumers holding - a scene reference. - -Changed -^^^^^^^ - -* **Breaking:** Changed scene-data providers to build visualizer backend models - from :meth:`~isaaclab.sim.SimulationContext.get_clone_plan` instead of a - clone-time visualizer artifact. Use the published - :class:`~isaaclab.cloner.ClonePlan` for custom scene-data integrations. - -Removed -^^^^^^^ - -* **Breaking:** Removed - :attr:`~isaaclab.cloner.TemplateCloneCfg.visualizer_clone_fn`, - :func:`~isaaclab.cloner.resolve_visualizer_clone_fn`, and - :class:`~isaaclab.physics.scene_data_requirements.VisualizerPrebuiltArtifacts`. - Use the :class:`~isaaclab.cloner.ClonePlan` published through - :meth:`~isaaclab.sim.SimulationContext.get_clone_plan` instead. -* **Breaking:** Removed - :meth:`~isaaclab.sim.SimulationContext.get_scene_data_visualizer_prebuilt_artifact`, - :meth:`~isaaclab.sim.SimulationContext.set_scene_data_visualizer_prebuilt_artifact`, - and - :meth:`~isaaclab.sim.SimulationContext.clear_scene_data_visualizer_prebuilt_artifact`. - Use :meth:`~isaaclab.sim.SimulationContext.get_clone_plan` / - :meth:`~isaaclab.sim.SimulationContext.set_clone_plan` instead. diff --git a/source/isaaclab/changelog.d/octi-cloner_ordering.major.rst b/source/isaaclab/changelog.d/octi-cloner_ordering.major.rst deleted file mode 100644 index fd0906e5cd66..000000000000 --- a/source/isaaclab/changelog.d/octi-cloner_ordering.major.rst +++ /dev/null @@ -1,29 +0,0 @@ -Added -^^^^^ - -* Added explicit ``spawn_paths`` support to multi-asset spawners so scene - planning can spawn representative heterogeneous sources directly. - -Changed -^^^^^^^ - -* **Breaking:** Changed :class:`~isaaclab.scene.InteractiveScene` to build clone - plans directly from asset configuration, spawn representative sources in their - selected environments, and replicate from those sources instead of spawning and - discovering prototypes under ``/World/template``. -* **Breaking:** Replaced ``TemplateCloneCfg`` with - :class:`~isaaclab.cloner.CloneCfg` for clone execution settings. -* **Breaking:** Changed :func:`~isaaclab.cloner.make_clone_plan` to return a - :class:`~isaaclab.cloner.ClonePlan` object directly. -* **Breaking:** Changed clone plan publication to use - :meth:`~isaaclab.sim.SimulationContext.get_clone_plan` and - :meth:`~isaaclab.sim.SimulationContext.set_clone_plan` for the single scene - clone plan. - -Removed -^^^^^^^ - -* **Breaking:** Removed :func:`~isaaclab.cloner.clone_from_template`. Use - :func:`~isaaclab.cloner.make_clone_plan`, - :func:`~isaaclab.cloner.usd_replicate`, and backend physics replication - functions for direct cloning workflows. diff --git a/source/isaaclab/config/extension.toml b/source/isaaclab/config/extension.toml index 338691cd0c00..70492269607c 100644 --- a/source/isaaclab/config/extension.toml +++ b/source/isaaclab/config/extension.toml @@ -1,7 +1,7 @@ [package] # Note: Semantic Versioning is used: https://semver.org/ -version = "4.8.2" +version = "5.0.0" # Description title = "Isaac Lab framework for Robot Learning" diff --git a/source/isaaclab/docs/CHANGELOG.rst b/source/isaaclab/docs/CHANGELOG.rst index 186d00855ac4..77a0b816c5d9 100644 --- a/source/isaaclab/docs/CHANGELOG.rst +++ b/source/isaaclab/docs/CHANGELOG.rst @@ -1,6 +1,64 @@ Changelog --------- +5.0.0 (2026-05-11) +~~~~~~~~~~~~~~~~~~ + +Added +^^^^^ + +* Added :class:`~isaaclab.cloner.ClonePlan` as the flat clone contract shared by + scene cloning, backend replication, and scene-data providers. +* Added :meth:`~isaaclab.sim.SimulationContext.get_clone_plan` and + :meth:`~isaaclab.sim.SimulationContext.set_clone_plan` for publishing the + scene's clone plan. +* Added :attr:`~isaaclab.scene.InteractiveScene.clone_plan` for consumers holding + a scene reference. +* Added explicit ``spawn_paths`` support to multi-asset spawners so scene + planning can spawn representative heterogeneous sources directly. + +Changed +^^^^^^^ + +* **Breaking:** Changed scene-data providers to build visualizer backend models + from :meth:`~isaaclab.sim.SimulationContext.get_clone_plan` instead of a + clone-time visualizer artifact. Use the published + :class:`~isaaclab.cloner.ClonePlan` for custom scene-data integrations. +* **Breaking:** Changed :class:`~isaaclab.scene.InteractiveScene` to build clone + plans directly from asset configuration, spawn representative sources in their + selected environments, and replicate from those sources instead of spawning and + discovering prototypes under ``/World/template``. +* **Breaking:** Replaced ``TemplateCloneCfg`` with + :class:`~isaaclab.cloner.CloneCfg` for clone execution settings. +* **Breaking:** Changed :func:`~isaaclab.cloner.make_clone_plan` to return a + :class:`~isaaclab.cloner.ClonePlan` object directly. +* **Breaking:** Changed clone plan publication to use + :meth:`~isaaclab.sim.SimulationContext.get_clone_plan` and + :meth:`~isaaclab.sim.SimulationContext.set_clone_plan` for the single scene + clone plan. + +Removed +^^^^^^^ + +* **Breaking:** Removed + :attr:`~isaaclab.cloner.TemplateCloneCfg.visualizer_clone_fn`, + :func:`~isaaclab.cloner.resolve_visualizer_clone_fn`, and + :class:`~isaaclab.physics.scene_data_requirements.VisualizerPrebuiltArtifacts`. + Use the :class:`~isaaclab.cloner.ClonePlan` published through + :meth:`~isaaclab.sim.SimulationContext.get_clone_plan` instead. +* **Breaking:** Removed + :meth:`~isaaclab.sim.SimulationContext.get_scene_data_visualizer_prebuilt_artifact`, + :meth:`~isaaclab.sim.SimulationContext.set_scene_data_visualizer_prebuilt_artifact`, + and + :meth:`~isaaclab.sim.SimulationContext.clear_scene_data_visualizer_prebuilt_artifact`. + Use :meth:`~isaaclab.sim.SimulationContext.get_clone_plan` / + :meth:`~isaaclab.sim.SimulationContext.set_clone_plan` instead. +* **Breaking:** Removed :func:`~isaaclab.cloner.clone_from_template`. Use + :func:`~isaaclab.cloner.make_clone_plan`, + :func:`~isaaclab.cloner.usd_replicate`, and backend physics replication + functions for direct cloning workflows. + + 4.8.2 (2026-05-10) ~~~~~~~~~~~~~~~~~~ diff --git a/source/isaaclab_newton/changelog.d/octi-cloner_ordering.rst b/source/isaaclab_newton/changelog.d/octi-cloner_ordering.rst deleted file mode 100644 index 807d81e7c558..000000000000 --- a/source/isaaclab_newton/changelog.d/octi-cloner_ordering.rst +++ /dev/null @@ -1,5 +0,0 @@ -Changed -^^^^^^^ - -* Changed rigid object collection spawning to honor planned ``spawn_path`` - values while falling back to ``prim_path`` for direct construction. diff --git a/source/isaaclab_newton/config/extension.toml b/source/isaaclab_newton/config/extension.toml index 0a55aaddb353..ee6aa21d379f 100644 --- a/source/isaaclab_newton/config/extension.toml +++ b/source/isaaclab_newton/config/extension.toml @@ -1,7 +1,7 @@ [package] # Note: Semantic Versioning is used: https://semver.org/ -version = "0.7.1" +version = "0.7.2" # Description title = "Newton simulation interfaces for IsaacLab core package" diff --git a/source/isaaclab_newton/docs/CHANGELOG.rst b/source/isaaclab_newton/docs/CHANGELOG.rst index a472bf0643c6..7ed2a512d2e1 100644 --- a/source/isaaclab_newton/docs/CHANGELOG.rst +++ b/source/isaaclab_newton/docs/CHANGELOG.rst @@ -1,6 +1,16 @@ Changelog --------- +0.7.2 (2026-05-11) +~~~~~~~~~~~~~~~~~~ + +Changed +^^^^^^^ + +* Changed rigid object collection spawning to honor planned ``spawn_path`` + values while falling back to ``prim_path`` for direct construction. + + 0.7.1 (2026-05-09) ~~~~~~~~~~~~~~~~~~ diff --git a/source/isaaclab_ovphysx/changelog.d/octi-cloner_ordering.skip b/source/isaaclab_ovphysx/changelog.d/octi-cloner_ordering.skip deleted file mode 100644 index e69de29bb2d1..000000000000 diff --git a/source/isaaclab_physx/changelog.d/octi-cloner_ordering.rst b/source/isaaclab_physx/changelog.d/octi-cloner_ordering.rst deleted file mode 100644 index 807d81e7c558..000000000000 --- a/source/isaaclab_physx/changelog.d/octi-cloner_ordering.rst +++ /dev/null @@ -1,5 +0,0 @@ -Changed -^^^^^^^ - -* Changed rigid object collection spawning to honor planned ``spawn_path`` - values while falling back to ``prim_path`` for direct construction. diff --git a/source/isaaclab_physx/config/extension.toml b/source/isaaclab_physx/config/extension.toml index d630d9c945c8..4e00f31716d6 100644 --- a/source/isaaclab_physx/config/extension.toml +++ b/source/isaaclab_physx/config/extension.toml @@ -1,7 +1,7 @@ [package] # Note: Semantic Versioning is used: https://semver.org/ -version = "0.6.2" +version = "0.6.3" # Description title = "PhysX simulation interfaces for IsaacLab core package" diff --git a/source/isaaclab_physx/docs/CHANGELOG.rst b/source/isaaclab_physx/docs/CHANGELOG.rst index 0220a659e721..95e059b045b6 100644 --- a/source/isaaclab_physx/docs/CHANGELOG.rst +++ b/source/isaaclab_physx/docs/CHANGELOG.rst @@ -1,6 +1,16 @@ Changelog --------- +0.6.3 (2026-05-11) +~~~~~~~~~~~~~~~~~~ + +Changed +^^^^^^^ + +* Changed rigid object collection spawning to honor planned ``spawn_path`` + values while falling back to ``prim_path`` for direct construction. + + 0.6.2 (2026-05-09) ~~~~~~~~~~~~~~~~~~ From e1fba6e2e8459a33e8cdfc589e8c1c5d21b5bd8c Mon Sep 17 00:00:00 2001 From: Kelly Guo Date: Mon, 11 May 2026 16:10:21 -0700 Subject: [PATCH 35/51] Fixes benchmark scripts when tensorboard logs are missing (#5564) # Description When benchmarking scripts are executed with num_iterations set to below the threshold for reward logging, the run can produce missing reward data. However, the scripts are hardcoded to always parse rewards from tensorboard, which may not exist in these cases. This change patches the RL benchmarking scripts to only process rewards logging if they were written to tensorboard. ## Type of change - Bug fix (non-breaking change which fixes an issue) ## Checklist - [x] I have read and understood the [contribution guidelines](https://isaac-sim.github.io/IsaacLab/main/source/refs/contributing.html) - [x] I have run the [`pre-commit` checks](https://pre-commit.com/) with `./isaaclab.sh --format` - [x] I have made corresponding changes to the documentation - [x] My changes generate no new warnings - [x] I have added tests that prove my fix is effective or that my feature works - [ ] I have updated the changelog and the corresponding version in the extension's `config/extension.toml` file - [ ] I have added my name to the `CONTRIBUTORS.md` or my name already exists there --- scripts/benchmarks/benchmark_rlgames.py | 19 ++-- scripts/benchmarks/benchmark_rsl_rl.py | 20 ++--- .../benchmarks/test/test_training_metrics.py | 90 +++++++++++++++++++ scripts/benchmarks/utils.py | 46 ++++++++++ 4 files changed, 148 insertions(+), 27 deletions(-) create mode 100644 scripts/benchmarks/test/test_training_metrics.py diff --git a/scripts/benchmarks/benchmark_rlgames.py b/scripts/benchmarks/benchmark_rlgames.py index ab1d625d5aaf..52257f722651 100644 --- a/scripts/benchmarks/benchmark_rlgames.py +++ b/scripts/benchmarks/benchmark_rlgames.py @@ -103,13 +103,9 @@ from scripts.benchmarks.utils import ( get_backend_type, get_preset_string, - get_success_rate_log, log_app_start_time, - log_convergence, log_python_imports_time, - log_rl_policy_episode_lengths, - log_rl_policy_rewards, - log_rl_policy_success_rates, + log_rl_training_metrics, log_runtime_step_times, log_scene_creation_time, log_simulation_start_time, @@ -288,15 +284,12 @@ def main( log_simulation_start_time(benchmark, Timer.get_timer_info("simulation_start") * 1000) log_total_start_time(benchmark, (task_startup_time_end - app_start_time_begin) / 1e6) log_runtime_step_times(benchmark, rl_training_times, compute_stats=True) - log_rl_policy_rewards(benchmark, log_data["rewards/iter"]) - log_rl_policy_episode_lengths(benchmark, log_data["episode_lengths/iter"]) - success_rates = get_success_rate_log(log_data) - if success_rates is not None: - log_rl_policy_success_rates(benchmark, success_rates) - log_convergence( + log_rl_training_metrics( benchmark, - log_data["rewards/iter"], - args_cli.task, + log_data, + reward_tag="rewards/iter", + episode_length_tag="episode_lengths/iter", + task=args_cli.task, workflow="rl_games", should_check_convergence=args_cli.check_convergence, reward_threshold=args_cli.reward_threshold, diff --git a/scripts/benchmarks/benchmark_rsl_rl.py b/scripts/benchmarks/benchmark_rsl_rl.py index 0eef6063fba7..2afb1f74833b 100644 --- a/scripts/benchmarks/benchmark_rsl_rl.py +++ b/scripts/benchmarks/benchmark_rsl_rl.py @@ -105,13 +105,9 @@ from scripts.benchmarks.utils import ( get_backend_type, get_preset_string, - get_success_rate_log, log_app_start_time, - log_convergence, log_python_imports_time, - log_rl_policy_episode_lengths, - log_rl_policy_rewards, - log_rl_policy_success_rates, + log_rl_training_metrics, log_runtime_step_times, log_scene_creation_time, log_simulation_start_time, @@ -287,16 +283,12 @@ def main( log_simulation_start_time(benchmark, Timer.get_timer_info("simulation_start") * 1000) log_total_start_time(benchmark, (task_startup_time_end - app_start_time_begin) / 1e6) log_runtime_step_times(benchmark, rl_training_times, compute_stats=True) - log_rl_policy_rewards(benchmark, log_data["Train/mean_reward"]) - log_rl_policy_episode_lengths(benchmark, log_data["Train/mean_episode_length"]) - success_rates = get_success_rate_log(log_data) - if success_rates is not None: - log_rl_policy_success_rates(benchmark, success_rates) - - log_convergence( + log_rl_training_metrics( benchmark, - log_data["Train/mean_reward"], - args_cli.task, + log_data, + reward_tag="Train/mean_reward", + episode_length_tag="Train/mean_episode_length", + task=args_cli.task, workflow="rsl_rl", should_check_convergence=args_cli.check_convergence, reward_threshold=args_cli.reward_threshold, diff --git a/scripts/benchmarks/test/test_training_metrics.py b/scripts/benchmarks/test/test_training_metrics.py new file mode 100644 index 000000000000..a3187fb15cc9 --- /dev/null +++ b/scripts/benchmarks/test/test_training_metrics.py @@ -0,0 +1,90 @@ +# Copyright (c) 2022-2026, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md). +# All rights reserved. +# +# SPDX-License-Identifier: BSD-3-Clause + +"""Unit tests for benchmark training-metric logging helpers.""" + +from __future__ import annotations + +import pytest + +from scripts.benchmarks.utils import SUCCESS_RATE_LOG_TAGS, log_rl_training_metrics + + +class _FakeBenchmark: + """Collect benchmark measurements without initializing benchmark backends.""" + + def __init__(self): + self.measurements: list[tuple[str, str, object, str]] = [] + + def add_measurement(self, phase, measurement): + self.measurements.append((phase, measurement.name, measurement.value, getattr(measurement, "unit", ""))) + + def measurement_by_name(self, name: str): + return next(m for m in self.measurements if m[1] == name) + + +@pytest.mark.parametrize( + "workflow,reward_tag,episode_length_tag", + [ + ("rl_games", "rewards/iter", "episode_lengths/iter"), + ("rsl_rl", "Train/mean_reward", "Train/mean_episode_length"), + ], +) +def test_log_rl_training_metrics_skips_missing_short_run_scalars( + workflow: str, reward_tag: str, episode_length_tag: str, capsys: pytest.CaptureFixture[str] +): + """Short benchmark runs may finish before reward and episode-length scalars are emitted.""" + benchmark = _FakeBenchmark() + + log_rl_training_metrics( + benchmark, + log_data={}, + reward_tag=reward_tag, + episode_length_tag=episode_length_tag, + task="Isaac-Ant-v0", + workflow=workflow, + should_check_convergence=True, + ) + + assert benchmark.measurements == [] + output = capsys.readouterr().out + assert f"TensorBoard log is missing '{reward_tag}'" in output + assert f"TensorBoard log is missing '{episode_length_tag}'" in output + assert f"Cannot check convergence because '{reward_tag}' was not logged" in output + + +@pytest.mark.parametrize( + "workflow,reward_tag,episode_length_tag", + [ + ("rl_games", "rewards/iter", "episode_lengths/iter"), + ("rsl_rl", "Train/mean_reward", "Train/mean_episode_length"), + ], +) +def test_log_rl_training_metrics_logs_present_normal_run_scalars( + workflow: str, reward_tag: str, episode_length_tag: str, capsys: pytest.CaptureFixture[str] +): + """Normal runs with reward and episode-length scalars should log train metrics.""" + benchmark = _FakeBenchmark() + + log_rl_training_metrics( + benchmark, + log_data={ + reward_tag: [1.0, 2.0, 3.0], + episode_length_tag: [10.0, 11.0], + SUCCESS_RATE_LOG_TAGS[0]: [0.25, 0.5], + }, + reward_tag=reward_tag, + episode_length_tag=episode_length_tag, + task="Isaac-Ant-v0", + workflow=workflow, + ) + + assert benchmark.measurement_by_name("Rewards")[2] == [1.0, 2.0, 3.0] + assert benchmark.measurement_by_name("Max Rewards")[2] == 3.0 + assert benchmark.measurement_by_name("Episode Lengths")[2] == [10.0, 11.0] + assert benchmark.measurement_by_name("Max Episode Lengths")[2] == 11.0 + assert benchmark.measurement_by_name("Success Rates")[2] == [0.25, 0.5] + assert benchmark.measurement_by_name("success_rate")[2] == 0.5 + assert "TensorBoard log is missing" not in capsys.readouterr().out diff --git a/scripts/benchmarks/utils.py b/scripts/benchmarks/utils.py index e157765adb0e..05effa524172 100644 --- a/scripts/benchmarks/utils.py +++ b/scripts/benchmarks/utils.py @@ -295,6 +295,52 @@ def log_success(benchmark, tracker, framework_iteration_count: int | None = None ) +def log_rl_training_metrics( + benchmark: BaseIsaacLabBenchmark, + log_data: dict[str, list[float]], + reward_tag: str, + episode_length_tag: str, + task: str, + workflow: str, + should_check_convergence: bool = False, + reward_threshold: float | None = None, + convergence_config: str = "full", +) -> None: + """Log optional RL training metrics from TensorBoard data. + + Short smoke-test runs can finish before the RL framework emits reward or + episode-length scalars. Missing tags should skip those measurements instead + of failing the whole benchmark. + """ + rewards = log_data.get(reward_tag) + episode_lengths = log_data.get(episode_length_tag) + if rewards: + log_rl_policy_rewards(benchmark, rewards) + else: + print(f"[WARNING] TensorBoard log is missing '{reward_tag}'; skipping reward benchmark metrics.") + if episode_lengths: + log_rl_policy_episode_lengths(benchmark, episode_lengths) + else: + print(f"[WARNING] TensorBoard log is missing '{episode_length_tag}'; skipping episode-length metrics.") + + success_rates = get_success_rate_log(log_data) + if success_rates is not None: + log_rl_policy_success_rates(benchmark, success_rates) + + if rewards: + log_convergence( + benchmark, + rewards, + task, + workflow=workflow, + should_check_convergence=should_check_convergence, + reward_threshold=reward_threshold, + convergence_config=convergence_config, + ) + elif should_check_convergence: + print(f"[WARNING] Cannot check convergence because '{reward_tag}' was not logged.") + + def parse_cprofile_stats( profile: cProfile.Profile, isaaclab_prefixes: list[str], From 5442de1475bd15fe4c9eccf83dcb10d107a4c6e0 Mon Sep 17 00:00:00 2001 From: hougantc-nvda <127865892+hougantc-nvda@users.noreply.github.com> Date: Mon, 11 May 2026 19:13:59 -0400 Subject: [PATCH 36/51] Fixes manus docs moving. (#5577) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit # Description Please include a summary of the change and which issue is fixed. Please also include relevant motivation and context. List any dependencies that are required for this change. Fixes # (issue) ## Type of change - Documentation update ## Screenshots Please attach before and after screenshots of the change if applicable. ## Checklist - [ ] I have read and understood the [contribution guidelines](https://isaac-sim.github.io/IsaacLab/main/source/refs/contributing.html) - [ ] I have run the [`pre-commit` checks](https://pre-commit.com/) with `./isaaclab.sh --format` - [ ] I have made corresponding changes to the documentation - [ ] My changes generate no new warnings - [ ] I have added tests that prove my fix is effective or that my feature works - [ ] I have updated the changelog and the corresponding version in the extension's `config/extension.toml` file - [ ] I have added my name to the `CONTRIBUTORS.md` or my name already exists there --- docs/source/how-to/cloudxr_teleoperation.rst | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/source/how-to/cloudxr_teleoperation.rst b/docs/source/how-to/cloudxr_teleoperation.rst index 3613228d5b7f..9ddc95d4dfd9 100644 --- a/docs/source/how-to/cloudxr_teleoperation.rst +++ b/docs/source/how-to/cloudxr_teleoperation.rst @@ -404,7 +404,7 @@ API as headset-based optical hand tracking in Isaac Teleop, so the same retarget work with both input sources. For plugin configuration details, see the `Manus plugin documentation -`_. +`_. The recommended workflow: From 707e87d13d42b1912137b303561741613c722669 Mon Sep 17 00:00:00 2001 From: Piotr Barejko Date: Mon, 11 May 2026 18:34:50 -0700 Subject: [PATCH 37/51] Pre and post physics renderer initialization (#5573) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit # Description Please include a summary of the change and which issue is fixed. Please also include relevant motivation and context. List any dependencies that are required for this change. Fixes # (issue) ## Type of change - Bug fix (non-breaking change which fixes an issue) - New feature (non-breaking change which adds functionality) - Breaking change (existing functionality will not work without user modification) - Documentation update ## Screenshots Please attach before and after screenshots of the change if applicable. ## Checklist - [ ] I have read and understood the [contribution guidelines](https://isaac-sim.github.io/IsaacLab/main/source/refs/contributing.html) - [ ] I have run the [`pre-commit` checks](https://pre-commit.com/) with `./isaaclab.sh --format` - [ ] I have made corresponding changes to the documentation - [ ] My changes generate no new warnings - [ ] I have added tests that prove my fix is effective or that my feature works - [ ] I have updated the changelog and the corresponding version in the extension's `config/extension.toml` file - [ ] I have added my name to the `CONTRIBUTORS.md` or my name already exists there --- .../scene-initialize-renderers.minor.rst | 31 +++++++++++++++ .../isaaclab/isaaclab/envs/direct_marl_env.py | 1 + .../isaaclab/isaaclab/envs/direct_rl_env.py | 1 + .../isaaclab/envs/leapp_deployment_env.py | 1 + .../isaaclab/envs/manager_based_env.py | 1 + .../isaaclab/renderers/base_renderer.py | 4 ++ .../isaaclab/renderers/render_context.py | 12 ++++++ .../isaaclab/scene/interactive_scene.py | 38 +++++++++++++++++++ .../isaaclab/sim/simulation_context.py | 9 ++++- .../scene-initialize-renderers.rst | 10 +++++ .../envs/direct_rl_env_warp.py | 1 + .../envs/manager_based_env_warp.py | 1 + .../scene-initialize-renderers.rst | 9 +++++ .../renderers/newton_warp_renderer.py | 19 ++++++---- .../scene-initialize-renderers.rst | 20 ++++++++++ .../isaaclab_ov/renderers/ovrtx_renderer.py | 30 ++++++++------- 16 files changed, 167 insertions(+), 21 deletions(-) create mode 100644 source/isaaclab/changelog.d/scene-initialize-renderers.minor.rst create mode 100644 source/isaaclab_experimental/changelog.d/scene-initialize-renderers.rst create mode 100644 source/isaaclab_newton/changelog.d/scene-initialize-renderers.rst create mode 100644 source/isaaclab_ov/changelog.d/scene-initialize-renderers.rst diff --git a/source/isaaclab/changelog.d/scene-initialize-renderers.minor.rst b/source/isaaclab/changelog.d/scene-initialize-renderers.minor.rst new file mode 100644 index 000000000000..86e29205be95 --- /dev/null +++ b/source/isaaclab/changelog.d/scene-initialize-renderers.minor.rst @@ -0,0 +1,31 @@ +Added +^^^^^ + +* Added :meth:`~isaaclab.scene.InteractiveScene.initialize_renderers` to + pre-create renderer backends for all scene sensors with a + ``renderer_cfg`` against the shared + :class:`~isaaclab.renderers.render_context.RenderContext`. The method is + idempotent and is now invoked from + :class:`~isaaclab.envs.DirectRLEnv`, + :class:`~isaaclab.envs.DirectMARLEnv`, + :class:`~isaaclab.envs.ManagerBasedEnv`, and + :class:`~isaaclab.envs.LeappDeploymentEnv` after scene construction so + that renderer backend creation order is deterministic and front-loaded + before the first :meth:`~isaaclab.sim.SimulationContext.reset`. +* Added :meth:`~isaaclab.renderers.base_renderer.BaseRenderer.initialize` + post-physics lifecycle hook (default no-op) that runs once per backend + after :meth:`~isaaclab.sim.SimulationContext.reset` builds physics + models. ``__init__`` now defines the pre-physics phase (eagerly invoked + by :meth:`~isaaclab.scene.InteractiveScene.initialize_renderers`) and + ``initialize`` defines the post-physics phase, letting backends whose + setup needs scene data (e.g. a built Newton model) defer that work + cleanly. Driven by + :meth:`~isaaclab.renderers.render_context.RenderContext.ensure_initialize`, + registered on + :class:`~isaaclab.physics.physics_manager.PhysicsEvent` ``PHYSICS_READY`` + by :class:`~isaaclab.sim.SimulationContext` at ``order=5`` so it fires + before sensor/asset callbacks (``order=10``). This decouples renderer + post-physics setup from camera initialization. Backends created lazily + after PHYSICS_READY are eagerly initialized at + :meth:`~isaaclab.renderers.render_context.RenderContext.get_renderer` + time. diff --git a/source/isaaclab/isaaclab/envs/direct_marl_env.py b/source/isaaclab/isaaclab/envs/direct_marl_env.py index b8fda8cf0986..56d3a38cdd1c 100644 --- a/source/isaaclab/isaaclab/envs/direct_marl_env.py +++ b/source/isaaclab/isaaclab/envs/direct_marl_env.py @@ -145,6 +145,7 @@ def _init_sim(self, render_mode: str | None = None, **kwargs): with use_stage(self.sim.stage): self.scene = InteractiveScene(self.cfg.scene) self._setup_scene() + self.scene.initialize_renderers() print("[INFO]: Scene manager: ", self.scene) # set up camera viewport controller diff --git a/source/isaaclab/isaaclab/envs/direct_rl_env.py b/source/isaaclab/isaaclab/envs/direct_rl_env.py index 9251eb0fe817..c03ca1f73596 100644 --- a/source/isaaclab/isaaclab/envs/direct_rl_env.py +++ b/source/isaaclab/isaaclab/envs/direct_rl_env.py @@ -150,6 +150,7 @@ def _init_sim(self, render_mode: str | None = None, **kwargs): with use_stage(self.sim.stage): self.scene = InteractiveScene(self.cfg.scene) self._setup_scene() + self.scene.initialize_renderers() print("[INFO]: Scene manager: ", self.scene) # set up camera viewport controller diff --git a/source/isaaclab/isaaclab/envs/leapp_deployment_env.py b/source/isaaclab/isaaclab/envs/leapp_deployment_env.py index fe81e8f82e5f..3284284570fe 100644 --- a/source/isaaclab/isaaclab/envs/leapp_deployment_env.py +++ b/source/isaaclab/isaaclab/envs/leapp_deployment_env.py @@ -183,6 +183,7 @@ def __init__(self, cfg: Any, leapp_yaml_path: str): with use_stage(self.sim.stage): self.scene = InteractiveScene(cfg.scene) + self.scene.initialize_renderers() with use_stage(self.sim.stage): self.sim.reset() self.scene.update(dt=self.physics_dt) diff --git a/source/isaaclab/isaaclab/envs/manager_based_env.py b/source/isaaclab/isaaclab/envs/manager_based_env.py index 92db9ad117b5..620cf2895718 100644 --- a/source/isaaclab/isaaclab/envs/manager_based_env.py +++ b/source/isaaclab/isaaclab/envs/manager_based_env.py @@ -169,6 +169,7 @@ def _init_sim(self): # set the stage context for scene creation steps which use the stage with use_stage(self.sim.stage): self.scene = InteractiveScene(self.cfg.scene) + self.scene.initialize_renderers() print("[INFO]: Scene manager: ", self.scene) # set up camera viewport controller diff --git a/source/isaaclab/isaaclab/renderers/base_renderer.py b/source/isaaclab/isaaclab/renderers/base_renderer.py index 2fc498eae8e3..be0da6e1c116 100644 --- a/source/isaaclab/isaaclab/renderers/base_renderer.py +++ b/source/isaaclab/isaaclab/renderers/base_renderer.py @@ -22,6 +22,10 @@ class BaseRenderer(ABC): """Abstract base class for renderer implementations.""" + def initialize(self) -> None: + """Post-physics one-time initialization hook. Called only once.""" + return + @abstractmethod def supported_output_types(self) -> dict[RenderBufferKind, RenderBufferSpec]: """Per-output layout (channels + dtype) this renderer can produce. diff --git a/source/isaaclab/isaaclab/renderers/render_context.py b/source/isaaclab/isaaclab/renderers/render_context.py index 1c1a45a19454..a6e49883350b 100644 --- a/source/isaaclab/isaaclab/renderers/render_context.py +++ b/source/isaaclab/isaaclab/renderers/render_context.py @@ -33,6 +33,7 @@ class RenderContext: __slots__ = ( "_renderer_entries", + "_physics_initialized", "_prepared_renderer_ids", "_prepared_num_envs", "_last_transforms_step", @@ -40,6 +41,7 @@ class RenderContext: def __init__(self) -> None: self._renderer_entries: list[tuple[RendererCfg, BaseRenderer]] = [] + self._physics_initialized: bool = False # Set to True after the first PHYSICS_READY callback fires. self._prepared_renderer_ids: set[int] = set() self._prepared_num_envs: int | None = None self._last_transforms_step: int | None = None @@ -65,8 +67,18 @@ def get_renderer(self, cfg: RendererCfg) -> BaseRenderer: "Created new renderer for simulation: %s", type(new_renderer).__name__, ) + if self._physics_initialized: + new_renderer.initialize() return new_renderer + def ensure_initialize(self) -> None: + """Idempotent call fired after PHYSICS_READY callback.""" + if self._physics_initialized: + return + self._physics_initialized = True + for _cfg, renderer in self._renderer_entries: + renderer.initialize() + def ensure_prepare_stage(self, stage: Any, num_envs: int) -> None: """Call :meth:`BaseRenderer.prepare_stage` for each registered backend (once per backend). diff --git a/source/isaaclab/isaaclab/scene/interactive_scene.py b/source/isaaclab/isaaclab/scene/interactive_scene.py index ae39e3daa719..6b13afb4565f 100644 --- a/source/isaaclab/isaaclab/scene/interactive_scene.py +++ b/source/isaaclab/isaaclab/scene/interactive_scene.py @@ -12,6 +12,8 @@ if TYPE_CHECKING: from isaaclab_physx.assets import DeformableObject, SurfaceGripper + from isaaclab.renderers.base_renderer import BaseRenderer + import torch import warp as wp @@ -364,6 +366,42 @@ def _sensor_renderer_types(self) -> list[str]: if (rcfg := getattr(getattr(s, "cfg", None), "renderer_cfg", None)) is not None ] + def initialize_renderers(self) -> list[BaseRenderer]: + """Pre-create renderer backends for all scene sensors with a ``renderer_cfg``. + + Walks the constructed sensors and registers each unique + :class:`~isaaclab.renderers.renderer_cfg.RendererCfg` with the + simulation-scoped :class:`~isaaclab.renderers.render_context.RenderContext`. + Configs that compare equal share a single backend (see + :meth:`~isaaclab.renderers.render_context.RenderContext.get_renderer`), so + calling this method is idempotent and safe to invoke before + :meth:`~isaaclab.sim.SimulationContext.reset`. + + Pre-creating backends here makes the order of renderer construction + deterministic (matches sensor registration order) and front-loads logging + instead of trickling out during the first :meth:`Camera._initialize_impl`. + :meth:`~isaaclab.renderers.base_renderer.BaseRenderer.prepare_stage` is + intentionally not invoked here; it runs on first camera initialization + with the correct ``num_envs`` and final stage. + + Returns: + The list of unique renderer backends now registered on the + shared :class:`~isaaclab.renderers.render_context.RenderContext`, + in sensor registration order. + """ + ctx = self.sim.render_context + backends: list[BaseRenderer] = [] + seen: set[int] = set() + for sensor in self._sensors.values(): + rcfg = getattr(getattr(sensor, "cfg", None), "renderer_cfg", None) + if rcfg is None: + continue + backend = ctx.get_renderer(rcfg) + if id(backend) not in seen: + seen.add(id(backend)) + backends.append(backend) + return backends + def filter_collisions(self, global_prim_paths: list[str] | None = None): """Filter environments collisions. diff --git a/source/isaaclab/isaaclab/sim/simulation_context.py b/source/isaaclab/isaaclab/sim/simulation_context.py index 121b01fdb622..607221bd4874 100644 --- a/source/isaaclab/isaaclab/sim/simulation_context.py +++ b/source/isaaclab/isaaclab/sim/simulation_context.py @@ -23,7 +23,7 @@ from isaaclab.app.settings_manager import SettingsManager from isaaclab.envs.utils.recording_hooks import run_recording_hooks_after_visualizers from isaaclab.markers.vis_marker_registry import VisMarkerRegistry -from isaaclab.physics import BaseSceneDataProvider, PhysicsManager, SceneDataProvider +from isaaclab.physics import BaseSceneDataProvider, PhysicsEvent, PhysicsManager, SceneDataProvider from isaaclab.physics.scene_data_requirements import ( SceneDataRequirement, resolve_scene_data_requirements, @@ -207,6 +207,13 @@ def __init__(self, cfg: SimulationCfg | None = None): # Shared renderers for all Camera sensors (compatible renderer_cfg only). self._render_context = RenderContext() + # Run renderer post-physics setup. + self.physics_manager.register_callback( + lambda _payload: self._render_context.ensure_initialize(), + PhysicsEvent.PHYSICS_READY, + order=5, + ) + type(self)._instance = self # Mark as valid singleton only after successful init def _apply_render_cfg_settings(self) -> None: diff --git a/source/isaaclab_experimental/changelog.d/scene-initialize-renderers.rst b/source/isaaclab_experimental/changelog.d/scene-initialize-renderers.rst new file mode 100644 index 000000000000..e33ce79b241e --- /dev/null +++ b/source/isaaclab_experimental/changelog.d/scene-initialize-renderers.rst @@ -0,0 +1,10 @@ +Changed +^^^^^^^ + +* Pre-create renderer backends in + :class:`~isaaclab_experimental.envs.ManagerBasedEnvWarp` and + :class:`~isaaclab_experimental.envs.DirectRLEnvWarp` by invoking + :meth:`~isaaclab.scene.InteractiveScene.initialize_renderers` after scene + construction so that renderer backend creation order is deterministic and + front-loaded before the first + :meth:`~isaaclab.sim.SimulationContext.reset`. diff --git a/source/isaaclab_experimental/isaaclab_experimental/envs/direct_rl_env_warp.py b/source/isaaclab_experimental/isaaclab_experimental/envs/direct_rl_env_warp.py index 125f2e61a429..20c82e582690 100644 --- a/source/isaaclab_experimental/isaaclab_experimental/envs/direct_rl_env_warp.py +++ b/source/isaaclab_experimental/isaaclab_experimental/envs/direct_rl_env_warp.py @@ -164,6 +164,7 @@ def __init__(self, cfg: DirectRLEnvCfg, render_mode: str | None = None, **kwargs with use_stage(self.sim.stage): self.scene = InteractiveSceneWarp(self.cfg.scene) self._setup_scene() + self.scene.initialize_renderers() # attach_stage_to_usd_context() print("[INFO]: Scene manager: ", self.scene) diff --git a/source/isaaclab_experimental/isaaclab_experimental/envs/manager_based_env_warp.py b/source/isaaclab_experimental/isaaclab_experimental/envs/manager_based_env_warp.py index 8c558b925947..5ace5168a9c8 100644 --- a/source/isaaclab_experimental/isaaclab_experimental/envs/manager_based_env_warp.py +++ b/source/isaaclab_experimental/isaaclab_experimental/envs/manager_based_env_warp.py @@ -132,6 +132,7 @@ def __init__(self, cfg: ManagerBasedEnvCfg): with use_stage(self.sim.stage): self.scene = InteractiveScene(self.cfg.scene) # attach_stage_to_usd_context() + self.scene.initialize_renderers() print("[INFO]: Scene manager: ", self.scene) # Shared per-env Warp RNG state (accessible to all managers/terms via `env`). diff --git a/source/isaaclab_newton/changelog.d/scene-initialize-renderers.rst b/source/isaaclab_newton/changelog.d/scene-initialize-renderers.rst new file mode 100644 index 000000000000..80eef5e9823b --- /dev/null +++ b/source/isaaclab_newton/changelog.d/scene-initialize-renderers.rst @@ -0,0 +1,9 @@ +Changed +^^^^^^^ + +* Split :class:`~isaaclab_newton.renderers.NewtonWarpRenderer` construction + into a pre-physics ``__init__`` (stores cfg and registers the Newton-Warp + scene-data requirement on + :class:`~isaaclab.sim.SimulationContext`) and a post-physics + :meth:`~isaaclab_newton.renderers.NewtonWarpRenderer.initialize` (reads + the built Newton model. diff --git a/source/isaaclab_newton/isaaclab_newton/renderers/newton_warp_renderer.py b/source/isaaclab_newton/isaaclab_newton/renderers/newton_warp_renderer.py index 78285636b6ef..0ba3558c3504 100644 --- a/source/isaaclab_newton/isaaclab_newton/renderers/newton_warp_renderer.py +++ b/source/isaaclab_newton/isaaclab_newton/renderers/newton_warp_renderer.py @@ -139,12 +139,15 @@ class NewtonWarpRenderer(BaseRenderer): RenderData = RenderData def __init__(self, cfg: NewtonWarpRendererCfg): + """Pre-physics initialization.""" from isaaclab.physics.scene_data_requirements import ( aggregate_requirements, requirement_for_renderer_type, ) self.cfg = cfg + self.newton_sensor: newton.sensors.SensorTiledCamera | None = None + sim = SimulationContext.instance() current_req = sim.get_scene_data_requirements() renderer_req = requirement_for_renderer_type("newton_warp") @@ -152,6 +155,8 @@ def __init__(self, cfg: NewtonWarpRendererCfg): if merged != current_req: sim.update_scene_data_requirements(merged) + def initialize(self) -> None: + """Post-physics setup: read the built Newton model and construct the sensor.""" newton_model = self.get_scene_data_provider().get_newton_model() if newton_model is None: raise RuntimeError( @@ -164,11 +169,11 @@ def __init__(self, cfg: NewtonWarpRendererCfg): self.newton_sensor = newton.sensors.SensorTiledCamera( newton_model, config=newton.sensors.SensorTiledCamera.RenderConfig( - enable_textures=cfg.enable_textures, - enable_shadows=cfg.enable_shadows, - enable_ambient_lighting=cfg.enable_ambient_lighting, - enable_backface_culling=cfg.enable_backface_culling, - max_distance=cfg.max_distance, + enable_textures=self.cfg.enable_textures, + enable_shadows=self.cfg.enable_shadows, + enable_ambient_lighting=self.cfg.enable_ambient_lighting, + enable_backface_culling=self.cfg.enable_backface_culling, + max_distance=self.cfg.max_distance, ), ) @@ -180,8 +185,8 @@ def __init__(self, cfg: NewtonWarpRendererCfg): if newton_model.shape_count > 0 and newton_model.bvh_shapes is None: newton.geometry.build_bvh_shape(newton_model, newton_model.state()) - if cfg.create_default_light: - self.newton_sensor.utils.create_default_light(enable_shadows=cfg.enable_shadows) + if self.cfg.create_default_light: + self.newton_sensor.utils.create_default_light(enable_shadows=self.cfg.enable_shadows) def supported_output_types(self) -> dict[RenderBufferKind, RenderBufferSpec]: """Publish the per-output layout this Newton Warp backend writes. diff --git a/source/isaaclab_ov/changelog.d/scene-initialize-renderers.rst b/source/isaaclab_ov/changelog.d/scene-initialize-renderers.rst new file mode 100644 index 000000000000..61103b21d517 --- /dev/null +++ b/source/isaaclab_ov/changelog.d/scene-initialize-renderers.rst @@ -0,0 +1,20 @@ +Changed +^^^^^^^ + +* Construct the underlying OVRTX ``Renderer`` in + :class:`~isaaclab_ov.renderers.OVRTXRenderer` ``__init__`` instead of + during :meth:`~isaaclab_ov.renderers.OVRTXRenderer.prepare_stage`. This + pairs with the new pre-physics ``__init__`` / + post-physics :meth:`~isaaclab.renderers.base_renderer.BaseRenderer.initialize` + lifecycle: when invoked eagerly via + :meth:`~isaaclab.scene.InteractiveScene.initialize_renderers`, the OVRTX + ``Renderer`` is created before + :meth:`~isaaclab.sim.SimulationContext.reset` (and therefore before + ovphysx initialises), which OVRTX 0.3 requires. +* Replaced an ``assert`` on the OVRTX ``Renderer`` construction with an + explicit :class:`RuntimeError` so the failure is reported even when + Python is run with ``-O``. +* Renamed the internal ``OVRTXRenderer.initialize(spec)`` helper to + ``_initialize_from_spec(spec)`` to avoid shadowing the new + no-arg :meth:`~isaaclab.renderers.base_renderer.BaseRenderer.initialize` + lifecycle hook. diff --git a/source/isaaclab_ov/isaaclab_ov/renderers/ovrtx_renderer.py b/source/isaaclab_ov/isaaclab_ov/renderers/ovrtx_renderer.py index 3c05a72dc30f..99ad0554048e 100644 --- a/source/isaaclab_ov/isaaclab_ov/renderers/ovrtx_renderer.py +++ b/source/isaaclab_ov/isaaclab_ov/renderers/ovrtx_renderer.py @@ -159,6 +159,21 @@ def __init__(self, cfg: OVRTXRendererCfg): self._camera_rel_path: str | None = None self._output_semantic_color_buffer: wp.array | None = None + logger.info("Creating OVRTX renderer...") + OVRTX_CONFIG = RendererConfig( + log_file_path=self.cfg.log_file_path, + log_level=self.cfg.log_level, + read_gpu_transforms=_IS_OVRTX_0_3_0_OR_NEWER, + keep_system_alive=True, + ) + self._renderer = Renderer(OVRTX_CONFIG) + if not self._renderer: + raise RuntimeError( + "Failed to create OVRTX Renderer; the underlying ovrtx.Renderer constructor returned a falsy" + " value. Check that ovrtx is installed correctly and its native dependencies are available." + ) + logger.info("OVRTX renderer created successfully") + def prepare_stage(self, stage: Any, num_envs: int) -> None: """Export the USD stage for OVRTX before create_render_data. @@ -178,7 +193,7 @@ def prepare_stage(self, stage: Any, num_envs: int) -> None: self._exported_usd_path = export_path logger.info("Exported to %s", export_path) - def initialize(self, spec: CameraRenderSpec): + def _initialize_from_spec(self, spec: CameraRenderSpec): """Initialize the OVRTX renderer with internal environment cloning. Args: @@ -198,17 +213,6 @@ def initialize(self, spec: CameraRenderSpec): usd_scene_path = self._exported_usd_path use_cloning = self.cfg.use_cloning - logger.info("Creating OVRTX renderer...") - OVRTX_CONFIG = RendererConfig( - log_file_path=self.cfg.log_file_path, - log_level=self.cfg.log_level, - read_gpu_transforms=_IS_OVRTX_0_3_0_OR_NEWER, - keep_system_alive=True, - ) - self._renderer = Renderer(OVRTX_CONFIG) - assert self._renderer, "Renderer should be valid after creation" - logger.info("OVRTX renderer created successfully") - if usd_scene_path is not None: logger.info("Injecting camera definitions...") @@ -367,7 +371,7 @@ def create_render_data(self, spec: CameraRenderSpec) -> OVRTXRenderData: matching the interface of Isaac RTX and Newton Warp which need no separate initialize(). """ if not self._initialized_scene: - self.initialize(spec) + self._initialize_from_spec(spec) return OVRTXRenderData(spec, DEVICE) # Map torch dtypes to their warp counterparts for zero-copy wrapping. From a337c0b036bae540bd47d4cd09b1c15fc0083f39 Mon Sep 17 00:00:00 2001 From: hougantc-nvda <127865892+hougantc-nvda@users.noreply.github.com> Date: Mon, 11 May 2026 21:38:40 -0400 Subject: [PATCH 38/51] Enables pipelined IsaacTeleop retargeting (#5493) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit This PR improves IsaacLab Teleop retargeting performance and installation reliability. - Added configurable IsaacTeleop retargeting execution via `IsaacTeleopCfg.retargeting_execution`. - Enabled deadline-paced pipelined retargeting by default, so IsaacTeleop retargeting work can overlap with Isaac Lab simulation stepping. - Preserved synchronous retargeting as an opt-in mode for exact current-frame behavior. - Added an extension-level `pip_upgrade_dependencies` setting in `extension.toml` so `./isaaclab.sh --install` can explicitly upgrade selected `install_requires` dependencies after editable install. - Used that mechanism for `isaaclab_teleop` to upgrade to the latest compatible `isaacteleop` without duplicating the version spec outside `setup.py`. ## Why The pipelined retargeting path reduces Python-side frame pressure by returning the latest completed retargeting output while the current frame is submitted in parallel. The install change fixes CI/local environments where an older compatible `isaacteleop` version is already installed. Since `pip install -e source/isaaclab_teleop` does not upgrade already-satisfied dependencies by default, which could keep using a stale IsaacTeleop package. The new targeted upgrade keeps the version range in `setup.py` as the source of truth while still allowing the install command to refresh `isaacteleop`. # Description Please include a summary of the change and which issue is fixed. Please also include relevant motivation and context. List any dependencies that are required for this change. Fixes # (issue) ## Type of change - New feature (non-breaking change which adds functionality) ## Screenshots Please attach before and after screenshots of the change if applicable. ## Checklist - [x] I have read and understood the [contribution guidelines](https://isaac-sim.github.io/IsaacLab/main/source/refs/contributing.html) - [x] I have run the [`pre-commit` checks](https://pre-commit.com/) with `./isaaclab.sh --format` - [x] I have made corresponding changes to the documentation - [x] My changes generate no new warnings - [x] I have added tests that prove my fix is effective or that my feature works - [x] I have updated the changelog and the corresponding version in the extension's `config/extension.toml` file - [x] I have added my name to the `CONTRIBUTORS.md` or my name already exists there --- docs/source/features/isaac_teleop.rst | 8 + .../overview/developer-guide/development.rst | 23 ++- .../hougantc-enable-pipeline-retarget.rst | 5 + .../isaaclab/isaaclab/cli/commands/install.py | 114 ++++++++++++ .../test/cli/test_install_commands.py | 162 ++++++++++++++++++ .../hougantc-pipelined-retargeting.rst | 23 +++ source/isaaclab_teleop/config/extension.toml | 4 + source/isaaclab_teleop/docs/README.md | 5 + .../isaaclab_teleop/isaac_teleop_cfg.py | 15 ++ .../isaaclab_teleop/session_lifecycle.py | 1 + .../test/test_cloudxr_lifecycle.py | 81 ++++++++- .../templates/extension/config/extension.toml | 5 + 12 files changed, 437 insertions(+), 9 deletions(-) create mode 100644 source/isaaclab/changelog.d/hougantc-enable-pipeline-retarget.rst create mode 100644 source/isaaclab_teleop/changelog.d/hougantc-pipelined-retargeting.rst diff --git a/docs/source/features/isaac_teleop.rst b/docs/source/features/isaac_teleop.rst index 733150259586..f5d30e39b161 100644 --- a/docs/source/features/isaac_teleop.rst +++ b/docs/source/features/isaac_teleop.rst @@ -685,6 +685,14 @@ Key ``IsaacTeleopCfg`` fields: * ``xr_cfg`` -- :class:`~isaaclab_teleop.XrCfg` for anchor configuration (see below). * ``plugins`` -- list of Isaac Teleop plugin configurations (e.g. Manus). * ``sim_device`` -- torch device string (default ``"cuda:0"``). +* ``retargeting_execution`` -- IsaacTeleop retargeting execution settings. + Defaults to ``RetargetingExecutionConfig(mode="pipelined")`` with + ``DeadlinePacingConfig(safety_margin_s=0.025)`` so retargeting can run on + the IsaacTeleop worker instead of blocking the simulation loop. + The 25 ms safety margin staggers IsaacTeleop's Python work behind Isaac + Lab's step Python, giving native work such as rendering time to overlap + instead of having both Python stacks contend for the GIL at the start of + the step. .. warning:: diff --git a/docs/source/overview/developer-guide/development.rst b/docs/source/overview/developer-guide/development.rst index 3d9ddbf014a3..2f789ac01acd 100644 --- a/docs/source/overview/developer-guide/development.rst +++ b/docs/source/overview/developer-guide/development.rst @@ -81,18 +81,21 @@ Custom Extension Dependency Management ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ Certain extensions may have dependencies which require the installation of additional packages before the extension -can be used. While Python dependencies are handled by the `setuptools `__ -package and specified in the ``setup.py`` file, non-Python dependencies such as `ROS `__ -packages or `apt `__ packages are not handled by setuptools. -Handling these kinds of dependencies requires an additional procedure. +can be used. Python dependencies are handled by the `setuptools `__ +package and specified in the ``setup.py`` file. Non-Python dependencies such as +`ROS `__ packages or `apt `__ +packages are not handled by setuptools. Handling these kinds of dependencies requires an additional procedure. -There are two types of dependencies that can be specified in the ``extension.toml`` file +There are three types of dependencies that can be specified in the ``extension.toml`` file under the ``isaac_lab_settings`` section: 1. **apt_deps**: A list of apt packages that need to be installed. These are installed using the `apt `__ package manager. 2. **ros_ws**: The path to the ROS workspace that contains the ROS packages. These are installed using the `rosdep `__ dependency manager. +3. **pip_upgrade_dependencies**: A list of ``install_requires`` dependency names that should be explicitly + upgraded after installing the extension with ``./isaaclab.sh --install``. List package names only. Version + ranges, extras, and platform markers are read from the installed extension metadata generated from ``setup.py``. As an example, the following ``extension.toml`` file specifies the dependencies for the extension: @@ -106,8 +109,11 @@ As an example, the following ``extension.toml`` file specifies the dependencies # note: if this path is relative, it is relative to the extension directory's root ros_ws = "/home/user/catkin_ws" -These dependencies are installed using the ``install_deps.py`` script provided in the ``tools`` directory. -To install all dependencies for all extensions, run the following command: + # Python dependency names to upgrade after installing this extension + pip_upgrade_dependencies = ["example_package"] + +The ``apt_deps`` and ``ros_ws`` dependencies are installed using the ``install_deps.py`` script provided in the +``tools`` directory. To install all apt and ROS dependencies for all extensions, run the following command: .. code-block:: bash @@ -121,6 +127,9 @@ To install all dependencies for all extensions, run the following command: and ``Dockerfile.ros2``. This ensures that all the 'apt' and 'rosdep' dependencies are installed before building the extensions respectively. +The ``pip_upgrade_dependencies`` entries are handled by ``./isaaclab.sh --install`` after the extension's editable +pip install completes. + Standalone applications ~~~~~~~~~~~~~~~~~~~~~~~ diff --git a/source/isaaclab/changelog.d/hougantc-enable-pipeline-retarget.rst b/source/isaaclab/changelog.d/hougantc-enable-pipeline-retarget.rst new file mode 100644 index 000000000000..451e8c1e572d --- /dev/null +++ b/source/isaaclab/changelog.d/hougantc-enable-pipeline-retarget.rst @@ -0,0 +1,5 @@ +Fixed +^^^^^ + +* Fixed extension installation to honor ``pip_upgrade_dependencies`` declared + in ``config/extension.toml``. diff --git a/source/isaaclab/isaaclab/cli/commands/install.py b/source/isaaclab/isaaclab/cli/commands/install.py index 46125ae46f1e..f83c4dfdbf87 100644 --- a/source/isaaclab/isaaclab/cli/commands/install.py +++ b/source/isaaclab/isaaclab/cli/commands/install.py @@ -4,10 +4,13 @@ # SPDX-License-Identifier: BSD-3-Clause import os +import re import shutil import sys from pathlib import Path +import tomllib + from ..utils import ( ISAACLAB_ROOT, extract_isaacsim_path, @@ -286,6 +289,111 @@ def _ensure_cuda_torch() -> None: NVIDIA_INDEX_URL = "https://pypi.nvidia.com" +def _normalize_package_name(name: str) -> str: + """Normalize a Python package name for metadata comparisons.""" + return re.sub(r"[-_.]+", "-", name).lower() + + +def _requirement_name(requirement: str) -> str: + """Extract the distribution name from a requirement string.""" + requirement = requirement.split(";", 1)[0].strip() + return re.split(r"\s|<|>|=|!|~|\[|@", requirement, maxsplit=1)[0] + + +def _get_installed_distribution_requirements(python_exe: str, distribution_name: str) -> list[str]: + """Return installed ``Requires-Dist`` requirements for a distribution.""" + probe = """import importlib.metadata +import sys + +try: + dist = importlib.metadata.distribution(sys.argv[1]) +except importlib.metadata.PackageNotFoundError: + sys.exit(1) + +for requirement in dist.requires or []: + print(requirement) +""" + result = run_command( + [python_exe, "-c", probe, distribution_name], + capture_output=True, + text=True, + check=False, + ) + if result.returncode != 0: + print_warning(f"Could not read installed metadata for {distribution_name}; skipping dependency upgrades.") + return [] + return [line.strip() for line in result.stdout.splitlines() if line.strip()] + + +def _get_extension_pip_upgrade_dependencies(extension_dir: Path) -> list[str]: + """Read dependency names opted into targeted pip upgrades from ``extension.toml``.""" + extension_toml = extension_dir / "config" / "extension.toml" + if not extension_toml.is_file(): + return [] + + try: + with extension_toml.open("rb") as fd: + extension_data = tomllib.load(fd) + except tomllib.TOMLDecodeError as exc: + print_warning(f"Could not parse {extension_toml}: {exc}; skipping targeted dependency upgrades.") + return [] + + isaac_lab_settings = extension_data.get("isaac_lab_settings", {}) + if not isinstance(isaac_lab_settings, dict): + print_warning( + f"Ignoring invalid isaac_lab_settings in {extension_toml}; expected a table with pip_upgrade_dependencies." + ) + return [] + + upgrade_dependencies = isaac_lab_settings.get("pip_upgrade_dependencies", []) + if not isinstance(upgrade_dependencies, list) or not all(isinstance(item, str) for item in upgrade_dependencies): + print_warning(f"Ignoring invalid pip_upgrade_dependencies in {extension_toml}; expected a list of strings.") + return [] + + return upgrade_dependencies + + +def _get_pip_upgrade_command(pip_cmd: list[str], dependency_name: str, requirement: str) -> list[str]: + """Return a pip command that upgrades one dependency requirement.""" + if pip_cmd[0] == "uv": + return pip_cmd + ["install", "--upgrade-package", dependency_name, requirement] + return pip_cmd + ["install", "--upgrade", requirement] + + +def _upgrade_extension_pip_dependencies( + python_exe: str, + pip_cmd: list[str], + distribution_name: str, + dependency_names: list[str], +) -> None: + """Upgrade selected dependencies using installed distribution metadata requirements.""" + if not dependency_names: + return + + requirements = _get_installed_distribution_requirements(python_exe, distribution_name) + seen_dependency_names = set() + + for dependency_name in dependency_names: + normalized_dependency_name = _normalize_package_name(dependency_name) + if normalized_dependency_name in seen_dependency_names: + continue + seen_dependency_names.add(normalized_dependency_name) + + matching_requirements = [ + req for req in requirements if _normalize_package_name(_requirement_name(req)) == normalized_dependency_name + ] + if not matching_requirements: + print_warning( + f"Could not find dependency '{dependency_name}' in installed metadata for {distribution_name}; " + "skipping targeted upgrade." + ) + continue + + for requirement in matching_requirements: + print_info(f"Upgrading {dependency_name} for {distribution_name}: {requirement}") + run_command(_get_pip_upgrade_command(pip_cmd, dependency_name, requirement)) + + def _install_isaacsim() -> None: """Install Isaac Sim pip package if not already present.""" python_exe = extract_python_exe() @@ -414,6 +522,12 @@ def _install_isaaclab_submodules( editable = (submodule_extras or {}).get(item.name, "") install_target = f"{item}{editable}" run_command(pip_cmd + ["install", "--editable", install_target]) + _upgrade_extension_pip_dependencies( + python_exe, + pip_cmd, + item.name, + _get_extension_pip_upgrade_dependencies(item), + ) def _install_extra_frameworks(framework_name: str = "all") -> None: diff --git a/source/isaaclab/test/cli/test_install_commands.py b/source/isaaclab/test/cli/test_install_commands.py index a7c89ccd9d53..f773d9f026cf 100644 --- a/source/isaaclab/test/cli/test_install_commands.py +++ b/source/isaaclab/test/cli/test_install_commands.py @@ -17,6 +17,7 @@ import pytest +import isaaclab.cli.commands.install as install_cmd from isaaclab.cli.commands.install import ( _PREBUNDLE_REPOINT_PACKAGES, _ensure_cuda_torch, @@ -68,6 +69,167 @@ def _make_site_packages( return site_pkgs +# --------------------------------------------------------------------------- +# _install_isaaclab_submodules targeted dependency upgrades +# --------------------------------------------------------------------------- + + +class TestInstallSubmodulesTargetedDependencyUpgrades: + """Tests for extension.toml-driven dependency upgrades.""" + + def _make_extension(self, tmp_path, extension_toml: str) -> Path: + """Create a minimal installable extension fixture.""" + source_dir = tmp_path / "source" + extension_dir = source_dir / "isaaclab_teleop" + config_dir = extension_dir / "config" + config_dir.mkdir(parents=True) + (extension_dir / "setup.py").write_text("# test fixture\n", encoding="utf-8") + (config_dir / "extension.toml").write_text(extension_toml, encoding="utf-8") + return extension_dir + + def test_installs_editable_then_upgrades_declared_dependency_from_metadata(self, tmp_path): + """An opted-in dependency is upgraded using the requirement recorded in installed metadata.""" + extension_dir = self._make_extension( + tmp_path, + '[isaac_lab_settings]\npip_upgrade_dependencies = ["isaacteleop"]\n', + ) + + python_exe = str(tmp_path / "python") + pip_cmd = [python_exe, "-m", "pip"] + isaacteleop_req = 'isaacteleop[cloudxr,retargeters,ui] ~=1.2.0; platform_system == "Linux"' + + with ( + mock.patch("isaaclab.cli.commands.install.ISAACLAB_ROOT", tmp_path), + mock.patch("isaaclab.cli.commands.install.extract_python_exe", return_value=python_exe), + mock.patch("isaaclab.cli.commands.install.get_pip_command", return_value=pip_cmd), + mock.patch( + "isaaclab.cli.commands.install._get_installed_distribution_requirements", + return_value=[isaacteleop_req], + ), + mock.patch("isaaclab.cli.commands.install.run_command") as mock_run, + ): + install_cmd._install_isaaclab_submodules(["isaaclab_teleop"]) + + assert [call.args[0] for call in mock_run.call_args_list] == [ + pip_cmd + ["install", "--editable", str(extension_dir)], + pip_cmd + ["install", "--upgrade", isaacteleop_req], + ] + + def test_uv_install_uses_upgrade_package_for_declared_dependency(self, tmp_path): + """uv upgrades only the declared package rather than using a global upgrade.""" + extension_dir = self._make_extension( + tmp_path, + '[isaac_lab_settings]\npip_upgrade_dependencies = ["isaacteleop"]\n', + ) + + python_exe = str(tmp_path / "python") + pip_cmd = ["uv", "pip"] + isaacteleop_req = 'isaacteleop[cloudxr,retargeters,ui] ~=1.2.0; platform_system == "Linux"' + + with ( + mock.patch("isaaclab.cli.commands.install.ISAACLAB_ROOT", tmp_path), + mock.patch("isaaclab.cli.commands.install.extract_python_exe", return_value=python_exe), + mock.patch("isaaclab.cli.commands.install.get_pip_command", return_value=pip_cmd), + mock.patch( + "isaaclab.cli.commands.install._get_installed_distribution_requirements", + return_value=[isaacteleop_req], + ), + mock.patch("isaaclab.cli.commands.install.run_command") as mock_run, + ): + install_cmd._install_isaaclab_submodules(["isaaclab_teleop"]) + + assert [call.args[0] for call in mock_run.call_args_list] == [ + pip_cmd + ["install", "--editable", str(extension_dir)], + pip_cmd + ["install", "--upgrade-package", "isaacteleop", isaacteleop_req], + ] + + def test_upgrades_all_matching_metadata_requirements(self, tmp_path): + """Duplicate metadata entries are preserved instead of collapsing to one requirement.""" + python_exe = str(tmp_path / "python") + pip_cmd = [python_exe, "-m", "pip"] + linux_req = 'example-package>=1.0; platform_system == "Linux"' + windows_req = 'example_package>=2.0; platform_system == "Windows"' + + with ( + mock.patch( + "isaaclab.cli.commands.install._get_installed_distribution_requirements", + return_value=[linux_req, windows_req], + ), + mock.patch("isaaclab.cli.commands.install.run_command") as mock_run, + ): + install_cmd._upgrade_extension_pip_dependencies( + python_exe, + pip_cmd, + "isaaclab_teleop", + ["example-package"], + ) + + assert [call.args[0] for call in mock_run.call_args_list] == [ + pip_cmd + ["install", "--upgrade", linux_req], + pip_cmd + ["install", "--upgrade", windows_req], + ] + + def test_skips_duplicate_declared_dependency_names(self, tmp_path): + """Duplicate TOML dependency names do not trigger duplicate pip commands.""" + python_exe = str(tmp_path / "python") + pip_cmd = [python_exe, "-m", "pip"] + req = "isaacteleop~=1.2.0" + + with ( + mock.patch( + "isaaclab.cli.commands.install._get_installed_distribution_requirements", + return_value=[req], + ), + mock.patch("isaaclab.cli.commands.install.run_command") as mock_run, + ): + install_cmd._upgrade_extension_pip_dependencies( + python_exe, + pip_cmd, + "isaaclab_teleop", + ["isaacteleop", "IsaacTeleop"], + ) + + mock_run.assert_called_once_with(pip_cmd + ["install", "--upgrade", req]) + + def test_skips_when_toml_has_no_upgrade_dependencies(self, tmp_path): + """Extensions without pip upgrade opt-ins do not trigger metadata probes.""" + extension_dir = self._make_extension(tmp_path, "[isaac_lab_settings]\n") + + assert install_cmd._get_extension_pip_upgrade_dependencies(extension_dir) == [] + + def test_warns_and_skips_invalid_upgrade_dependency_names(self, tmp_path): + """Invalid TOML value types warn and disable targeted upgrades.""" + extension_dir = self._make_extension( + tmp_path, + '[isaac_lab_settings]\npip_upgrade_dependencies = "isaacteleop"\n', + ) + + with mock.patch("isaaclab.cli.commands.install.print_warning") as mock_warning: + assert install_cmd._get_extension_pip_upgrade_dependencies(extension_dir) == [] + + mock_warning.assert_called_once() + + def test_warns_when_declared_dependency_missing_from_metadata(self, tmp_path): + """A declared dependency name must exist in installed package metadata.""" + with ( + mock.patch( + "isaaclab.cli.commands.install._get_installed_distribution_requirements", + return_value=["dex-retargeting==0.5.0"], + ), + mock.patch("isaaclab.cli.commands.install.print_warning") as mock_warning, + mock.patch("isaaclab.cli.commands.install.run_command") as mock_run, + ): + install_cmd._upgrade_extension_pip_dependencies( + str(tmp_path / "python"), + [str(tmp_path / "python"), "-m", "pip"], + "isaaclab_teleop", + ["isaacteleop"], + ) + + mock_warning.assert_called_once() + mock_run.assert_not_called() + + # --------------------------------------------------------------------------- # _torch_first_on_sys_path_is_prebundle # --------------------------------------------------------------------------- diff --git a/source/isaaclab_teleop/changelog.d/hougantc-pipelined-retargeting.rst b/source/isaaclab_teleop/changelog.d/hougantc-pipelined-retargeting.rst new file mode 100644 index 000000000000..2a58c6560fab --- /dev/null +++ b/source/isaaclab_teleop/changelog.d/hougantc-pipelined-retargeting.rst @@ -0,0 +1,23 @@ +Added +^^^^^ + +* Added :attr:`~isaaclab_teleop.IsaacTeleopCfg.retargeting_execution` for + configuring IsaacTeleop retargeting execution mode from Isaac Lab. + +Changed +^^^^^^^ + +* Changed :class:`~isaaclab_teleop.IsaacTeleopCfg` to enable IsaacTeleop + deadline-paced pipelined retargeting by default. This returns the latest + completed retargeting output while the current frame is submitted, using + ``DeadlinePacingConfig(safety_margin_s=0.025)`` to sample close to the next + simulation consumption point and stagger IsaacTeleop's Python work behind + Isaac Lab's step Python. Set + ``retargeting_execution=RetargetingExecutionConfig(mode="sync")`` to restore + exact current-frame retargeting. + +Fixed +^^^^^ + +* Fixed installation to upgrade to the latest compatible ``isaacteleop`` + package when installing ``isaaclab_teleop``. diff --git a/source/isaaclab_teleop/config/extension.toml b/source/isaaclab_teleop/config/extension.toml index 48415f4bf5eb..9fd1742d243f 100644 --- a/source/isaaclab_teleop/config/extension.toml +++ b/source/isaaclab_teleop/config/extension.toml @@ -13,6 +13,10 @@ keywords = ["kit", "robotics", "teleoperation", "xr", "isaaclab"] [dependencies] "isaaclab" = {} +[isaac_lab_settings] +# Names only. Version ranges, extras, and platform markers come from setup.py metadata. +pip_upgrade_dependencies = ["isaacteleop"] + [core] reloadable = false diff --git a/source/isaaclab_teleop/docs/README.md b/source/isaaclab_teleop/docs/README.md index bd6a3c7f6c7b..1f412e0f0238 100644 --- a/source/isaaclab_teleop/docs/README.md +++ b/source/isaaclab_teleop/docs/README.md @@ -120,9 +120,14 @@ rendering without blocking. | `retargeters_to_tune` | `Callable[[], list[BaseRetargeter]] \| None` | `None` | Retargeters to expose in the tuning UI | | `plugins` | `list[PluginConfig]` | `[]` | IsaacTeleop plugin configurations | | `sim_device` | `str` | `"cuda:0"` | Torch device for output action tensors | +| `retargeting_execution` | `RetargetingExecutionConfig` | `mode="pipelined", pacing=DeadlinePacingConfig(safety_margin_s=0.025)` | IsaacTeleop retargeting execution settings | | `teleoperation_active_default` | `bool` | `False` | Whether teleoperation is active on session start | | `app_name` | `str` | `"IsaacLabTeleop"` | Application name for the IsaacTeleop session | +The 25 ms `DeadlinePacingConfig` safety margin staggers IsaacTeleop's Python work behind Isaac Lab's +step Python, giving native work such as rendering time to overlap instead of having both Python stacks +contend for the GIL at the start of the step. + ### `XrCfg` | Field | Type | Default | Description | diff --git a/source/isaaclab_teleop/isaaclab_teleop/isaac_teleop_cfg.py b/source/isaaclab_teleop/isaaclab_teleop/isaac_teleop_cfg.py index f94a63d57589..a15d09bebb01 100644 --- a/source/isaaclab_teleop/isaaclab_teleop/isaac_teleop_cfg.py +++ b/source/isaaclab_teleop/isaaclab_teleop/isaac_teleop_cfg.py @@ -12,6 +12,8 @@ from pathlib import Path from typing import TYPE_CHECKING +from isaacteleop.teleop_session_manager import DeadlinePacingConfig, RetargetingExecutionConfig + from isaaclab.utils import configclass from .control_events import TELEOP_CONTROL_CHANNEL_UUID @@ -95,6 +97,19 @@ def build_pipeline(): sim_device: str = "cuda:0" """Torch device string for placing output action tensors.""" + retargeting_execution: RetargetingExecutionConfig = field( + default_factory=lambda: RetargetingExecutionConfig( + mode="pipelined", + pacing=DeadlinePacingConfig(safety_margin_s=0.025), + ) + ) + """IsaacTeleop retargeting execution settings. + + Isaac Lab opts into IsaacTeleop's pipelined execution by default. Set this + to ``RetargetingExecutionConfig(mode="sync")`` for exact current-frame + retargeting while debugging or comparing behavior. + """ + teleoperation_active_default: bool = False """Whether teleoperation should be active by default when the session starts. diff --git a/source/isaaclab_teleop/isaaclab_teleop/session_lifecycle.py b/source/isaaclab_teleop/isaaclab_teleop/session_lifecycle.py index fa5f36f658e0..9c3a7813cd81 100644 --- a/source/isaaclab_teleop/isaaclab_teleop/session_lifecycle.py +++ b/source/isaaclab_teleop/isaaclab_teleop/session_lifecycle.py @@ -502,6 +502,7 @@ def _try_start_session(self) -> bool: teleop_control_pipeline=self._teleop_control_pipeline, plugins=self._cfg.plugins, oxr_handles=oxr_handles, + retargeting_execution=self._cfg.retargeting_execution, ) # Create and enter the TeleopSession diff --git a/source/isaaclab_teleop/test/test_cloudxr_lifecycle.py b/source/isaaclab_teleop/test/test_cloudxr_lifecycle.py index 43131f70cfc3..457a2a26d967 100644 --- a/source/isaaclab_teleop/test/test_cloudxr_lifecycle.py +++ b/source/isaaclab_teleop/test/test_cloudxr_lifecycle.py @@ -20,6 +20,7 @@ import os import sys +from dataclasses import dataclass from pathlib import Path from types import ModuleType from unittest.mock import MagicMock, patch @@ -70,8 +71,38 @@ def _install_stubs(): """Insert MagicMock modules for all heavy dependencies.""" for name in _MODULES_TO_STUB: if name not in sys.modules: - _stubs_installed[name] = MagicMock() - sys.modules[name] = _stubs_installed[name] + sys.modules[name] = _stubs_installed.setdefault(name, MagicMock()) + if "." in name: + parent_name, child_name = name.rsplit(".", 1) + setattr(sys.modules[parent_name], child_name, sys.modules[name]) + + @dataclass + class DeadlinePacingConfig: + safety_margin_s: float = 0.025 + + @dataclass + class RetargetingExecutionConfig: + mode: str = "sync" + pacing: DeadlinePacingConfig | None = None + + tsm = sys.modules["isaacteleop.teleop_session_manager"] + tsm.DeadlinePacingConfig = DeadlinePacingConfig # type: ignore[attr-defined] + tsm.RetargetingExecutionConfig = RetargetingExecutionConfig # type: ignore[attr-defined] + + +def _restore_stubs(): + """Remove stubs installed for this test module from ``sys.modules``.""" + for name in reversed(_MODULES_TO_STUB): + stub = _stubs_installed.get(name) + if stub is None: + continue + if "." in name: + parent_name, child_name = name.rsplit(".", 1) + parent = sys.modules.get(parent_name) + if parent is not None and getattr(parent, child_name, None) is stub: + delattr(parent, child_name) + if sys.modules.get(name) is stub: + del sys.modules[name] _install_stubs() @@ -83,11 +114,21 @@ def _install_stubs(): ) from isaaclab_teleop.session_lifecycle import TeleopSessionLifecycle # noqa: E402 +_restore_stubs() + # --------------------------------------------------------------------------- # Helpers # --------------------------------------------------------------------------- +@pytest.fixture(autouse=True) +def _stub_heavy_dependencies(): + """Keep CloudXR tests isolated from modules collected later in the suite.""" + _install_stubs() + yield + _restore_stubs() + + def _make_cfg() -> IsaacTeleopCfg: """Build a minimal IsaacTeleopCfg with a dummy pipeline_builder.""" return IsaacTeleopCfg( @@ -139,6 +180,42 @@ def test_profiles_are_in_same_directory(self): assert Path(CLOUDXR_AVP_ENV).parent == Path(CLOUDXR_JS_ENV).parent +# ============================================================================ +# IsaacTeleop execution config +# ============================================================================ + + +class TestRetargetingExecutionConfig: + """Tests for Isaac Lab's IsaacTeleop retargeting execution defaults.""" + + def test_session_config_receives_deadline_paced_pipelined_retargeting(self): + """The default retargeting execution config is passed into TeleopSession.""" + cfg = _make_cfg() + + assert cfg.retargeting_execution.mode == "pipelined" + assert cfg.retargeting_execution.pacing.safety_margin_s == 0.025 + + sentinel_execution = cfg.retargeting_execution + + lifecycle = TeleopSessionLifecycle(cfg) + lifecycle._pipeline = MagicMock() + lifecycle._teleop_control_pipeline = None + + session_config_cls = MagicMock(return_value=MagicMock()) + session_cls = MagicMock() + fake_tsm_module = sys.modules["isaacteleop.teleop_session_manager"] + + with ( + patch.object(fake_tsm_module, "TeleopSessionConfig", session_config_cls), + patch.object(fake_tsm_module, "TeleopSession", session_cls), + patch.object(lifecycle, "_ensure_xr_ar_profile_enabled"), + patch.object(lifecycle, "_acquire_kit_oxr_handles", return_value=object()), + ): + assert lifecycle.try_start_session() is True + + assert session_config_cls.call_args.kwargs["retargeting_execution"] is sentinel_execution + + # ============================================================================ # _ensure_cloudxr_runtime # ============================================================================ diff --git a/tools/template/templates/extension/config/extension.toml b/tools/template/templates/extension/config/extension.toml index dbe4b064fbc4..c23cf2de1287 100644 --- a/tools/template/templates/extension/config/extension.toml +++ b/tools/template/templates/extension/config/extension.toml @@ -33,3 +33,8 @@ name = "{{ name }}" # with rosdeps to be installed. If none, # leave it commented out. # ros_ws = "path/from/extension_root/to/ros_ws" +# TODO: Uncomment and list install_requires dependency names that should be upgraded +# after this extension is installed with ./isaaclab.sh --install. +# List package names only; version ranges, extras, and platform markers +# come from this extension's setup.py metadata. +# pip_upgrade_dependencies = ["example_package"] From dd5a21aeea35a69450cf26714c0e47ff4ca7293c Mon Sep 17 00:00:00 2001 From: mingxueg Date: Tue, 12 May 2026 10:12:49 +0800 Subject: [PATCH 39/51] Add assemble_trocar task for G129-Dex3 (#5082) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit # Description Adds the **Assemble Trocar** manipulation task for the Unitree G1 (29-DoF + Dex3), with RLinf support. Key additions: - **Task MDP**: observations (body + Dex3 joint states), reward functions (4-stage sparse), termination conditions (timeout, success, object drop), and reset events (scene reset, task stage reset, random tray rotation). - **Camera presets**: front camera and left/right wrist cameras (TiledCamera, 224×224) configured for GR00T visual input. - **Robot presets**: G1 29-DoF + Dex3 articulation configuration. - **GR00T data config**: `IsaacLabDataConfig` defining video/state/action modality keys, transforms (SinCos state encoding, min-max action normalization, color jitter), and model-specific settings. - **RLinf extension update**: minor update to `isaaclab_contrib/rl/rlinf/extension.py` to support the new task registration. ## Type of change - New feature (non-breaking change which adds functionality) ## Checklist - [x] I have read and understood the [contribution guidelines](https://isaac-sim.github.io/IsaacLab/main/source/refs/contributing.html) - [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 - [ ] I have added tests that prove my fix is effective or that my feature works - [ ] 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 --------- Co-authored-by: Kelly Guo --- .../tasks/manipulation/g1_assemble_trocar.jpg | Bin 0 -> 476908 bytes .../experimental-features/bleeding-edge.rst | 141 ++++ docs/source/overview/environments.rst | 9 + .../reinforcement_learning/rlinf/README.md | 10 +- .../Adds-Assemble-Trocar-task-Based-RLinf.rst | 5 + .../isaaclab_assets/robots/unitree.py | 202 +++++- .../Adds-Assemble-Trocar-task-Based-RLinf.rst | 5 + .../isaaclab_contrib/rl/rlinf/extension.py | 15 +- .../Adds-Assemble-Trocar-task-Based-RLinf.rst | 7 + .../manipulation/assemble_trocar/__init__.py | 6 + .../assemble_trocar/config/__init__.py | 9 + .../assemble_trocar/config/camera_config.py | 131 ++++ .../assemble_trocar/config/gr00t_config.py | 144 ++++ .../isaaclab_ppo_gr00t_assemble_trocar.yaml | 298 ++++++++ .../assemble_trocar/config/robot_config.py | 147 ++++ .../assemble_trocar/g129_dex3_env_cfg.py | 444 ++++++++++++ .../assemble_trocar/mdp/__init__.py | 10 + .../assemble_trocar/mdp/events.py | 253 +++++++ .../assemble_trocar/mdp/observations.py | 119 ++++ .../assemble_trocar/mdp/rewards.py | 634 ++++++++++++++++++ .../assemble_trocar/mdp/terminations.py | 80 +++ 21 files changed, 2662 insertions(+), 7 deletions(-) create mode 100644 docs/source/_static/tasks/manipulation/g1_assemble_trocar.jpg create mode 100644 source/isaaclab_assets/changelog.d/Adds-Assemble-Trocar-task-Based-RLinf.rst create mode 100644 source/isaaclab_contrib/changelog.d/Adds-Assemble-Trocar-task-Based-RLinf.rst create mode 100644 source/isaaclab_tasks/changelog.d/Adds-Assemble-Trocar-task-Based-RLinf.rst create mode 100644 source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/assemble_trocar/__init__.py create mode 100644 source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/assemble_trocar/config/__init__.py create mode 100644 source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/assemble_trocar/config/camera_config.py create mode 100644 source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/assemble_trocar/config/gr00t_config.py create mode 100644 source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/assemble_trocar/config/isaaclab_ppo_gr00t_assemble_trocar.yaml create mode 100644 source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/assemble_trocar/config/robot_config.py create mode 100644 source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/assemble_trocar/g129_dex3_env_cfg.py create mode 100644 source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/assemble_trocar/mdp/__init__.py create mode 100644 source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/assemble_trocar/mdp/events.py create mode 100644 source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/assemble_trocar/mdp/observations.py create mode 100644 source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/assemble_trocar/mdp/rewards.py create mode 100644 source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/assemble_trocar/mdp/terminations.py diff --git a/docs/source/_static/tasks/manipulation/g1_assemble_trocar.jpg b/docs/source/_static/tasks/manipulation/g1_assemble_trocar.jpg new file mode 100644 index 0000000000000000000000000000000000000000..ad62167a29332177e8b88a2c18e9e299ca13e7a4 GIT binary patch literal 476908 zcmbT8cRbZ?{Qr;atO!v!h3vg$oFpqnlD*0vA!NrXLPms)Y}qTxCaJ8fY}tEc?|Fvb zbq?M4{r&#+`~A8f_x<=h>h$?s*YzH+=lgX&?vtUDDaeI8iYkf_92^J)2mAv$8HLD0 zhzJM>3Gj&s2?>dbiO!Q!laZ2;kkV6Kq@ZTJ3}s@x%)oG!m5==@GY<;`1BW;#kAR?v zhzOKjQbs~Znon3n2y+u0Vq#)a5>h%cGCHAa4A+GIpMRZvgHRITrxCuu#bJh=qr}0b z#5rk%K*2ikaj?H2XTNaH;o{*F5E2oeCjlQQzW_OhgNu6(4;LRF4-b6W2mCn%j}o8i znxGuPMUBUV%uduoFC){5SZ>_>c__7WZafZeeL)?>6=yx%(aq;gHK4fHO zW#{DP<$o?ME3c@ms;>Fb(Ad=6^0T$Ax37O-@b}R0$n?zY-2B4gpQYuk?Va7d{e#1! zW6ZvAAh@U70{=bT*#FuWCD_+FJUm=HLd?E!&bfnsaVhceuL%-R$!QQicDl$c^pc4B zR%Cj~cVZUd2b(me&OPU8Sw*I=Z(+8E-P!-$#{B-jcJ|N4{@vFIgcKJC1P_-I0)u?B zDH|Fk#@q2eIy6BM!rDG~C+bKD+|9qi)s_bTBl-{rHGTYBb((?@N?pDpmcf`r`?`qr z4ZT_HFNvRYKPuFGU}U30k~90BClC#B6dH=Wr*fh4{SO5j=XEcxHgfpZ$ohv(!obMy zi7hu=a?uyeG*2KIWX@idF*a~lGaDcK>xB*)=9StcSNDDq!`?H!3b!%jQ8eo-3gmm0 zcmi2`=Nt$N9({S-?aFPT&UeM;vD%EJqQSD;;^vaxgnmkC+Hv3s zA)UF+HtEpt7>F##+IeEu$^?lnC7U3adUS%EYfj^2b$L?i(VyOrO5OIeM+2QC4F?lk z{hi6l9rq-{es&5AoX^0OY{|pL9jviS4RCJjV+$?TwG}pq;=9If);t~usbmd=icO>% zs#?2A1SNFFmsD1|4vIo!uBz#L0C-_F_>#nKEX`PHdmS9>t#7oDE zr1=4CN=)rT-U(?}@Z1hGi9VE8yUD!5Y_5QHiI!9tFHYFMjripo_=S4GW2bf7x~3Ts z#fcH!wYAz0f$b-dFHT+C`}xL(COg}y2kr0x9Ov<-y}G`Qge!qEgd5F}U0g@prTa&* zCOc~|YyfYuM4){yZaZ$~T(4=pdi%Xz@VE1YDk#pO+bQ;ONQC+c1m1E2xu|Ux-guiW zg?RRskpD0I)IVao2Pcrd`}S)*N*h)ob}6lX8nR!UeQMxbIV_&N!mZAQYyEF0rSe)b`}GQVbM{R62n?uROeu z_tie~1QO>Rfk49!LsEK4yjvUZk94RBbyz_-)>THoW$P_ryh_(scdR{t^Bfdzh&84j z?pJ}#nLUBL&V3H97HfR(p{YHcP9R;+kcmjnAz~zErGGz@Ni}@&1j2M0J(>&Q!Y2^k zK5%da6|rv>D8E!ilHPH;d|~p7qgpZ{99?&nhh=!^W*otUW0^AXo4XBM^^=G%Q1!0f z(h)l<6|vuV$48haXC?8-=U4O-^fIpWXNj&i#Vmrs2-7at-V{E!7x$xu=9WiCwQcQdi5bgF%~1kh#GiH1Q{pjaX1@ zDmeU!|1N|2zssQ1I1+?+^_yUqao1#L=MpB4H>rZ3C?RXR&X%fEPFNbiTNHK?85wl- zE&+)PYND!1v!o<^9Ze_OooE#J^h%Czf8`p@0CI;Ue!nzI!XdfV>pt%DQU0Upv;9&k zVd_Sj54Ld#3Y!bc#eZ}Z0Zu-nEfno*213Pg&P1pM?eh_~aeM;VqA7T^pE`88l=n+I z>=_;XOZJ7e?JeD}hPq%|?@l0J4UpWXKR8+f%S|TJ@u#nR8gur^wWds5(1mvuwV+NQ zP^1F;`^Wzl>LpBOf+7H!sWA^S6vm0Y)~urP9EAQG6m1@d)kk0b&pHX86P!Hs z;flj1^^y4DgV!HGYkGxQ>nGav!M4G5-OD4+X3m+xEfOF|4`uCNfP}X@P58>n1dm(8fYx#$Q1%PV@|UaG`3 zSPAj>BW=J`;%z7Y)G~HVCg}?`Fl9V(pq(b`mp^C^Jo;VwY-Q!BmtMW&6Kor_FKnck zEF%81b!--btt&-Cktn5z0|QXSWLJ3AehnM5mnW!t!Uh%laJvqI+P_m*?pKH{M>pW@ z=(itSzlhV7e#Jv}AbGCo_nII$F&gI|^St!4vDR7TalzNFeVUjJC)&%zce)Oq_O~ah zE)2oD3Qr)|Zf=TD4aYM`w2O)Tb?cU-_D|V2Ed;rkGVQ>YsnknL?si>P^0#V4Ym2y% ze|+zh5u|!XTREq@gT$t7->sk4!fYxc1{MgA)ISbEwHVXzqPM~ zEyqf1SD>*HJE$@U&Fy{SBsSOpuWMP+vi!WwkXg$7Y2TEhN@DIlEkpEh^YkD|z$0g( zDo6ygwn6pz_HyqYH(`ALVJNd_$yMaP^+HQx6T&6iZJM_`7uR&BhmfW#vyS_ z=kCf)n&+UIV$%e){TzdpTQAwl6BHQES<;)Nj~+kEFLKCjGJf{phF=kydXkU-=ujP# zH!t{(+=MvoJglN|uS-wS`Cjova@8lAO`JXawc?98!>h? ziR!dt6cl~rxS6-MetGPPLGB2%uk|=x9#Zfo*+o52re%`{hd}U|jr5zH->M1sd(ILr zi#^O{yfODYj>M4@_AHPCP9+4>5A=~-`(zPwu5$b-{W}y9od|vqDo5?z^jdbVpu)cK+$rZq#592@>{#IU_58Kc zuhk`G{r2W%Z`ug4jK>}Y7m^{S6Zt4bDt2uD_1?F*jx`2NZfN7$Hbp!JLA;6IXI#QpkA2(zqOL??p8dC40I`lJm= z(?cKy)*+2;&K7T2Hdy9xj(uYU45Z8u?=xb+iToLY%0(=y%|IEn!xHBzV_8?bBo_aO zxhV6C96DbsjZZp(6xt}laVl|-`nfMo7_!=MCfLw%eJBtXl!g$%NOe?Z_#xwmcJihD zjt#Qx^6HvOO zUd9eOk&am(ONeN~@%*FUK&@L*>oPZ6aL2ax(r!P^s_Q7A7SrKd{1gw8!@45+am1KR z$80{JJN4g=?7PSP!V@gF?bkBHCx-SENcB*|B^b72lW6@%$2dr07wZF;4mxQXnEVf> zATp5AZ@C!d{M(MxhoQ&=bbY}@>W;jbI&Okb>$g%o!FJ`~%~D@ZG04sr?24s*(+2){ z9~R`|yW4~^5GN3K|D~g2EnLw^cCnr46NnMe-HR%Mm#E63jIOy!vfIG}l(1S%3`jup z6V*|L$ z&u`9?;xPVf7+0Q|1x@Gf1)nU4+jj{ELf`(;#qb5RXF!LyQLFKl9EXW_FCscVgR=%5 z5nH?*J3RGgDHviEO#$@!6tU(22Ea5rM@ z{=i!bK_{x|C}{dT??(p#9fs#3R&>$!0KU#ZGNHRCfgtK0z_||b(D`Wp?RqT-rQ)5! zl~6%@sRo{(AHz;*4$^=vg41y;!9)xs#QGU)^Rq#Zjw3KtoY5MD_RYX9go85APUg*= zs`=(!I`bc$0xPJowLkFG!Q9&6j2JuBfJaZ2QY20wEnJk;@@Ql1Hj6kPhdwA5CwUsU zd>ysf@O)*s#&r+*hhDV$?O8;x6`uJ+EKhkyDijW|;r7~uLpe4ZPG{BoM6 z_wjQ-u047yeSeIb;`m8DQbCO%)r&;lUZ`{8ng9UX+HG`9Dz@oRVpEx#$dr_*CX5md zW;TfGf}Xj*y;JJ(I!J4Eu?FnuatH*?_9sGgCZM|J4SO@*cLOr?0kn80zi*ht^RDx+ zkjeE*mVT$7X@so%PF2tRrga(o*y*8%YbFTa_s_pO^3I2-rCRIZu%o6c_i$nQZQGcU zqv|iwVNMf6mM{2?3`R$2ChfQtk(r@S&sXhBaaF!I1H50~L9GDCd&Md-8` z2F)GrRGGK=t=G6>&;LkX#A>$oV|qws_e=kq4Qn@^eUxt3iymi# zwmWWT365OQm-4jG7-z>r8whbFwwyOR_%nIa1KDJ0ThnplzG146CH+I~t7vwH2e{8G z5-)DyZKEu|oj|%>ka@+fwzD>VKB?muIiSb*S{$&&eBb(MBlcI%ube=Ld@19>zKZH-eixxVZ zRdZ$3(ic5}j09H8=(LyCRhN_k$}4}<7F4N2a+R_5d)I({;D&h=7?nbH+_BbI=AYAyS${)%E zgN;Y5XJqJe7*GUb39`eFDP`{!9-$F;#3^#xoRFyHg`hMOkAjDGs@%EeNs8ufG4c5K zZ?;P8U3FS9l4<#o!Q)Pn;o;Y=QCneOYA|(8?F$wCr(wG9ExwAJM&vE$`-W?2?Y#XO z=b|M*=V-C1T?K0S>a=rjpE?d8?# zcm=ZL#&9nj0Zge6uCX<}i#J|&8o*0y&RM>+08^9c)TydfjQCmUv9=cR&}i7vO`;WT zJfPklw(WrN=sq;?8X7mavK?hqnT;MaK)i4&ArECSD%W{hIu|vL070CNFLRZ83|w~$ z8>jHKTTvVrHiWuPbsorTZ~-SxNF!U7pSk>j(i!q0m+p$ivK&M=@pf77N9FBF%psob z?dC^O3dcpQ8AUwM0c1-8|3(5>Kc955t!LZeeD3#UXGqHP|s~ zmDy3K9qp6-cMhX{YcMfJ^tdc3$s&G?TWz^{6liF<$7%LIYT^%L@ToQCM7YXKRVA)`35>I_$_*CVA_Y2&-e+f_l`|MLT)A-NzeS(xY`<(GH zVHLbqJPwPPjv(l`PToNo~O-2$DS?8K~=9M87Wt_p*& zyrlu19H#Qf`9}CWmgZh*@Fzb0*F)pjc>-GuICGDb<}e4O;S1VtV-NP)347gFMa5I` zufavBQ%=k?t!ih&3?FY~c*#M>yW_IG*UXh15T@h4`F;OgLls^C2K*|!00{Px#BZ)E zPuIAuEh+2JWA|`w+K6yfs$&0!GSTj!` zhZlf;~Qt{{#&s*qXBIg_#i+DqEB2i+=jYLLfC9Tbcw zkf2_ynbU^NXd;ZTo;ryfpF-VLt?XTS$ncxZOmhxqlb{E-7q0`RKeOYsI*o}EJRE%c za~F^0vd46}W}%6EJ{CV5V!6C>Uw)p;^mYhjm*hZn3| z=GAB)2~0gzZy$3x)K-ZF*ai*_liFP9kZyYOzJ)4v<}EkqyEny1-k+;>H)i@)4}|1- z+CD2b={~Mv*-R%3#RLX(HW>88B;{X8Q^Lw6HXfdWz~ntWrSr`(WrO08youjAT)U#0 zoxl|BF6G5EaRSlLUNaBZSmVPbC)#NNOmdqFOb=KGr|fzl@14;#66aLg*S@=tzq+oD z-#A7;dy(_M9L)cYjz=0GGHt$KSo`|$uf47I-RxHTgR%;}Yu&Zv74$qqm>frc#zAW|G3(fyPC>HoP;LHCD1HYex6=6M;Pp{3*L%#SFlw zE>Z&K3yHm|zx_$P#_;Kfaf5N53TG;+yJB*?PsqtMwgLI3o(996wVZ6ekeo?^k2>P` zNhY+oy;H9_)q_ONk*oc8>qVT@1Lu11d_gO;tl1g2OMIVMz;Z;S4y({mxNN6W3rZZ= z%mjA-#GAP=qSW|JE{WXus{^=(EuU5>LF6dgOr)J!}I~pG$u{XcBV)i~ykZV69?xuD_9ZQSG}vGSQu9 zXEP!`&#D^0H7WnOAQ*EDr?W6~W_b;Q>odvg%mCo!g#j$NMlhh{r%@0Z(iEv(<;wntm~AN5n|a%i&ZXsBLTZo9$)$WLecLl@HL zjM^`Wyjv2NE_9K*h9-=Eg1q7gjabxBXQ1uCt8hP0!S#GAkg3Ii?7=qZm8pMEu*6Za z@=DloWiQuyWe_)Y z{dv+#=Byai)E&wfl^)i^whVuB*Ef0Pe5@~6FX}a(tIm==j!n%#wLZ$QA3rzD@7E#wL3g}M4O?)B^_yR($$`3`gu-875FEa z_gffwEA%}}g)E7?OJxqa(q3$C<;GJkNwRMqgS19|A8WyT88Y*3?zhn_5V!op?D;~6 zWZp;TCWNV95ub~WoqFrs^vOriaLy|wdp$oc?r!504hxlSY-8Q8jqg!#v*(gqie+r? zq^rv1E;J}2o)(h(SVHerFO>K)syo@t-jjW%^7Ys18+3e^GHE#H~ znj~7XJR4u;{zmAC0KO*Ap&;bS)#x8obhE6_4rpq#tm9JX`qe6D?45fjevLtyiCFE! zn{*l0Atj?pI8o|-1oX;NNGpaL(9k{QDNWJQUsl4(Uz8S}A8PHBg{A(~;pF*zk41&M zw3Z>(EXo$0Q9NO?92XZXy;;=Q#qs*CT4#rvaLe6et;hMc^nmO~QxV6Lv--TREsTB0 z*tn+qHvn`+j7A`iZ9Bxp3oduM!kr_bHF!ZTD9NRbo77j!qNbA5@HJxHB(#_oa_r*Q z-nCdIMFz&B7LL6rejh!oyu6SuM#HxdavhNyMR}C6IMxpxsfhqY4}6=!wDZ-SG<^kCXdOWBVIw^&y3)ceP|J)0_|0iC4O_WDkVp{ah}eD`*6)aQUl|X%1Nm>hGywJ zeN@>y`z5~p!sOE#`RHqChGQIgyhr0>t)8ye8*^NKHpTZ#6qtL)jAH_;V9N8C>!JJ>!2 z;`{IQRqh=FZ8N5e{fUg0ui!Vj(Ea_e#p6XZI$^l7pC3Mb;mh0cuKG2N07rp2(#x#E z$unX7U`YM<2B$YWf}xNiM8#cM498j#Yup=0nD0?B2YF?ycYhX*t~~5!9!u*?8?D!L zw9B^cj8=b7FT~)Nc`>3vG|AOSUV0L9MuXXbTAlO-u#vdQ z9n2G8AWf1FkZ6pBL2=lP|LCcmqprysqwJ)vT%66v>xNp=_*&nZ>%WI>|qc}ne|`w$yZ;KI)NOaFuMzkSX0GZV^bzRn7^p|gV8AG zg*%=mM+@WNkkoB6g}Co@>DLAts=G+Pl^A7?lf>=!qEzv8$sHM^Mm*cNLiTe;K1j2> zKkQfQZpJ3qsQct;jPCs>M)x2pk8|r1KYu2+&%9z0P$Pj3>h9Yk6Mg)~VU3~Fg8lr^ zJjH>o8|+sadf;yY*$xEO``E}Dd$I*oMX|dCLXBI-?h`o33xLzp@UDV5Y2x<|Nd)DWwm$dEITjJ&n)1%18kge+!yGtsloU>%z>^Z#zR`+DX zP5jREfZMNsC>yN*yx~KUzMsG6MrNfEu+2B`y8dy_U)#L8wkkNM^h?!`urIuvV=1%! z-sopI(IL1(6%XGkNo%F9ac`YK_^~%r+RwtIJjSLcJI7PBD;~nquk}6%Fs+Yo{RGt5 zXPKn#hMoCEPCfe}WT{eHs@Wf(H|+Z4Az)kBWQPnFnFqKth*)LhwWT(vZ|JZL zloO3IuRErj$|1SnYxI0#GwUW%{MU>}uMZqmOmpgkxZJy%lybJCN}!eE(#M&!5G zJBkX`(8v_I9W|moLTS*IFEs+oV+_m+o85SarPa+-_7;2e)?L&6zUA*{JXp)R*OT(h zxu_)=7~Tped=cda35ZNZqoG@cj?#M1^BwzHDc*p%$5 z2^9=qK_fH|%~p&9HirXqK6vE!Vv!~aAdRy8e~`vxWF*M06_D+8vHYQp%wSR0VWJws z@z{JnzXJUv=xR))JNY4g94omHr%Yg_WEbV3`kkKLuJYl-k1Y=pJ4p6DUX00gvDk^L zKc{#;#R$juFliV`4RF{i^3pR6AKW1QVN_6}1zdi$nZwx>2;GJqnkFtR!pIVY{v61G z87|kVX!%2@8ImiVcj))7_{f|{Mx@}(w5Knv*5?jpm8Z_y3P;ZHFF$27$!FegP8#c#b0=Tat(mmRRVt^o za@3cRWivUo|eKl4$Z=d%tq2vvpp%EO9_ zS8^teY%04ahC4RLZjDC%&V}{6v7|HTWY|Uc6eC%BK02@qjj2B0R^|B!!4)P=`9@A4 z^%UR9#JalV+8*~xY;RI=vmU?5!tVEGo9h~2()2j8G?^nMM6^hiLX7{HpM z__oQn^m7QnD1pn)CHh^`v?ZG%tWt@nY?-d@ysDp$8$HvsZniyo>Axr@-kv}_>rl1Y z_6DG*wjh1MCNPSPAri1fl*lT+q4$HCLZCFjqKp7)0oJH#Fuok;!lN;1NaYpH`Hiu4 z|HBNul{FvZ`%!bsH@&hqDCCyaZSChYU`IFMMNCAvpK9G^`=DTcRC#%Dx+~# zC(i40rX4<=^4h-&a-m1QSWSyYXrDk%IVhh}JERnq<1@04K?4}3A7YQ>&Nsb2rD#WQ z_i(dN)71Ucd9*=2SLcR-`{kIuuMxKOPpWn-E#IaJELtBaZQK3=zz18z-hx0I$${kR z+W&~5KEOa2>H|y~ghd{JordSjE3Hl-%qdwLBJxLr?x!CFcnDyr!oGNe;#D!LxJw-3 z?jy;!bEHi8q?Es=dUmwx*DxIsOL0YLkyMPHo`HbPIW8APH7}qz7y?!7j;T$d`+3yzvwOr=k5r5Pwt$#HFfccv zHFETLME)Ionq_My5znPc_MH|YaqYq2g7WpcYCRUyLg~R}*yV`-Q4=BMJQrK-Z``A7 z$orWG@Ri~Sea0pC9apLUCUYKE#>YtK@MaK0B_WaTYi*qN{s%g;pK3HlZ*Nj99f#^kv0P0U zQM(>cBY=M8Cd!tc!$X-hUhuv!6Hy!v%Gb4yVkdv{Z(JL+SEc0umMkWye1OL)XFAJM z{PAgmSoDUB_WS;(R`oW6yYPku`I%#>BpvPg{**Q1u*dm4p%Q;;hZ30B%zX;u+n1L48$+_pKKJn8Ceq^@Y3FU%+LonIG*0`ttB8}$AO2V7W#NKs9 z!VQ+>wuZ6G1ozV}k0a#zbzI-f4IU^Jm9{-?K?TBo?(7w|)b*#kg{vmUSV(Xg`f;42 zoA*ePcF+oP(mZ+#h(v=Sb*G1ra2eLH4P1U36Em0{5dO;qSr{-or7^OELFI>HxQbpk zwsW@7F*N%34DJV4@{WC-s*pSO*Zi1qy%|!QFky1gDvwfHIlNEc_SDvcZ{fw;aJSSi zVM0ZFg#OxDb^TM1J{ygN?J~>z@5(H*YB$scHOd9BJ=+Ea+am&+Vf5fvrJIqy%uUCVN!JJpW9zCek!Vpbn<*EaRNyR ztRtB&{Cy+){fxcTTK$sCNIu3_$>U~TXH>(nXvM9{-iKCBwtb$cQfYt)So>; zZO{lYC3p7Kafsh|xsilhFx5rs;jX!vJW*b($|I;hK0Tybex56DG|YURKU{JO|NF`l zq|jE7y=Au#9~MF^Qtn-xu7Azr=*nT)&kKB&SJkcTf>XFj+ce=fHXHoNFH%zWJij&r z2foT>vVetTmmEcQp}S4~ZwfKK$_3!7JoTJosNEo6s^2Vr;<_e#J=TMv$>)7&SnM~` zGXx1+q!)kA_)$8AZp-7#SB1B_3pAdBNFo0AXw-t--s7=;I9d68RsYAbd$w~bR=JAj zcz%s_5Pj23;=G#THLpV`k#V2f!(XwltP5fzu46DiC`xegb~`6gq?rWCn<|{>aPkES zR#F{OwR^4;Qd@?{^&#uV&GWszVjNdY;=Ch!TJbO>I8hBg7AckH~yu`Fv=WDHB<}WwhI;KQyY? z4(*_E5PthDO7S6sS;-TZ80O?D$MYt3IuWvY`FE~Xaxdt&JiYrW<>e>mv?;`1vm{IA zmPx=DlVW4M&-I@^_gy`*p9;63o_c2a!?nfX#Z#$h-d#>!3ZD9bYv|tUx&X7-{TZuR zl@P|)9V$}P`-^#no|dtm`YJ}rLvy7J(fVFVHD4q14VQM7g`@}9&D=t!YNBMw;c6M_ z5I?T?0e;XZ_NU;Z^4hPt&Al|V>&r!PK$&8sXCT+X@wT1lV7e=V(mH>FJFMFa%PYq7 z;bUj6N@jnj6XWOjBH=CyK|0G*S0(Q9II`+tb%I1cGWRpIBV{2C4Delm6@aG#W_C!v zjnm(!U~G+E01Jd@6VR5IvR`R68GY(Y*&AA?{EjhIdIZEt__@8MbdHeoH5Db$ksLHr3s&9C&+ zJ%h^?z(qf^6`~P38mH6jvGutu8tdg#p~Aon#!`vXECjS-zQ<+?VQgJY%Wl$ zs1Pf&T*-X?jLCm&Kl4kqT`<8Vb7ip>x<3Uv{N?Q#pGoXSBiLlckAkqQvYU_9KQxvH z6q>a@6v1sVqKd&Zk^fx2DCo+v`{Nc__8CJePx_T-5o<{9!-U+L*bl2Tj(ou&?bJm} z3YXorY4?vGx<`AKkR4Ebi87ZdU6siGPA4u-Wn|bY-Jyp8m1PERp!G&)GM9-S=$D$r z$njl;CkTyH+tPo$6)>*;wON27zY*~iFg8k&uBrgzoekP#zIMBCWF%GNi@##INrn2t z-8D|BUv3fad}|A&mup@EgCB!-w)cm%LrPAis1!5y0v7@^sj6cp)%zjiD-JzwhpL*6 zdg;(#r68|J;VoDWE_ci|jvz8t-OodIl{Kd$8{P`o>h}C{QUY$9&I1q^1aKK_VCAm- zM<);raRtWHR2^inOn}#&ZEer|8{pO?{H2S#JbLeZGHzA+ZrzIcogNbtnJsF3{P;}wR3qBaUmwC|Ou_JS?8JZ%JK_ zzTZbnZBVNytlQ?R)WQL;nFuTZhrNu8Ho>fF8SxREq1$k5LqL5X+gj zxCUOqUz7vZVo)6w{N3-#|8yPbdYwRSbY4zA@WztDIZ~~7zEjTxI*s1;_D6Bn|KsMI z#t@CACg7L^-!AzSMIfPf>4R+jyyTl!^r&^L1OGt+JnqOht4ehs0F1Af`)x zAqnc#CGtIY@^m1xg~W;Jn2`qdYK}Yiq&DQDZ0T3oD{%jXP zJ_!jj#%S6$@n7M~?3sO&M$W;p1MmWUEwgVlu6vt(=OGP>@TuB6a zB1v{*?(f06Xe6XlJkmwPpBY5Wk3TQxW-xN&XjxpjkH>x(y=5E9F5;T4!ucw?y#+kx zJbo?Q7lv5XaI}{hTcM^b3s=XnQ;2H03#}XWbOrAS^e?a;r_RVWM0gR%+hwat8$bW} z)_}ZJ*@L~CJQHy~xtOZ+u9pLg%;o7J&o{g1KgTW`dIvfO;^CJ)RcYunx;b`n(`XFe zlDl+XWuuHnsvK6O-BjPgJUU`4cOX|X8!y!gz5!lCf$Jb`mTXwVDM_DnJU#a_2Uc{w zu3)T$K-L*)OXN}4bTsPDr=9>z8-W!pY4YxHQU-k8i^)KartpfFgU4qUkMZxQ#D5S|& z;r;;cOSJHzCcOM=mr_e_st}3ref@gmZV(z>d^i{o7`c#F{pJ1R&+>t91+GUN=uCXN zI`AaQW5PNsR=~NfkUG^7U3V|{Fx_$P{v$y-DCMo3dAYTX4b5k?mK9mf2OW`(rh$We z%mEg3CNALnhXIPx`UCLVKz#vPG*(nuum`-dl+4dNC!zN+!HYQC7y(8*&R>iL?b*8Xj&$6ZDzOr#~&dO9(u$8?!vlYCV3may|Z0-nb z?%(I@v}Uk{;)jSa-}xvn?sZ<}c+HSncL|fI zSqRqDNq=xt_QQU9kPcU>&GqXK(m|lw(IOv4w5|rdHcQ=WM~mu+SiZP%&vLw+S9Vfc zF|17~+8H;D5ZC`O4on6e{y{0}in0-l#)MK%5%mFmQ!`s>l#pR$U($I!)2 zv-J$wU0o7Q-Fu|P41w35nP$>Iyr49zfqD=A5(Oqk1#95lcsm)CW130gpl%C17j1H< zZAl@p72O7s9$S4q`#NVinbt}F;YW2|j-h%^$J1^VQvWBP$_mPV_Z6FXC4irelZTEz zTcT2BlQ>Eucnv0c@O9TEQ5UuTtiA=FG-)-l_KQBlm%4kc-B}PkFJ_;aVA4Es-yOY+ zy()9%y}{;>kXPr~cX-<7yUU9jLx`smqZt@PDdMAr7Ra!_$Wu80lyC#<(Oh2zGe4)6>lVPjyQZ-iwu>idX zs;;G6`6oV*bYCa}i7E3`iAikMepnt<)iFA>c>FF>O{*nW)HpsAX72Rs&uO_>H@Pe} zR~(15h}?W^uBX!x=FPAz6S1UQogv)=X0WQBxe&3G3EhvpaxDpk1TwE>z`H7_J808n zJ8zkH6Hlmw#BWJa{!wz$*&kX?qZ{TarqFF|d;m2=vJY+TW)e8Y`Y0`MJ}*Ugp>{bP zc(cpmn{Eh6tPU_Or&XI?3G$ymqNjLhdOr0><^_dk!Vc|V(r+De*_AngF!+k97M)iX zz2>aWrM$DCIJ=x(U3^LH2Z^qbTdZYEA9U78IWc5b+K9O#{T%1CY3ng?0tT~qDK*Ac zW`pM=9|%@Q+{}sAk!@hC8h7Oq-Vb1~+5#>9P|LC|+DwUxhsfg^1@9hsQjB(2ok;Mq zajc5b^K$EqAhc%&gyQ$_t^5UMSTJm(M8ncw>(TY?hyyTPd~M=?=X4N_Mo^D>+k9Nq zwV$zJHTzLyz4p0}aO2Lzcz9$Usu#Nd8qqT3v~EKb{#zw>8gKjOTYdkIZE>jFvQL1X zxQaEYm*vo5gQ0M7{G^(%#wzSadre){m$;6UTXUowf2h51y3Yr(g_6&8U7>OY7K~5G zqp;%~)IMkC*4+<3u5Y)(JYgH@cVahq{3O0vn!TW2h#l!wjcU3{l=LO+X}(OSu6OR* zte_qN{dBgpFbY-!YfW?K@rk;E-w}a#U=;1a2}O);`_y@WHZA{E8v3)Kv^##?QS(FQ8hcP&nrLC z+>o78O;fjb~?MLRz?&kEs^KwOb6;+RP<|yUpMya_E%$WR-Q+7X! zsppQ>t*|l0d)ct(F%>Ggz8rMf7 zRY_LY+t$PJQ;?}>{Yy_jrsC>0u&N8gTRL90pf+WK;P5QP`Yq0Ky(?%~wqY}DF$6ku z0`b`2WjNN>lgvBkSSpF;sNVp;_XcVK-)O>;f-RMe@P^tqbx^-ZlY=dcU{xM~kJN`^ z1k28vwWd0p=%o$oBXGX7xGuNL4LB?Z`A9A7n}?`BUCWYz@s+<}ebC9$&RSAh&C~c( zQZ#4g%Ig{HXNlUKb@A8Y;S50=;=6^?y~Nl1#&$oncV9rwqXAyOGSeFsAD)9C^hJMjFP^5qx z4#I~`&|dPV_at;)*Nswj{=@!< z;3w);&`3Du*rKt&i-68*Xxw~bbd{)F)p>)q**+o;>RKg(B70a>8buQP*z{$FX$~JD z%T|6{qrla{ltv?x-i@xf<)1z#rqv=Ol5P94u z`;Yz%Y{Sb7+i?>ATv}k9mz!LM#h54g-vODY^cR&r|AR`#Aw0qcYE@Nz*{mW$@>fTB zc)8YGcUO-4M*_pX>WuPSSK(>>-X7KnuNgzvtx$cmsR^rjKL3vJP4lp+W6jDRu#nJI z;1tVT1DRZa7O4mMeoDr+`x)6y`%bw_9ld(h4V;MX$^(PZ?t{XlK1$fX8D!JbAR@#Q z%wyaBli7j}W&72-6Ji&tyGPj(yJ>U+`K>_Azp|YQoMz4^Y=PS0@>DfRLS-RDu;hoG z)(Y;7{dSH%QPifA$7Q}P{oZbC4}>Vd>0#&sti>l1Thu_bKP(KYYG3*Eb1XB&xll$f zSNQJjALH*9J3?W51Mudu2YZ&mkNUN&6sE!dyuutFu|;8a6!No^UPPDA#>nO#HO$&i zp{fG5-6Ju&+E9{zi*3&Y@kg`Baj_(>Gw?xBI$;LIEeZ{tm!Ag+%(!jbyqeY5#}LqI z*>O(NjJZmaIP@_M<%66gUxHL8N72Gg(ycOwI;}vmTV#T?kE>&8h6H+2avQkd$9txt z;ZN@>nVmqKB23cJfu#qRBlQ96Q4nkHaMFDDh~ll8t6$57^&RW@#_C3< z?q-fU4_sJ7CNyx-jKPuhC8dg4_rnFEG)Nbp$rlZV$UO)Dy^rE|w^Yi?bopo%Ie(Oy zJIm~7tA`YZQjDt+!r#H)T)NqJ<9*iqme{X`PUNo(AxQ7k=7Lp;<nTe`Z&ob7td*+wqonnZJ>? zOxB&;1eqzCUKkZ?wFe`aSn0(VxVQ-g`>*|Bd~DxE@T?oF;DTvPTW)}*iwJ)C@jx95G?~v_ zR{IH&QH=;Z>;+t3wv!#(z`?{3j4BYfxC1MkgWTt*I6A=V44!9FPf6+)h|Y&pY09A!K6Ky(t0}lV-jWM;b#*PXl$Sl z6(0^rdB6Us`HT<_p{}ZArmKP=t=S8_f>z|pt>rOYgYtI|zV(S8A5ig| ztdo0@qxUX@x9Icx?~ECD)Ymf3$RkZOM|TPf6K<;S>%r=<2%NDR1wWnjw01TW?@1A1 z^yX}B?8B+B({*TA0>o4;cs=!+HcIh)##kRoVgh6SaFbYxoXJMIC{RTI&S4;<(oy)g^km@`$od2!__bPe~M3Z?2ZU8N0b zpPnwDX;%LkT0>MWtI!Wc>CPqG?fo>2ox!00dj`X>%D0NY4cyL|+ua0z?Bn6~?_luy z*d+$ejf6$vCP&z}@FY-oLawq*a&{ACJnPl+aCfDv{%w@~hg-6MHGve45AV8_2jjobP;b^jw zdgZ{Zb;rmFW&~SO zAq&T#0NBX?vIB}i?)_)}Ot-i^F1JteKK;ImfU>z}2}(8y{7{wdQ5He6-+W#no1Y@K z-(RpW^grr19q!sX1F0P|ty12>ef&B17(y_AX~iYo$B!sE-7fqM)a-OV2iDl-;z&gW zh^@`wM}EIxf;FtL_mGbWcT2`|87s@ z&vXJO&1~#-3rW1YX~5Aeh+a{xI_`NSitb2wA?b0oc0cm}5cbzmQAb@HFg&z^fCxy3 z(jX!*bPT9;cZ*662uKSELkK8>bPXWg3`&EDph$O1Bi*QUjqe%M`?>G+t?zyRn6;ST zcXD6*+WYLY_g$5fv-~~j5p|Qx-=ni*yA*UnbhsCpdW%*lz3JMwS*{zikI{ISE4r&%58mh7*|4%NyIh1i2Q0K%~n7gvJ_t`iTraB%<_*OPdtM=@Y$57 zbO&_44XtJAe>49sX|qZ;N!7#C25rRuRUI+Tv7K(wHW&r?Pk9H%=m+{XyVFS*0CVWk zps9%(TtZILf$p8Ao#fBav=_!roU<<`o!ph_FxOg$i9w! z=+4)HM=>9tr1Oy2Nh_e#4idhxxL@PQc4xXb5rmaWPP7f1wg@`XdMH^M##!q6=yQ^% z(9P*7<}ZER=k&u+oq8gMgwXlZ^c!xI3HS9SRf{Oo`}udw$jW2U-jf#SdX$$TEB%|Q z30vC2hH6_Y5RJ=(*daBpZGUxtRl4b@FU<*XTQF`!1u#&$e4H@Wu95457804`lzxwr zOug2+|I4iN zc=`s*Ut{^lwi7GfiQd}Bvzi54C%B|>JVoJ!8LEf;)0Ott8;JZ80=bv zEq5Ps$u-3)kFCfX-oDz!qy}KQYRqt5T#|I9$L-zChi%tenN!^*-6&h-Xj`cDa45FZ zxa*Q{bJ!NRQ^6AsMy7k!*8U@Obu|FFr=?8OWPLUf|M$yD@Z5vTm%pzq=fK;wOs zh9;GURz@t5lf72_#(u}nwdc#d&QTHu5_#Xc3hk~=$bF7}uW_j0YViDCfr7ht^}&?U z#Jl)Q`#6PXYV1%0ba(O_)q~L4EiMpEG9Cj=hn93SZvN2-t#a|D#`9#pv%?AyhMxnr zH>`pUZ1w}h(Y5piUBMlB-&O42kOSZq|7r6Z62OHP%6H0_st$Eqw%0r)DZ8;dMoqxm z>wG@3;)QasIAz3^{m--EVuyKD;5ZZW znH0Di`GX5H9UX|3hIBL@$I-}@bKAaA|Gz(g2_ufKrZ1SF@_-3_Ni?#rYRaj`rq9&E zQGA8wpj7<>m%Jp7)1=7P-;jm8SXx0uxiw}T_|6D5erBJtI~^bW8($v~MCs+E*KMkC z?zI(Xw?TA=vD3lx^xc^;;5Y+QB6*6`w8dT>0_*j5wDIs9(OPx8gmFc_!kPEeD$)I( zmD_jJmsX^g-(#WFB!Sm7(;+;nSRBlrI_YX_tc(G=ClT#4ftXVU@HifW==0GyyR7lE zNCCxm2Morl>+fi}VW4BT&5w65)2aoShGv#O)IdGnkg0M48@9FtYpro_5ZhOwb1-77 z-mQLFS|+eHBQEUi!V^u|@I56dqI<$>=<&qy^Ky+JjX%=+j)yCu02VM4INx`%pKQ_H ziD7LD(kgdUV#v*WRdK6{Nb!pJl5(-gFiF=9>^v7lQf z&lTLm*K#6bJ~aqz5~(g4#+SF0nxE89NNIaU1bse-d|a~;QlY1#^A{o}y? z*1$;I#SH13*)3=1%Ssgv?|n?MKv$D@$@r2MozS-A+&nxmZTz?4p$N>H{oA#+8P+`| z0!?{bY?TSqkv(*#rPA4NNgHmRu>Y{Cs0~z<>9Tg~_G?S^(|euDsCNIu;MyV9eC#b) zeczmK!F$tT%$oQZ162Yd#b`s8$2OyBtlv&+x=XvHZ}eDB+xK^>+_S#P5rcD9w~s^b z%ac||KGU~ss&43^)x;#L(;c=XEY~;dj_44nS zo-gM4bXYp(7K)kL2}?=Bx4m|^5SRObIN`rtL7Pk>F0|zW;`=S9V=&nE#&bLKBNaNd zFYFhP1LJqe4xsB1+knSy12^D-ihQkccFFu_KC!UI@lhq%9Km2gvNbzg zDU7C?S>A8RLB0s!J3FV+A!vM{(O}h4F1Twdd!$J0>cmp- zXnjiqCE~6jI;?j1vHC%5$O#Ubl5E(a%>_Z&GObjry<)K>+*pYMmlV#5dP0ix+FTg7 z#TH+Aee-|b*1xz{>griV7eT)%rj7*4s<=RvQRcg@Lj(j%%NJ6#Q8200`YZoD(@-K3 z#qxZ;X>k$rJn`Dcr*}ib6qA@vZ1L0%F8g#qPP(&C#?s)2H6E_ZQ!zf7i%ckYO}h?O z?!i{A(}HD`Vj{WgCI`?~Kzz)=xf1;KlfZ*@6%W(sE7r2FNDB{`&h47YhHtUeYPs{s zU0teOJSD90^mek^#m9a47|KBDLs&eOVpt`VbEwk+P4p<)^yIe>ra8AG&ub?=IR&0A zr^{#|4XAbDO(WM+0RV^g01hvsp|hLguINu=7eHp02d`W9S8X^?!ypNeoqg0fhlVeQ zTDqPW@7W>|u(OC}kf!LEFwaTsYc2>KEdJM0#iGQK;sd<)6GL#6s`D^8%Tj zH>e|If<$~{1>hp-uVH7GjA7*fh%kR*P?{#I=u4dsrXv>$0|OYaKPnyk6nrn11zZHb zA>%HHz8;`KIgUo-Kc%r%zw&6kP={Q*V{{7LQ!7l<^L0P$4GdZus)C~=TS$`@&huA} z9dbSkkX|T!47}-_!C~b<$)u--yecN3zpvTd(`XO^U%7=ZFzSuO?k4IyJS^rcn%$o;8wLQaa&V3 ztFHQsx%g>ZARhZqCv-9991y|A-3iR}URSS=hLWTR&QAjh-Y5+QL^;~t*p^@B7c zM;bp-JvJH+`d?-ZlpLOKUIJQh;n^Jh-l72qa{5P4xAn4_z*3pR^G`;77%kYFo0%1P zVELD<5TXAEyY;qFixu?=6A$l4^XoItXZA=CF3oP%{neK`KnZsJpS~=#4j;kF$BXYN z`PoM~o%Mk}@U~9mC~6kY1ZQ%nj2W;1TJSbGS!0ISs*gUt-FBMqfmnz8?3EzPvXvda zqZ8e4w(E-DCFegm6x^HQysRJ<%R*d!|L~H&-1em&!^R)Kx<-lsQQK0MeHdcB`PG&}AJH2DQt90cs8=RcazXivx1dZa|hq%h0~#ad&rD?dgQ zSs*rdI%GA_5Xj-xR0Bl2eB)kUw z0EO83Q7TnMSAPJvzCi`!ey8lHROlk-l4co5-6}owL|yUNiukOEOp*m{A`hF>>vqqk zsB4be*{V`RQdTv_Oe}wU+SsTe06R2+WzHvi=1;brcB$PReHO{=)k))*ExNE_$^iZ& zZqu)aqs0917}lDjVnljKIw%Jltu1m<97xR;NVm{P6(i}N=mK6iV2aSrOX}yk%i*pZ zB8EpY5$-b<$NKW`Bs5%tdkt@2&g@*Jc+$PjnN@L%Gb;>IpJ(SuYc-aF`zAA_gHm0j zaGez8eLcNKr@|zOEeO8(t0?-2c9(GK$9DdKN@PX%XNN_xTP_~y#sy_iPxJ9#7#7wF z2wz6sD+hA7Sd-Mf%bcz!`g*N-sAw$UY4#bdn0fp)#!G5FHHPheDE~3)|A*a<@xt#gVr%&p46KIwL@^YDISoz!GWh#&~d8g zw?7S6l2l^F!=+jpntb$coY$Y*R}Jn@+J>q5;6@1iD$66R@aU70Dozfhe3j0iqI+DV z{T^A@AE7TXKE9IlDs?e|Aa);hBd;E!zup}LZioSNXt6=QB`V}Sp^w}~RtcE;Fd#5u zxckRufFi7wz{bIFcwpXLKO8WH5Okgo4=;}7yU>i}svFI=^Z!re3$$cjFR1*50Dy*-Ta_!- z1CCRDPgv6uSf#z^{9Q1}Uiyr7WEAF%7Xg5s-l$j^vRu_3z^G~)kHVYg7 z8Zx846nH%V_8V8KfMKJ6!6YC>|16$@0hz7^)!2^*7eHKLrUCLv@ z`k#3dB8la+^L+M%_zGF#c|70Qnb8GVS2)o9OH?mRh-{=~B0v!kSdFpZ0E!IJevuR1 zMMVyN2arD?GvEdvWIA^Gqho~%-5(y(^2T0vc-{1X-AT$h(34LLM3&TT+ncC=J<-p0 z3NO#<{rDT=20$GSrQ$(YcdFx#0#y=p0SKfZsFc~6$VJ-VP^-Jg{i#&QdMFJ9|??YvyHlbUyJ~l#6qCoil=vpCJm}|pLn%%n3dIS zl6W(Y_;YWkdp}ubOMHG?xQk}B3oRX2Ld9@l&-`tg@4)i^?1UcquFcpWI$+%p|FdpJ z#BX6t-2W{2AEVFdzl=T*w9w?R_GLr8c9#CYFqa-Z^1)q-=p`}U=*=GxudPT104qvpcwyRfE!rZF9c zuHNSD&CkPjaDA1v-Y=55&lpk$ztnJ^{8zi=Tu>bLKhs44Y<`S|gZlV`D`KfUW;(Ku z+>D*Hb|q*>Mfim&&6923rI%OUi(F1RPf7Iy3Zh_P^!k@MC5pDE+aG^|$N`XnP+WKY zsa0j)xvv6Rh_WTyxM{afDyuccW0YZ7Vb~qknk7qumeg7eC0(hc4&tWK-Eqy+Z9EHABFol*3 zzM%dVL#B(~H_L}}`$bu~^38;hai#JGxY2s5MilqMnY}x#9a%}#TA%!xkX$JsAJ;W4 zt(|ONh?1P()7&XetnsYmTJ3EL$hu3qaU|vw?3Z=ILm!=D{C{vysL=;;H&g0w^Zvre zDOem4Bu7CUw2Z0`QH<9$l6`%7?uu#4P31iHza{I+TmL+w&H3BtNW+u?(XVQ{TA=_L zHbs_#V(qfqB2qjWuy1dfV)lOe_$JM<6e*mk9qpCE%`EAngGjZE5+5)R?>tm2y&WDv zaWg^FkaMe^rbzfuU{aA$KtM_!1TfZBQQZ!el@p%)s=j{RuwIjP*n>|B7`D@Rp+@PXS@Gt2UdweH;=|6VkQtAB+I5Y>{y&W0Z0mu`5AuX87F!u1?>fl zggGd90uI-hiU&XN%xbjx)W9-J9u=7)TmbFF0>^&y_E{er;-3@eb(CMJ+=+Um>Mm6l zrcEox=u1q0LR)juDhOcvGrGU6&i-jtRZji?`$saAu3#Kc-R;E;G#d=mmP|X|C_0F% z87IoF?|;97BPv(^YdU42Lr$tojlSy2TJYV0)9yf zt8@eT1Au<+llZq{>1Zz?bYR84%UpMxe7Su?++h+gc#>Zku@npDiKB5v*YRP(;P<&? zWyMfj+LTju#I_0IVuhc`6{?hsd-<6)9=srmXUAo?WT<0M$j{~VU%~33=`j(HTR7rv z{6P!47JI7fbiDGP$!{t~s_ufDfq!Q1@5<^ekM-1XTU6hIg>L@DERo2gZ&mqr2DA=? zeK=S4tR7(icbnTx+kqRt5UY{IqX;5^WT(k?g8JY1RrNgBNHi!re)7IGd5xYse-}dA z`^G>?r1(8ct*B5+vT44`tyhEz9)tua?G(LNSigD~3^%uKbd_1GtKI)~(`5xaHm$AQ zxb9=ZMyLyg2fd!ByH=tob&huyCi=ZPr=a$AyOq`o$n!P}ZyK zoL>r>@|SZgfbULF9`5hDr4+lSf)wC{tPF;!4#*Jlu={x7hEFQtu7nMZ|FGlc#AzIQH>6c*6!$2Ul=E?Kk0f*+&L2Bzt z+O;LNk2c2dhpYWHHfSd~6RRl_T_sq3<#z=VX?>V3ofwT#p94 zdqT2MRunZYCo(O0LYoL3qKqhZkQaMe9u;{)`%$sf1Z7?}!clRokO0=neS!ES+L-H* zt-0*IajaN=Bw2Q;sz>`wy0r$H{k1uTJYP1I@OwJ#CTZRU-bhF8x{f7r2{~Ghkj0O^ zd`_W>R7GtUNNFQfRdf_zMbsMe&E!1IPf_>lyDEayW+8=Bbr&%e^E152GpL{Vthb`XAingC#!l<7#P6~N~&43N2j!FcG1xMu|NGcXAMeXN^7P0YK1z45#E64H+D7ua9fJ@N80&a&-DXqd zhMs!vQ+eUZ0FWOUgMvb=v{l{OEJY?(>Ix?q(1z$Cg+pv!wbIbx`V71G+aLaFE2?Ns zSQd-7GM#LF_ULVntC4~ZXyW~e$wd>_xiEm^2&;Djz`BN}K-f+pJiy%@tf4bbGF_dK zWJ7_NOJcYnqX$>0;a22%eH)sh@dAPV>WqgD_F+P5H^)pP@gFeP<5ZAD9F2*Et$h?J zKCV&Ao4EzE{-B*q#!UDd^2Ph%sM+3Of=Ky959Rw9c5a1n48p=W`k!=Vm4bQbIq!1% zr-x1xFsO2*gPpvlWB{wo?>ni-dU|sq$Op&%3FB`_ zn%0Lv6^YP5_sN^|SMAKVRQ#X4`8UP(4nkt?X_9SAlWBMHI%BcPxk;wpWFKpPBe8L( zD_S{-Z@b4(gT`(H3or;erS`W|Tmh=IrXxUczx)j`07d{t3kBbkE+5_4eGTj{&&`1q zaLYa8^4^xbukfN8xJX(x5TZ9$d-L5ot(%B&sLo(B9pc!5RNw#f9#h-ok0Q^LxRdy< z9)7v0@p0NhY)tTA3zeMv2$bpck4_tqhZ%-Vx1)YAHU7m4~|mRH<}Tk%Q1=-%RxOw-y z;;@7$ub+tY<5ueWta%bb{A_y^J|wzBl#qfKtWLMVGt4rcM6^YPc+UmYzVKbMkrjAc zAXF0ej9wGJ=tFI1ltPuLzIbI6eRz<;+(#vRx+SL-ndds!8e~wd+;OaF`{L6lI~5T zqy(uR+;-t`Gl)OjZI(lQ`90_@{c$)USV?;a zfDBD>wD0qB(ZFyEP_>qii0}6v>ZV;0lvHcxVm_A>_&|E~K|3-=3eua zeU>qy*z;Ub;P>?S%PsDD5>bK!RlC`P)c;~`}pgnU(%4_ zE_G3Y^=2ZMSmvS-w0Vc*8eg!Bw=|brHcfo|S;<;O_|LhYJL{ny8pb*^iLKl9+R0N( z4_h8m08Rv{Ytyuyl3MM#0fjV(4=6g%AZ29_q6076yPPQ z6R?crl7kp2H08gtE05Kn$sl61X<&S`Ul3R&c|{ZF5Gf+Wp$vDHxwZp!D!39i#Mb~Z z+U4Ap)7=&D9-Q-xBDI5*TT{$R>f&NnF2j!^MF;JTj>EE?()P_No|ifmdR&DAFCtr;au>o*7l{^`J+aT%kK!M^K&u3h& zYm{OHII+jb&K~0%uaR65TB>)K!<0F(v&d)`M65{tQuVOYc#(Oh%zgT;iZVH%fQYFF$lCu z5awQW$?*`P#6d9&yHjhUhfcLe?xqH~(*B0vq|Y<9){XC9dU%V-@zFPZspTqY@5AsK zZEUWlGrRJ;+k%4R==M2%NBJ=J7l%7ANW8gniMluP<>c2U{{W4GJmYp{O6v}SNK^gi z-Sy;yZUwouZ|=A>rOWCren`-%!XMbu)^eG*QcQAcwg`96vorQKfmc)AUCT>Y1ZJ6k z8h@W(UJ-8{bK(;}XpP{<_bqh7_bu$sxn7o*w!7rzzgZi0?a`;GJIJ_gN)j=m$y=GI;dyW$S=q1_Iy)`tpxeH@gOjo4y8-qx@a zW0j#YFS`&Y(UVt5eU?HB)^`= zp1Z3CF`ZTVRO|%Bhho|I(yiB8sC@DVS^rN^%i1(v8AK+lvwEsi?s>;&;8J|gd}24{ zy~xI+{F_%+r!otVg401JG7AK%xAp{c1WU?NWujdbd?UrXpFyz_Wfv= z@Jspn?%@Ni%4MIW`jiK785NWv#GE-<{`4`>Cp6T7B+pP1zDg!baSuVXkG{TbuU%XT zd#Ri3NFui^V^;X+6`iijo&0V2c0<(-O7GtVyB^byC<$_0f9+N|v(KtkS)OAj(0eyv z+pa^X6fqzvWKa6jOnK-Ia3T6>o!c{3J(pvqO&`|`OelCC?n45CDb?XO-e-kzy~Ol^ z!Av?&_=rvc=VJ`{F>-06VDxH!keiG+!^(c4g#sT^P?jR8=qfPG;yg3(vcfoV>^03R zZH?V$^=10`f#<$|RLJ2QBKMi6W_7Rewb+7#)!A-+CU3vK4#^UTwc=PI*PDajK`k7`JsLv5!>YU9;gB=$HdveW~_Dq(3^=eEzeHY@Z9q7~2 z=POwn+R3X-eXN*N2waXRRlKb50aaP;X2H+gN_3QNVz?ec#CU<>u>tFFtO~?6^NBR= zahWFp?$^N1M?CXkS}`0{j1I5I!+C4Rxqmo>ya%u9DpVj5C?S0;G0GYXEip9 zWpg<@DRfGJ$e@327?o^ps_?U(^o!=~XfAeXDVj$24|%(&@u}}?D}*esQ>(t<5xt`D zNT*=)+6?z1`{n(j4Co3U^NB99=-%~g?#bY*;SPjK3{rMU8#1)~E%eXCXo|5~dDsjC zKIc2Rg3nTR`v*Q$P%bi7?g(hylc6;!m^PZVb>2|EZRnmsw6sPvqL<2qVzh!7%}BwC zMttWZ1^jP0Q4BE`h@9#e^%6sLvVukdJ*ChDSh*ycHxvv}Er0x$t!M$duOmb5^=bIi zqrJQ$@1Y-@ShDPi>?yTaYJ4)+mLo>6Vv;N~h@`D02EAtX4W;MtZtJ>R91%j&d$W5B zJmucJQ~Jbo0zc8jopIh$ItbEodVStF7?l)xcly5}RXJaci6V~CaMs39s&gMc)0QHt3nh1VeLZg0Z zM@fzfM}1OjIyeP_Ij5?m2+{16C1`Mse>}5pV%?egX5E{1KsA)Ss*ZiASvYFXr;yef znCpIe=&CRcA>QRW{K8vux?jugMsth2FHp06xqch&sz^!^QV{K`f>f5V#cD>mouo73 z3=)(KG7XR2!E-z5>zbRUlv0g28N_UA)d3~ddv&=vJv15E2{8%&!tTtDZoI;)E*8X& zE2}QBdnfw57rWX=tD0c>Medi#fyTQ$Br$Y^#tyvvBv~m)(|(-j&N~kknHR~-gg;~( z4s5x%`|s-hp;iF4U5+USo@sCMRrcgg|J&Ax??Sii%RuVIGK9_TbYG#8W=vdFV}pJk z_JEQ+{H1XWO-`WY1)7&g(7r)#m)-Cb#g3vgegQ8qX3(CNac-Hiliol)C%t#Jam{Gq z1vyK=)=WXo%f)gp;))WV{%rD~I*li^Ena!Gj}^M!ZgrGQmB2ggP3>In+`LigeOSaA z4Yj;!jBitT_C7ZYeZ5Y*=R+fkd$>||~iN3*_nhDIYtmwQE>D;kLd3RpL z|LP|#OS4X_buKofQ9vKjD%ar{{-Q}tE&tatUuRXqRh^>%i~Zv0saAaK#|7G9kRhYd zoNI+ELU9yt!(rl2jR4#Y?PBdH)#`g#Go%2<^v%5o0>7TqqfI4U#SCJD1BX+J$T^{2 zl~}^-m#6N?%kCEtrD`o};=5zqP2fey)ntw2w*4tXA~&B)q*%GxkG(?iWiQ-SiysPE z;Aps02W^&vaABNB$;u}X3j5UszjxVXF+f5Nw;a&JuE_c6uGf~{(_V5B2So7dlk zHBAExmZRt)w{+dKJM$z{=I=kz#Fq7V_p1>cq2?L^Bp#itdr)<)PZILZ90fW}DDV|) zM{RnUU2~4{s3gye{Yi{Q8Hz`r*fGOhE07bSXhw3sWTr>Q2FWcJ)j>1yv^kz-^hML) zkh{{}+9C6+;UD^j&5`Y4t8+hvzAo@MSnQ+#x_^Y6dsM&JCUQk0z(gFHXAYy8$btCU z8!EoKzy2HYow@GwZ-@fm1Wn+#U!v^Cq_#>(M|)vEN|1PP3qgxhKg99wP~#60*pGr) z(^|)b3Gee;z{Nn=-9y33qU2tmyM~wG>(_xX1kBVM3cHv>+>CJbTXG|kLIN&r^^*l0 z84yA!M~>nse~g8Wp_6L%a&HIcXY(VfZ9uGv57QYg#sQH-+tZ3zm;tr`1l)3%x0is% z-={@PdNS?qJOY-PGsg9aaF_y#_(RcH7>i-liUKSDyas$BeZX`?fN5UgV7l$>^cyhz z=z+myt)*yV@O|15?k)#x4OxaSNxhS{V=aoyJ6>u^RY?4ruS`KMB;LoU01oK(JnTMZ$ur-Pp{?{!jq0^kFU+9=+amnD+ zZDF7~lS33m(ww&2w0c%--fgIo`z`&zC+yFSAmIobxCimwmGbLsp%S+DZXq$!0J zdpR#f@@jN@pXw7&jgU?CntjZX(qNCyu%HbVebj1)tiI%U++$=vI)Tl}xa^Phq;Oa9 zOLSfYKFb4N#R8hH)C&4Rj|@C7nqI>}?uz$%xMi!59(F;qgb1etGjW0T>-vjt(IZ+B zU#G))9I%%yk`3?jPg$b%668swcs}9~4+WV@ec7swvY>v<)hSG2)?Sbm78sZajnl-E zw*{<+IxN~!=u&P55oA$Q?k*jEE@=xy4^RsT#kzy2CU)4fjvOsyytY4?Y#}ArXBi6e z02!jes4Dp$RiMNY^OCu5?hV>v>#*Id-2qn&$&X(Rb)BhbdliYxlMW9>fe3T-E#;#VM*_;pBO4Qu!#w@4 zZUrZDHTFqeT!`ojeQM`CIP(=T zi4lMx6vd@s^i=JCNptq8;~b)^ArgoxNI|NiO02Op`R@4pg(M?>3Jq-_OMV>LDs2nAk64}f`B$4^qtOPnvs)>V$A@KqVKj29IQ{?LRlwmf55#*0o+RDUIIja3(Kty3 za1GP3i-+Hhg<|Ch75l@6K@0^efG%;^)d%;#C-5*U+&fS_0wG)W+_9;H?-_viK&kMV z->h*Uoes0KUcbGY3tibFBkZdI|9J)It0Y*RYrr91Daqk`%~a!p9W3$#=MK>UY-OTs zXLIp=L&B)mZtJAd{$WnETEdV?GHhw|^QUU?&%vVhH4ux<3B=eYc=uB%wucYO%7YX< z3bB87CBo?;Vyl-QSdL?Ch0g+gm0fb~6C6HzaTA?puZWJJ|xl5 zG3vXgI360?m~2?Kw~D90N=NnlmhQVo{E`us0|0McbSVJPK_> z;|m`z#?Q;e1?R-V{4o;dmiq9AFR`3d0ZiZulU>ebov5dFQzD_;UG4iBxNnvXsc$7) zq4m7Qw6)@%oa(B+68IUkqenYonBwNe6aj%B6rAk|c-eW1)Y$dJEPI;eL~jJBS4!)B zN#D8RDns>PsvciZlw~L^Sr#XOcN=b-fk!|;I+`}G@>=vhJCBhCPDso&^}@Qmn#)iJ zTV>0Tgh|1cHfqm-ag(9>2%fjiUh3IwUdzqzkdM)#i0>-r4M1w7KOp`pT}dx8aH4LB z;P!PhY#Kq&VuW4|29!2N0BtY=_(w?sA7@Wa{-ZoQVwXh#1h0S~i-OPA_8ZiF5X829 zOD2My;U;dEn%q_|HJ$MUm)3lp2bp@!{Wmw#RdcCz%rJ@hpA5h1L48%P0o z*kAkzV9*HNPqrGdsE#3$QyR&ZaESI|UdY&Q0Ri<>3Ot$BWu2)^d!iUEjDnTIo`>^VFTb{layLaP;I~^uxg%`2W`%9^tS|TJsAUbJ0&AW=#M6 z?x#?S9K;^s1c*&u`X8PXEDj?xlV4x6&oAb}a0GOGq?}raC-PH18#>4V_1VdG8|LoD zTBC5Ip8kR%m`~O)?QZ;CFoWl8KGbz7%Johc_O6eJ1=_cmN~;{??Bb|QdNl8nKRXk% zDQt?KxmY@hze@+JDTS>JssDv9KoiQ?3&%>GTdLnmCt$F_${rcqvK`M&jf##7(V@5$ z%Cd?_(^N!tXrlYI!O(TDFrh`k6`#nX_1MMq1X&JY;2Q6dgTAJ)>icdeXsO`IY1oOg zD`FS9<)`hym4FlOR@9Dm?={^ocDxyG^|CJ)q7Ub&mHKi*__W%vb?p+)#=Yra>hQJ6-j!cal7mQ!F|2)F z=hl+Bj$^5%8FKS2JuSpPkc5~GZZE6?FEDMRkTO+vLX~R!3ogg-|L==GK9GwN2W(K zOiQ+x>l=PQ35gtqHue;ikBq_Eh5>#DzASz@*XOYFK{<%6#Mg+*YSO{1fNldhjT`H+ z{1!1T@W&R*`5ZfhkV%ZcM0%UKdXr3&H*mG z1Zne}+bKU<#k6s}R6>^T{FgoIryDuK%9g)G)nj5eAoXcw?g!d+=Q!QGQN;0gzVjcp zr$RvdF^|4`Gb`^D3eFV1T(o%c~w*TkKNGk=l~rw51mzSR90?5B zz)eHq8`Y_ZE>J-zR`nid{`p(P@d7C02KVc64nGFYnpt-Ln_0Q1Lal;}Dxf_i9yn3h z#blepfB)K ziBavmd^#46I?WzJe07RT1;rC@;$8D+`=0z1$Ax6x~m=ZSULagMN6eYwN1P-tpkNs(q#rs#?ih+XhO zR=INeNpWWuQfrwY8N;S zRRaTN!FlRFkBwskAHHBj#f>l%BBKYFuL_^%yq9YB6AF^fq)^tEHm(VmJm+;MBe7l#oGIk798`=b{O6hsotv)yrZFzZU~UGXLH`N~ zL0Rz(qp6ypH>Y_w$kA5#CSbU*7)e>dGxhK~j8AsI=*?o6g>fu0r9B1xtOK)=q`QD_ zl)Tu1j*sQ!)DBeA{|W+I-=9t16cRq1H@LW01Ed0)Zdu3l3nLNzxDR8^oWjs%IL%;h zsV|~m10lPuaP}S}JEKRRMlJGeZOh7d90IXp$L*{>(2l2i*cSS=VOq1q?01fFM?rL+ z#_8M$7Nc!PprZL4yY=P`5cfuM7v(^Zv+jMqQ-ni)PzE9R7k9YJnJP`alT-qj$`sl{{uHHXctkq znOd${wr|Wap|Ap0+2@@8f$jkVcVdD0FKBxZQ)}T;*QWJt)M_(tls?L{W}0I1eGJ#S zh|&2VBkVP0DmQ!baLms##^N54t)~k+Xv!C9BGBzvz3-CD`O{!s7{r=Z0O zZ)yI{8`JNP&AwWc?Fso2OH1fZQrw{M#6i}!Y^zu}Xk}D}u#D*P89OY#Oo;J{@Rt`K zaQ1O>%t;`bohCr8yu1B&U8Z}Agu3+jOuHCrL$xf4PQ8+GUngXQ8MsCl$j`Y1Tu3oE=%^= zNq%0_vJUUZ9oJE+WQ@NK7x1Bl#AQ-+YnIV~H25s-ZFnBniD;-yY0!5Wkp-J!tWT) zBdOnn_zN?~_5_6C1J9?rCC z^>jPTt0Dh315lZ_3GAf{kdEC1G^W-3ba6~6fPs=@+y-bS0StOamSeV(6=sJ)6wExs zTBnJcH-OxH1#(j~i8+%7A;X{4+|hi28k=c&dere%D>$Ox?H;V!7q)t4<(x{+?sjUN zE)M!4!8t$B40bOB!a!wgU=3n)hQfso6hHtq!2*5^5Few%py^h1fZKW@c7kNCpn5D* zP#nq)P0NBr>F$z#@o#t?|ESY3S$i9)*%zhX?_*v(zg@a2n!SHKXj{b@Mwl=qMF1X=4A(9bUZ5fVY29ilBuz#O)I zCKF`bza{i7bmxy7cn1iK>&?-HO3c*Ze=xsXkNSFIHl@z%r1NMhAFG}=amv1|a{$>; z02eX#JsT~*zm)yBjt~?N)SVFt6ZVwX(~42d_k|RDxm1sKuh7+7zYluFYBO6~*0G#l zmsVe?5EfB~8@*Ax&370m1S!CSy>0lk#E!F;lZ!do8FGlSD3&%`#%#Fzquo}GJ}kCcJ&Y}`6$6c#x{wk zvCY*X)UQA*{~BaV3CCLH5#}|#)Rz>BsJW-dKD=%E-H`Ku(iwhj$U1mCD~d;fW|~7? z!hq+gigLGiEV8-{QYHnCzkt3Hi0=w3W1!H|ymO(cxNI|Uvl3$buYx4v7BozuXDGT@Gx)FLA+jv7v2Z!Jw(C}}>4<`dK4hgJNNhvxd<^vd*2e)>hM~XKr zFCUI&o{UnCq>j35#w+egMVJrq8Gn1yYa!LZ650P%YVosQtO|W3y-7?cr<*b75GAD#(4jl2~HFI`Z zn=Nc^Zs~uknt{zWq;PPN2>TGE-X0O>$!MxOM-_k_ecp#jOO2_e@f!jZ6+%rX%l|ee z1u)a!4?xW*)X(_+>4wtiCDYDe)F+oxS&M)%riiE6Vx?VewdR|-d(~^lx(x#=)~+y6 zD(4K8egF-QV(tS}Re{XPKp-1Y7nd^&Vpa~SGrF_2}fu{Cnb0h6&Bv9p1Q&;jQz zM4-&a|J%O@fKWtCRkDi`Q{ai9l8y0+{qe1w`sCoR>aRcCefo`+?AUWr9BJf$Q?dKN;RvkChJlj{0uwNsh|h zvFh8B*!kB6^iM?$Opz0(pG9%j0oPmepA%3e;-DvLjt0RzVG{0wDFk2YR$@K1`=9>1 ztWUg=r8;B|ias4e3(3$vmDI-VT`~OlVdSHf18UM#vApfHI9Gus`pkS~^kbV=L&C{w z*R9f(j9WhXY0DL^7CC+S3OC5i=GvwB*G#*VrR-@wg$$S}nKd!ky%>yXqp0Zn6-CNk z4=TkXh*^JHJjp`qK%=S4A5xaYL1-DS1pj9WUQAX^S#N zxEtGi;iG!cLzWPa82fl_$Q zC#KQcZe2%TrtVHV|N3xXbs!{CJAh^PB%(?lf0+Y9SUN^XK%XwFDN&!gK)t5CK(-7g z&B!CX_c?b>1`pf+@|unUjtFlHL{851YQZMgcL;S0L`#=-I7^zlUG|%%0R@(+yc8E9 zmNv8~uedTe0&+z`R&7gBjRG<>8isuKvCzbk}& zoh2!H7t#f-mK#P|WvN%4&7Nz^`QXptaM2eN*5-Vjeseo)x^V!<+T?+h#r}ytYxGBT zt>I#lj6r8xcsNu`Nn7yl=-RcbG4y1EAZNV17{`y2)oeHk0nX?S3zRT-4Gjx<2G} zu>LioIY^`Q#p5mnM*c4Ha)aAt|EU^BdNd+#{FwI-C|s0}0YPsc{t4=ko^1wEVX+-J zw{6=8Vj?v9?90LS%#h;!56Mb3U60y37En)Dv7Q)MESz12z8CjRIpYFO;wJzr5*v3< zF@^FjvSM#y5@e5X8(Svy=KBJOr~nw!tR|ke^Ea`)UVF|hPVBye_FV6EhKj4F*mekIZ#G`YLVFuIp1>{b=DD8`3IE*`?PbusFVc{SW{Hk6-26 zX4U5(-e$2{iPVS@5FCO6IelAZe+nIfCz$+XD5x599FV{I353xiP?p#8F!)os)41{r z%pIoWQ@(HH(M4fDfJOIf8P-CU#I+vE?O@>J6u4;s=t0vR8(_bVfhz`6dk;EQO#&(C zX?`mhR;89`VX#$m5B&f*fG|H?94*a!s=xds2waAvJF};#M?4$E@6*v=3v06|eHJsn zp%J7Rc8@N7x|`yMx+tu-u17>$r9qeX7wh^New1b5$*9%H_*H5VhMYh-gP~<6r%(nQ zYisWtTle#ld#$Eac@73NeIqh zge^3ZJPWk<(%*&z0U3{|FOB`*p&nEHFC&Rr)s%6$&3`j9Ag~E9W{Xa~7Wk6I>*X|%lcS)mk2uL>r(k0y>okMp>3nJ18NP{rI00Saj zN|(|@cXvujjQ8-q-@W(yHv_Zx*=Nt0^{jaIv+7di#Eas-wum2*Q~qJ1Z%w`X*#$v| z1h}l&lmovZciN1X`c5&VrE z@HvELQu|ggNg!wtWNMm2!x9=t666;0u{`@jyH011u=>c6TLysAb##3 z4*-oE;hSmhd?C#~4aQ^x2vod?yz&`P(Gm2Ypw4cfYcsTUMeR z>=XRoUnlTSpFFq5Fg`_>CTao#H10b|LZBgG`&#e7XWXQ!LO;QDd>VeW;-$9rs~(x0`gBiEp^7e`E+~c>DJd;LA7*U zKjKd{!o5#0W+TGw5lmV;i{JlTn9Bn#G5a0Cc=yWowlp5fF3zoR}!y9OC8dbspc zF2Em9VL$5{9T9;&twEj^U_a~)y}yD@FXW_ZW1dNq^@Jb-LZ<9pUUWsMgAC61;y?mB z8LX(`Y9kJ)<2@1UONMb6njU+}rpHjnEfr}>9Wyj;ICh#SnhjNT0A>~g@2C@Kjho@T zxZf$d!3RfS(>mF3lh9oO55x>`VsKR0zov)L5RjJNNFnCgo(zC41YAnGe#Oz@87@c@ zrVW$`yiK!rVVMWPwx}Gn@l5B`dB>j0sOkvl5upJIbd|^Cf{L-MG`gd%mpW9xb32T? zw}YbMD#Hymu-Y9W#fKfiVJk4{pl-SXS@2O`wvg)Z(ga#U&9=U-+^F&gLv0YrDyL1} z&O~~ni+OMQdKxsT6&sa4GvcD0m`1)(rZlvOj5Kq8_R&4ep4bng-SR*PseUIy|MKT6 zsfWFhVF$M5tsuMpUwIt6+qH}?@T{@;YY>F-wFNt3%n{KsU6=a1@ofMNRbH+4bx&pS zC5?WXx6H03b6K5^mx9wrnn*qnXU$Dy?{eOc^bP|?x8Hl0WHayNHgxOWb}czdj;mV7 z4O148>Ja{q4aGFp1CpEQ-cm2Xj^8Iv`lW2>O!BWjuQ%`SuA4XbvuJe&iHCJROmF<1 z5el4;wc1VrD3U&;pZBe(Rq8$;gNpg7&Ev1-U)>e@BJ1Cqpk^H$A5EMu_UzDX5+QWO zcs_V9w9CnsEh)u>tbU?tEPXz${i%KU>jeRdzuZl=$rB&2MdRNc#`xtJf}iK;Ka!%^ zj<_}=mYHHH5F8A+Pc>hGXe**l?{U_0NsZ>_kJ7OG?A_895Z5$T-`tSwPHrBbbR#Hc z;#}}rY0n+5`0EeNTJxGHCTzCb)(NQhy%ze}9NfFXUVuU)kX^*`EzVG7|3ZpnYuKa* zG`F(n8EfyP>Z{<_dHFaro=&r(Pnyl~{L>}J6#iq^I#_&VKWKdOh(v37pIiG>~1a3Z(;6U0zkGuFJc6D_G3jr=?) zWwPsNtQLn7>rkPe6+CtPF2)Q&pILKWjTl3Z&iwkREPdUt$Np2k5? zdEhCZuMLM+ZbZc}D~ePFY6$LpuIX6zI5FUgd2?u^`L!BG#y#(#T}*cGrGZ8lT~PCi zt)tW`PV6&@zFqWhaTGOWaL|6qaa|I{z7>{o6MwALZExwHs1K zMGL7o$?MVq+uMuyMj+!?L2wGZaSdzvNMjXpl@FWs&0zTU%jY|`=Y8j^s zYq)k)Gd5jT7SjMkx>NR2i<-%WkqjcY*OGmKR4%=h&s0Aa;q7`1+(YoO^2irIV6+>h z+y*>*+K_nV4;LNJXBVJiuGBse&&POS0=0+uI^tFcD3O^*fL5udYkwGEr{oA7^CYvb}g>Stm!i%%9Yl!5_B2LLwHYNl(=vp55S}DAU8Ot-!QTsQIjnv2IsQ2useGowAAhO_8sS9yI~ysV)&Ohi>cR6&4z~cS+9flKbeYN zl~7V#mtQ$oP@(IZuhWMQ^HwRI{xP~M`va16ni51*>3SQFKqZgb(>hNu6)gAL^r@Bl zZ{kgfD{qOY6Ly&g==#3Ltv-yYn`p^8d~TLhE`Isc0FNo(M;T^ampjTCzOSzOS+nW` zr8H@`khonXp7`ByD2l#ST{L(ND8mQIaa;4^P6{!;c06)%FEbj@x*T@KMF|6yQ?bbxu^c(OZi~ z_>j+3S^xHhe{%1BQGC2|O22ba?LPlH!K+vMbomo{RKeU{4Q>o0_Hdl5+qzrNHhfum zOFn8pR3(XX(Nqzun^>a&2DjDrV;>Mqe!ke#$TaovG8z{{UZenT!RtILLlBn+RhvW_ zMPerGoo5)&Cl?#*UvqKvMS?*GGzRbQ17fObi$>>;ay1$N;$5{gol;Sr<5}0Ap_(3O zZVQUm=F}1s3GB6kKP&60zyv~V(wu-}p(cP5+6h!rjtnIanl?S=YcJ7iKce5+*n9QU z=Q^yaB>yh99VPQ*BU5B#iNegefPIeO6VrFDX_bcda*>9q@B*jmWcX?oJ2&;Pe=>E8 zKTF>;(a)p1WBPD(W@kAqwEJ^IUA{)xI_+y~(-GI#4poO}@GN@S{)kz87b7Mna<(|jQ@R!Y_`I`M?uSyNpZ3|PU+{pSpw#pRO|3YUz(|A5D^Jz9c zAF@96KRi(!6+EHzF#1+T^jvC-)r+!SfWj}csnw8;7I~bNPl|%2Vi{Yx9$$x|+2a_c zbY$Q=sbUw#zB++8B6nhd29BZr-yEQdCZ8i426`A**DH=gk~U%t*~zj)r#O5Ht4dUL zaa6=ELu;(6}eZU%}_&m8+>C)1mgFWXYAY@cIt_ zXoiq5U%^`2cg$KeIU>8u^;Rd!89I|y?`5|e;uc8`+vV|C-e+s*#A~F5U%*Ao-78z_ z-B|EB8D$k>tr|)1$Iz0%X=1|8e@q0UMd>bUoRBUpKwEa>$za^=kL(U7@=i9QQkTA9 zLjRU;=Bgg1??m~^uE}QZ13zR{64agcUgL~qKc8Cn@vw7i*7nxo|~E-f>|G5ikVqsu%}vPz8{?8V-s ztKX6mIlFThaXy??E_?NhIK=QrQS(*h=!btGVnNkv!rl_6KR7Ym**31y=tBLpVv!SJ zl0(8vI)ww}Nr_pN*dPN`!S#F^0VaB@nXl5c*@u5tgO9OvZh?ejy|BtEl5-)rbnU9( zb;P)UC;LS=ZvH@)0|Dwp-R!Ykibe`i!_l5GReMIJ1sa<$qdm4*Y{)0brqS_B{uhhV zM>;F!@B++ODtk)P3wqD%D3}LhOcR4$Ufly#dXw(`*?)3p z@*uG^1K{Bi$_dYmC}YY4k)pVA+JJ~Xojf_dx22zK{f;XgkLH;F-ZYd2vcqHHP}8;w zql^`rJd;_qxhTLKLby=~RJ#|wkg`5f`)Kph2vDa4g(p=TyS%kQvxtSg3^8%{FF@C( z0;+Cxx>r|TOX=r2zKixry!r5#S6;^7|L!&VdJG5{K8@-Vx)6LNs0pKi!BW(_^YB21 z!xA(IX+(|e%R_P|d)6>e0S4n|3z<%`TH!e#Fs_;H&&dKGZ&RPQAO0fKJV)0~K60<} zf1>ApC2VJa)4!oPxW?tB5uv*G-0|x~B5iHGQa&`UR;uT4f;n<+6&_vbULK zj4mb6ID}4CuzsvsxDI*&R)JL`QQC;Ab?iR4rd|T|A>Sv0kKps-3wiO17m@C zQ-SaPzw?H6DOUPTJznqY;mh~P0YvNUW1XQ0;APHHWk4PWtgLAX$6QJPBB5^%z?Wl_ zp=&Htwf{gbsDZ|kPJfxC0C#~rH~9P22t;&>n``#TS&}fmyp?jX6Wb>Bf5*%J{CLSD zB{?5I*g1le!oj7gk63Nbq(bhzNPP0)8BmKj|PaX3vl3;Zko9 z^quxfb=}itd-N{4%F*|l*J(QCmm5c4N(Dcu2&$m$otv)f(?wtjqCA(SZZ~&11m=8c z1yppuXB`%DY^>VU*ZepA=S9(CdJSE6<%8Ozqx^i_&_*ScY0Buau{e|S`^rt<@l00p z*fcjGTsu9nl)ioaxc-8+UeI+X-Eiq4QRDYtX?PsbcFxwhhk)Tr6CBjbx3b2U*ddwioJiq;$iIic0tsfK1oalSE4zeQN15heAo!Yq3v@z26kKB4=_^bz=%>u%*{pXr{RqiNAT5 zrLYj!yMS15=1ymX^*zf9O`)#AyF^oeI?$rX#)VEIjJR?ob@U`iqeO#mw6Z;M&rDC9NY(yq+DK@gxo#^oi63 zrc`nSnEzO71rBE&+Hnk4AcHbWCx)uEL1rbyN7DC{vx_>pvj7{Rous=up^2(adZ^=o zG8AH|KQ?7nL|K*E{o`4_*=#yQV1jqcTJ7jI4}p@N$@G*`DxxJAqtm#dW#jPll}tCk zd(l2*@}BcFZ&aPrqnut$YvQ>-z0Pv$UX{Qw-6EE4#56MnPEye+Day8QD5i5kjbrsO zbBf;U*WFQ+bj3S~9s2k+s{`H-*g;>QSw;-hajyQHdH!U(#-%;fL?peIZcM-Z@d4Bd zF@xlP&{S9H@-Lm2=&^l{i<0ED-f^aGHDnSn;Tygl>$CVifuM?D>+cksIYfUm`5^1P z?3=XN1(_r`w{O`MILcy>TK0v)KD(;B0OLDEXN43yFK}u#M>kw_&m>FtnebKr;prg1 zVtglQilmr6fU}Cqh+~0+l<65h>El*EMnb2xW>$ydnxA=`XOPby3~RcS96WTJgm4G_s+h&@*kl4d zDagAV>8x1!TlVyKY4TKseXnu-68u6L?Sz5|HA)0d##xbOYYkdhZZvr$Z>ZlfuN|O0 zk`E7BKIjBXg{}w^&0NyXKD(yBo-6rGXhclS`D1#L{syJwllbqr`5~z?$6pl?k|)H+ zn}F#VR;8J5rWd^Un1{3+W>?{~Xpy&ucts-P0luSS#PnqX`N--6qhN9BGUvPN8EsSq zrOCb1q8R+4d$Gc|N>j6zpl#zizn3`9aLMM9sE@@Ve0>S<4**0{2=Ln8aLI~AxLcN!(ASYDM?K2jE>_k!KqJaYI z6-&j!o0k3u4>v%;;h7$Qh(0q9f89=Di81y0w^%@myZbS}Lk?h_jA}K|MA?Z8^XGR# zp1-G$_^J+^Zc;{s_s?>F58e9|8f8ewG#w7C96Ac%mBvTGRN!Dbu=K<6G6w@>-xLO` z#^Wg9hM(?y5TtIx=FazNyO2^1jWP%DIK#LPTo2%M?c)Wx>wydYXQ)Msh{0IB2fv(m zYd6EC7Ai4VW%+a^O0YFJNWHCTlG{3(^L^@e+~!(%pSb?cJyXlf0~%2HuYF@qa-afm zi5x~ksvyE@_2PM#RIAw4p>$RlD_MCgxG1!k129^$8HjgfR!!k>3r&*PbY8YA*M_Zi zhIR8#y8HrIaReKRjavOn4n4jVe?V#0X?9PwRS@K)eM5@Es679}^#->7bVkBfz~dDp zi206>Xe>z?Aaw`ZgpeH|Ma~#^12r-nI_t%|w~XcUJOdlYLM04FpWR9omZm*R5+i3# z9RSN3P&AHVyU(i&57RjB0V1ONZD0?ngzt(%$vefndf$qLcSdCmlTCjoM;Xz8L{MsC z>#~*$VvCOW&X99tOW1@7#mCO7;yo*Z@UFYRHi;A8>U|w~tl4v+7@G2qGH_E<83xn0 zs&wdD*M1j*nF8l;?lygWFRfFJ4B{;6EWXCbSyW*TGxXOoEB6TeB^F#r#ACwV)sXGB^9u;o=N-iU5cUsCtb`whcHiDCxNfx zcIc0&rrAbbD;GK?H|tpX^gr+mCRXhl_cW-~>=`8ZMZE6n**LG3ubtUC6Uqk~hzaJE zMQ+Y-$$e<|ybkP-d09n=bxB>9{05WTDVt?JQ`5Bg48y!9P-m{GQr@>dhiq>#aJtf! zNwZ^F@^Dwhf=VcHu{EF+*?O()U4A93&eF)N zTFavSz?=wiYRVlekMkFdXOd5SZ^2!7A$J7tPG<`bcf3MghlzkF@;}?PxS;m1J6Z-q zM5J80IQn@k_y+{{(&^DJg1pghx7W8mn3Y;hqZghosG1C>&ma4zh3rRAUsl9qHE#x% zeG#bSc( z`M{fist^5H(@@(=`KR@pj^px`xz z{})tIMU6kZk^&0#(*M0n#sB>Vh^1vJL&sEh9y`geJ)Z{eGJ8EnVpQSu|NCSAcTDx; zHUWtGJ`wV`zPuo>NGlDQh#JvMlBjpV#u$CQ1#_kE}3wbdXt$R^^{UbvNIj)r}O;-{b!Q^ zfOy;^;Hv_5?0?>b-ZNzl{sVo1t^fouV2>cINUMy{>x;=+hJnO8dL3YOK+p$(Ows>- z1ADy1&|P*Q3Jp~UzF{%Ic7K6CPGJ<4ls^kpZ~yp=fjYzH_ni2#8l+XJ6a%8)?9B-hnPu&t zt!Lg0TiQXkWSLgN@ej-=ssxwtM|H_3aeCEL(x+9c00;|e6ZxhZ~l}8R$`Xj5; zaY;SsL#q%p_$8CY^C(}(jI}$MFIcr-%&JdH$%bTTIi?NZrluaA`T2AhE{45Agn7Y{J~5kXcomy@VOQ`HSIEE*4*z<3F}$3C1tmz)0^`>ZT6I&h z*#zv7eGyBO0A>9*e2Qp#T&7IdT3?FM%9Cb~h5^aets-4Vnrpl~$M<#(6>M+@a+7$X zGP=6V^A8f$)ljKSh77aZMB{CWGa$FCr7mwc#x^3kFY2m={w)2X0Lw6nk~J2_H4f(R zzAUpzgG%H{vPXx#G&1=W6#BGHt1d-p?R7QNO!e+EPD9JM8u_#^xnHtPCeza0Nmb~m z;8q@8bKWoG#->KU1UXjx9HKPF+nEB{^?0Xei-K6AQx!^myB{T$>`#$!+$g#(_wI&n zy`4!nxJz+UQ(Z1YoU0#i4%@N1pODz$GW(?Z&jq?ky||FQ$W` zKMD(NIXjW(Qzi0oSVfK@+d{Xg%4BuPLYv+gf2Y1-6cnM3>4*HTb`Z5$6s3Q45UbFQ zOO%B%5vh0BJx}S^;yD7n^jj`jNcZp!F~@zUKMLb^i~#>&lMoOXw0iB zp<@ykA11{c4f;2T?RrwWD1`e#l1!<-vv!?&@?=xR*}!*hgY(K?bpB+zuFXk*VrJq3 zr_#5SF3HH6X0tI-qCiSD<+v!Zrr1ChEw0UD8ur)omuF4X-`Q0Ht0^1Szi z5XzQAzDtn13M)G2NEA&ao<{zC;9T&AQ@HB?U<;tS<|+SSJL6=j;I-;b*7wCQZ9{xW+5!4pgu{InII zG|06=*1fd<%x|=1d)?@b*PmuE6cm{D5A^9mT+rtky~8`A2BQ4wW?3Kd+G4W~*w#mD z8r@jUJb~+x$MJSmk$QEi_}z3Mos(^#wArwe(kKh>Gowmdp#0T(h^x> zym-T9OZcIwE+4{s@GXHo$foWYZ;t>nA}=BUV~~U}X!=`%py+J#tL%|bUl4#gK`X4IP`rRjBaty%2?`@`;~TcYF1Do5~on`S)&7=Z^~Ds48Jq8f9e2q91bZEj2> zSF?!l#Jpf=Z4IR}H2JcDC?(fc@?Z9QAvK)16FcNRZy;EzC5eB{kon@Nl3)~mE!l4f z)3anH_*l^sJT;zk_tE^m8il@uvxzUq7)(hvzZsu?T1<2QZZn#NZ#V+BY-0f*>LU4qOr44Y8U2T0!2jy9K5MHl*%FRS|a z@c()VZ_Z5cbRw123o(C>f{L0HQ1RLp=TB0xu6!DXWbjkzKdy|=Eqp7F(Y_CFZ&2#e z!wv8U=Clhn|I6kfYTc~CJX95+ygpZK2lvR z)C8Dj0~K5ohdL7y_bZ7|SH+@VPtc;tAAA!c8q&xJ zIm+~CL1fO3jTBo3e~RwJHpWB6rgR{M*=70Kjg-Yq*g3PNk@-Ae1v0a7#2TU+p*e{* zNl#Nv^NGn>?=!%qpgMHfX*df`YH0Oeon|zZ=cOPakUcTggptL*;!t8tl2?^yfaVTz z5RFRm8-x$rF@G*i!K|p^FIZqvI)vcx2NgE@c6s-SR%vK`_lMf!T$0VZsrd}+w=~4A z1suqKsY<|)otzSAtaTGaw{nxYhVZ3DliC6NIz{8wfKmHyDr zDrwCAL7KqE*w|Bh`xJ9-{xGq6NtYt6v6@SPB<|r~_eO)TUJ$I}DfN@y`V?pDD8RldOrCI=Dc zUpKSdj8NogsJ^9akS@f$=C#=j<@l(sw!Xpniu>aSxH@jZ;7q;!&XZgmJGG33SnnmM zyI|Xp`u!wVQBW}pPfHt#etPHVvb$8;ayd(t>{wKBFYA}z?y<@hd)C;OiyY#ynEyFhiJ_$| z|BB480-aXgJA~7`jv7zdUH&&VMdArQo|n&L)16zm)~V{;qV+Bu=%fvEDE1=N)}CZi z@ewAi1J$KfuMN{cTH1UQSu=>XW{Glw?Art7ei8_vH}dx5*8F(IOq>$Z1e|o@Ru(5M z^6Ky9a&WqpyH%(W$}?0t%TLRQ?}&^2D6o)D$%Zjip5mN7v3Pm%1cFuOZ%69)`>Okw zTfyF~f%?u9vDnii(tR=c^~H`e7sl=QkKF{JfyYPhbRbN!M_gCFw0`s%e=2t{nu|FU zA-P3#7fVwg9brBDbnNL$quv(sjyT1(6oMaN77b4|r+k83=+*O(SJFvx%}jZv-{`gr zrUWY_S%y?w=cXw%Z2*M}46nBs8$1+CH!b&;^PHF($In^+f#}@yk$N7HNz~~-o;OU_ zXa6L00&bIMvGHT#?dL-bSfvJuf4C3KI%1ixVcgq}rsndBEW-^t(&@>6I~7^Hm=GSy zalt<6AtzdF|1uc%{i)IG2tOY|rz3D}G;`;d1d_?cX{%QL3`uqCx6pP3jy4e3m+vp) z<1r2p`cNKne)8;hGh6WF-+R+}QMo6@a=EO!pzWO=umEx0g}AR z*f5WhN|dyMy%W9l2S;=fR5397^ZPH}ZsyjqVTfZ-Qr$oE8m_%I@zLTNi6eO}J_iam zZFs;k`+ohEU`B@IC!X=M3$ijWuqq9vnR@ zuLH`rzB6VWx<&qY=CsTj&%!`LH`$6UJCmZGAJfn?Y?dfOp zAQqA~Y4SQrmPV^gR}V!`0R(dA03vh!;3%tMt-<}}SCihNZ-++aY*WB#@BQU;_WF&t zkAFPh|GqO|$TijCVmACYYjZ0Nnzm(~;ap2H!;+1_5BLWMHC)f@0EKbgc`f2eDt)A7-H>+EYsS4QG8hyt+bO;JhrnZ=B+FXa>bLa*p zXLRd+1D|X>wy7oJ7N1OUTV|vCn&V^Bp71qJFSNdN8F!pmT7+eXiJLi?BZ*VdCCCjKsox> z;MPwS$IOp+eff;6pU0N@5jtvNeq{M=c^7WirHB1P=6{|cv~gnkwK)=iZbYw<7Y|?l zs`l;k&Q69*v`1-kohWY;7{7}VRUPyOaA`4iY}$3J$pkW}(yB`Fv}O+|;-I!W9Y2$z zMWgw`yfaIrN99l)D-}Q!i}x!zZc2yaN?=6-TU3iVU+^EOEmTaFk*=g70NMBXx1zYl zmi$+~zN^ck-%|BLpGp@Y^W}4|w-hE!9CqmDs>bf60)CEf)VD?JT-$_XejR65*uiKU zZ>d~y$jU7#l1y&2I&GGX^$wx?k>=+rcV!(b!0)NGSXS$7F*M82aQSKUh>KxpPlLUg z>Frw6&RMS>-Ln?Pou;^8QFuJ7Y&3;k1A@tsYxAv~JsRDsP?dM{PvH1FoYo#cbz)df z(xN>stEDHsU962eYipDGa{{W*OSc1&q$@apAR@#4f~nlcU^>k7-Q(998Ww@>!4SkM zB2o@cpFX}3@!pzlYI_|V#F-a`t6D^@2n#Q|7mrw$Z<=DclPi~fsoaHnlBcm}mQx@! zv4k=L=v^XEHXQHw@CH*C=D%|E={b#5RY$V`$iA6ek7`J&wk{@Z z{@F+M21bM|oriH|QcH=Q<%G~q+M4+3|MX!H1a}`pb{Yb>Ssd-Wm=bz3vtg_-Xlr{j z!ZmOG*goAr)Xq9pEpe;l?l~6^>6MTCFRGY<*ya%psDARV&BnJ~#W<_SpoHk;#pl1M z3ce2%p(L~}_GACJ%LM#)DFk@dTiAE-g z<^%~OOA9AG&O<6Bi7B;JSffM#<7AcibMR|Uhw-3VR%1!Z{HK-r1H?=nw4=uP^+saB zK!q$l;Fd^liB6~+rgO}xYM5YiMb7F_j2{R1wS)oaEjQ5mv$U-FWj@(Txu#g_jxT{! z8)d|NuWUsu#}IYel=7rhR@f?lK+zoFPrM{l_TZBzCifH9#V;O1yLHVMDh*5@OE5eS zV!ITC!kq}^pE!yIg?@b<;zw&2dP47}lCPN#CYYt=p6h-)1fGDJ0|_w;`W@3z9aVUr zSV~H)6?u(Mu9)%{)7Pyr6t=V>^|gvB>Sp-dzt{d~#Lo*YmNW`-(I~eBS)lsZ&?3_! zI*Q0FWN2k*IWefIS-oDfzb_hZja9bf_IuHt5M5S5<{TMmV3liX8H2H0Y}GCF50rM} zF<(+XgBd3rt=av<(V}VDx0$*X5YLS@RuLOROI8~js47i@G@q8FmfqybaaC}^cUL>c zZN4GTbK)L2BZ}`Jb7H@66KRT$zta%iO!cV~Z+OiqcHQ(TO^t4V0M)^A@*6*=qI^Q> zDoG$lI;`N7uRSA(5s0}I2fSyOZnksw>6!soDf*|UyU2^5AG?u ze=5>VQ%S~Sm793_bpS|>$W)cTGO0tOO3#Nltn6mJ_rne>hoR}av(%eww9kXr&Ab|y ziP@0-?_9H#Trws!S09y}1lfhlQJHM&z0c%}nUwP9JESn^?cH{a;!BNXe>r)O?8X9Q z8-XOoFf%CSW-W<4&(gsQ0UubwUR-wZ85$AL7=R%Z{v6=KDbX=To+Z*xSMDxTA_U{P zITs)?J)Sh4zeVp+;DR>+Fjw4jlbVagf1rDH7mhPIIPL*0fokl!sA7zZi8XpB$R2P6 zE9R?`En!PokHVKViCZ|0?%+E?$Gx{$ZFPtjDO=AS$U2jyt&@RrG~)I;V&@0KSY3?m zYeV0Y@8AD{n9FWQEmsD%pLJzHe9q*<0DevAO?jFGQ3>!IBzLRR1AkcuG&S!z;kp;+ z1gk6e>Y^cZ2b_}t2=@c(S09XOg!If&cHbxR_X*Ko4*@D`J}x12yA-4M%)pPE0LfiS zhkHgyqw4k-(9<9RGypLDViJuCP=( z|3C>~t-sjD2?LG5VtxyAR>J5nPk{b>+Vs(Kp}#G`C&0Y6dL^e)-y1#K^XJyzH)s-j zVgMRGdu#dRieZi8xZZygfh~D+(q!bzLXR7M0Ph1IeE9Bc9gDCSCoS|nmdHYysGuupo?v@Be(0qua|}mlG3c- zX!QQpArS86odX_}nX+jI*3+(WUI&ST-p$x-8CM6H!$^{^4+Sgi2dQw%uirBsm~nBMsE z6JGt%nso;jdsPVm)?6Q%4T~nevTI2rm$QrWj7u99#YvrKDAk~4zP{T_wLnsr;gQth zVeTT>qMF7si@xO{kZKYm*~xnCj_93qKG*CQufk4;lP|_v$}vw>kfJyv#9(?7lsB)uNUdQ+I&*`^p?vl z6c(||FKBoxoy36?8dUr7q>ZAiF{!hgBpv;~AGU74bRtPbt5Uj^zfbCrkCi!FG;bwt z7@#}!nmYC|sZ?&Yk|&L;>f4Zh&g`Y!4kJ%aGjbmS(r@W;V|<@)ZQN4n2ZF`*O~(e& zqG&8)cO6rDX$~6XaU~B#J0;^S_247^-o-50S^S2%!jB>mgmI`9?4Sx$@ha9i3Ja2gbypCn0tnsE9lSINCne zFTTpc;(gWbphZa9ZsSDn+JnGe`ft4Z?gtJ%uzRRGfUP5rY+rNcWZz5@chsKnFyh+8 zfjAyW^`KVN&BKsyhwTK3Kbn^gi~_2L_UAd9+L{#;i$yhzBQbxFq!`pO*8yk`2KrP&bg#LAzh3QPZkwc8WV8@9V z=o>Sy*~ozctljb?(1-I}yG%6c+@?0_!d=$j7j|DG zU_?xCrEED`?^As`Bye{-lnDO;zH&PA@MZAv|8lI81aM<_vlt+O$UN>tA6N_;V^1}& zt<;?^(8gHxHI3FG9nCj0PQ`|AM$;REXl|&ko;??Xm++|_R`o!Ow60Io2)kSoj<1;dOlBVO&bAY@80Va{R3I~ z19VIc-31y?5^^zTiRxW>Pi=N1BcZTTOz^596PkNKV#e1CBd&}>UkRINew&CpDv_@ zF79!)H1Tm9GgXJKRY*NQy@Cb71hOFVct6ITykZ2ro-T*!yM&=W@I8Yu3jMk0YzPOi zefEz8U{wI&3P&~WGk_`z3?uTL!kdtBmzzl7(5E&y@?MVj(R(m?PqTYzh z%m4Ck7!Drd`3HKYW{&A_j6O;}FFZj5-0CGT{W7a2e*gvjN#g|>wZB1+{CBtKg9m>A zq##iNzyuGtAit`lgr0NgBb?YjV(y#Ve;`=_);+iUhpeO<)gBBu0t1N-K(H{92+!S< zn+qT!)B?*HAKoUHJ6Kg^(fqYeYAcCZ2fo+C=$Q9BUuKlQ7W$2WjM5~)zIpGR_e4@Q z|Fo0<$3HGE_$wcH1-$l%LoW$Hb9~3<#3q2ZVH$eJF*Es&{b@snpX~!2_iV9@5-Yx# zCK9pTys-)o9#L+P+5zygqQ&67poz)sW=q1diF=5*EF$Ffrym=W-%8hd%r0j?OcNl7 zip`@{-hdlY0l51Iy5mUL=@Q#(Nj|dsXf--OkrVz`J07)0YD~;irU{N}Q)BcT#l%QW;Qx!w z!@XuZi>NvEra~{{E@`>b=_@Wgze2kd85{(Z+@;tNb-gK?)~WBH(n-W1x-U}o=pU_F zvWq@vnF}cw|7sT9Lj;T9+~~E&OS;|DT_^YdSfAk&+X2M87Qti~f5_PHW~?FV_@3*x zF0a>)tAzeec=jrQ3A&2#h839@mi<0b2jT)T;jVD655Uk96a`K*~;pufbo~^5JOri*{N`!yh8;2#82W_~pl31??C4X`4hG zF&{8s)iO1cM;8koc;8)6EBxHNbQC_4IwhCsYK0Y8V0*yVl;yT7^oA3-veYIujGsDL zy9@Arps>Ka5WvPTM%T$#i|?}*Cn$CLox&P5B$gDK>kW_>X=2zN_%7n8v}^H_ohjl{64yX{(d>vkf$AlcZz%Ec{C*IR0TPv@Cf|_LLf179cV2{|bmd+HRZpT?Askx(cxc3}#trWYc{4F9DRow5pd1`(JjwW@ zajMFQnnU`}muMQIG;K-o8JS}L(4M_A6LseMYETk?h01+cz&^*{y2Wh9X~tctG`3C( z$$iWL4osLZiV->R^u=6YUBthY=WU!Twz5jX$Go_mmea3&qash5Ft^H)5}Fp&`QkHb ztlt+>>n(a2H3C9)5sY>=DycFg6=O;ies)R@%F^HCB=wB^rP7)7ukM+C8_>9P4PkR!YUBMTk7t7BX+R>3#r zcG+u^fwx1{F<&T_WS=ZV%bZ+8r2SEQo`(Oi0Aj~{0K}?hjG30mjs)P`^V_12L1~>! z9JL#&2>3(~u0NwT zS|llA(Qx*4)8FhtFJsbtX17DXU5wsRxP&qTjsgt)zur{Xyc3<0_J}qn%M)p}L3=w2ogz_aoKKlm*mqOAu7u|dXxP4Ild5dz5<)KAA znF4AdXJ5>z!-fVfc&bbg2ftSrH&?ET_afXts3Y`zSNbQ_^PSKR#AB4pKHwV6g(j_! z%KpA5V`n`sY|y-m!{$SVu-k}iICCPhmVf*Mvd4qXcL3<8N)UYAYNi#L?d^d2U69?K z^+v9Qd`epNWpCj|AV~uPm<^&l^V)X~TLYXcGnp}^VguX`+zp}Unlwmk;6f#9h+ly* zDVmW$CIjOiP@lR~4>haHg?_Ie@VHdvr*s=KY2T3Lf~Dy1)eo0-Nw`n37jGRjNNSeD zSLiKOUl~W@!)LZHX~K(N^`%F(wb+&&oa@nzuaBlUv>$pR-azwWmyXp&eS78B>vNwr84j8^14 zMDS`T>#;E=aAUaVzJ1-k=~^t@^;IijvM{eeUS7Dtt&d8I+{Q)Fdtfn!`)nDLlf_c9xB`@JhxWs3UE=;ACxuw-9J{Muk%;)NP7O6!OKi_V_-@!rE4epZ*>3(5g8fEdlq0jDF%$;}ZDp))U zdvc)Ef*QPnZz*y{ZM*y~D`NSQ-QWJH!?V4coy^?if&u&vbf47`;#EGS9q+{im-iT^ zm!W^{&d-pgfTh82razrwKWz4ku$s_ps{kumL?GR4w9&+qm_#=)?DW8C=v4l|cT~>7 zj%Q|=h_g0Y5xuy4SQ-(mOvsk=rJSFT`A%wnt~P{U&WwLXWqFI7S%vryDZTF;edxWK zDsQrAM1BuB=( z(sy&omk1wvS$mxitb&bXkKpT}b6BA`v-B7sG*x95Pc@Z=y-X>N+=%xhfpJL&?vNWGTOxaMT+hvi0EBoCmz{HRK)d z<8{ZD6p~Kh|J~MJq0+QuB?g-FaiZ&CJAECez$Va~N;n6wGyk7GEip^eU&(yL(@VLx z4oW1>#R7?k4~fF2YDlTox>|Oul|N5r9CGj`pHGU#dhm99)fD-;@ek;Q(W;D-aFvxy z!bQdHRCAN272nAezq{#(q73&U;CKd0=?QvJC##(sJUUFJrJ8b+9r;q1MK^5}d32D-2;>9=<5)vt)T zKXcv2CL3+=uPbBr%P{gqepNap9LhfrBrt+2+T<%^jbijdQ$pQ{+G;acrld1Yn(t}O zDqs^r5_z{NGIF;Jcj1d?(resy%Y?U%kUeZsG18J+U(G%78P#2kBuuZkgx>FetuYRU znIbC&#i(<3E5Z!w`aH$e8(OF6)2Cpcu(!>POHOc(Ao(vHPDM#tXQ;GQeG5g_3e>yP z9W{v1I2)+~%FQ;hT5PGYXH7Bi;=)ttAHtj-(P*Mvb%_4t$^7)pR~|gj2sj~l@_m6I zjr&$)y2v(cSSlGO*>$-Wk9pf^9&Rf4Ygq&x>l^-L!uYO&TeCvSLaWxNH2x1CSzF>c zTgb=;HuUWte^$@1vC1(0jxAL3p{}d>(exGL`SOUfe!5NCxMrd8R7hDl$RI}5=84Uc z%>ro-f$^=5P5z-FMf{p_G*e@3>aUBSswSFpNV5nLVh{Q7g`oWYtRpm86(H|fiC@8a z!x2uIv=UE&5&19=Oqq65N+J8U28v?A{Q(q4i11t2XuCY{^#t&YNuux(la!sf# z)dRtT0E68?%>8<82O@&f*tQaQZUV%~Ja1XL2TsMZAD|9rMFZ=ncrjOwaj4^I*qKIF z7LhS*o0;VCmgw~M%Ssb!<}>&(7I>9F)4-#y*Hg4@JwO%J1B=4$_M;d_Lc3w>ut(?^ zHPIH$A`p@KNdOOdJ9wKR`{pk!iUdQ(hk0Y&xqdPxzX)kFx&b2~9AN?4sFiN#jF5C# z%?Hv_wcj*pCh`A~a&$T(*Gp}KTqL9GnV#*$p zn0@!O;_*S(#Zy(JNE!C90qaicTsB}=iriMB1z#=49ICxd`W2JBtM(7bF1+0QR`sRV z3_f_p2vHzHSg(>aBb$Bm3i;01)xpGmkMUsLmx-?0ElQ-DMKiO4?HTi(vONCQ{vgkn zTiun|pi-IBI%Sybuo1q5!zPQ4=3P0u#UIiDf6xGWl7E)9s;}hgP{UW1oy<%*;$ywLL)0FRVz(~F_w~(nixc`G=F1Fyb4)@6ywTXjgWycJ8^K{c zTjn0ojqEJ{4Shd6A{1i@+8{)^Fx%<+wQ>xEMYKrR6f9&E%Lb^N=RS9%c~M*6Bxj&F zb3vCXGmiOqJHCqx%#4-B*Qe_14RBq$;bFN?Ce21uez9XoW|rVq3;F62O>|&sJqmJJ z<(ghR=w>ONNe+%(hq=z<#17GezKzIiVelM=W!1j_<=dxm|Bg8LZ;4x(XGhXGSJ2AaXChUgyd4H&PqnAysBWTjFTWD{I(HgCN`;VtU49J z!J=MfywaCPq`DapLYkk)4XO=|+>8LptE!c7iat${f-*~>6RG02F^lCm+Hn5pBZZFx zCbJ5V|B?FF{QjGfkH6A|V+i2bDh%XCtfn`_gWLo|9)Hu^nHSy0v_Y)1a9e7g7aJ{=wwiG)ZBvad zF;+Vug*Tr){9$9Pvx*xxIE>ko-LEd2E8?NAjUL-hHj7t+n!x7}(M>ad{(;upHoNX4C(-h6y2hIFJCLX8QLQa{qo9(O1*aNWnwHu7a=K ze&Ol(7ZA?=1Bd^+{XM6KPeEMj9XZ5N`ao?$lLwlOq$A(^7e;P7wp4}??WZb}d+kpI z@N(g+Y)q)@_TWwE|5Ls>JO_XJ(5yi-0>CfS^<74-VU7$Te}PlX~5F+#K&#KR}47yw9Ti`UK zitfkE^}ec+$m{S>l#;2}2&cXZW>>uQI}V((Bh%{W6i;vfd%q4;CyQMlamUvAAjRV; zZ%D~#lzzAMC`+`|xE^$x`$ER+U<7&x?y8awvV$XXU(~6}1U2Ip2wwI3)&BIVu&TKg z%j+dBuX}1G^6gW_?Ob0&&+(@b)TTN1?4~9-(-J#e$J1M5CR1}>snK_Z!sOZAW%;z+ zt$4}uM#ZTeTY%zk{y;D_fzx*R_5%llW+?Yl5)G1}~}v0BJYP*wKz#Ng)yF zlB8cX%~@ggGf!`n?@u5&JEZlL0r21n>@XhSMR;{JEA@D%3!3@QiZ%__N7C3Z$9sZ% zly2bjBGZ+qI&l=?8=yj}gbc0?>Nadn1*|8FD2Y^{5RjG>>9_;(3`h-WA)1Z8fqRav zqSGa$Z5WcS7vJqI{VE3-&gW^t8C1fw9)z@RBnQl~rwht=3pho`BUI^DqLoje3&_p_ zoj9}Xw-ROp0&!pj8sMjWkLJM|C`tzR`?FVsx?+JpIK=?L*wsF4gM6X}1qYw*Si-vL zo^B}{f){B1b?lD#P?H!aG$0(#d2Vzo>FW0>(wCu#0N=(qs96!bUs9HRE3ps>vmto6 ze$IrXD-*DV0O*tK&!g8PAopqW?Rdo^DNHwAm`Ul|8F$a2^V*g+7!lsYkD4}mxU4PR zP$*)2l(~+Q0J(xq094FQ`}hyY2peg$JN5^>(^?83Kq<)6LOXJe=3!fPbi>?f?B|<% ze`^faKa122s#~ZQP00dCQP;EO0_4Wb`g?_VC6iGVkylZPC9|Zy#1iH`8{gn=OI{L( z`VwSZe0-hsMM_Xmvnb@U`hrS>h}nW(aBvwKG&46A_}!|+K<_mx@xsNVk|>k|+4aa0 zUO$JL-_oepV5VF(camOy;xq_O9oRC++%T6jkR%Lx7G{DPeo@{LfD02ab{1HEX2SJ{ zFsvpC-UaS^I^1{neE3$=!mZ;)?H2c^`^*L{rMEE;qNkDBw=V$j#V8jc)3jFAcqsoF zwq=lL;bs;_NFlr3Io&5&yP@}E%N{;;u&B-O5YINPUn_zu;`q@Z<{kCtk|CO@=0z2i z_f82dY&>tN2#GWEUn_sJ%OmU;1g5@qe@uuZJ;@zuHkg)l>}I6BchWFV4qj;}>4GeV z&s@DWiNpJnFZWk4yT6$I*$;Jz8JB^nJR6yH*9rmW))-ahx8?#e&W`Wd3JU^P^-8`d z_m3S)8?~HgiI9^A5HXk-aH`N-F(%%XmIf{}X0U+RH0tPYS?@aFvcgbkKh| z!c^;S1zs~0Zk};r9DvZLdy&hKt$hDT2?(p$*#Vy3TR6>~^Zyq8p?G&&i`2W@i_*9KYrYd^bh;N6m3jh%R4Th9}SmghJCC!$+BokGi z`Kq;p_qzu?iz2g_4=^&3tgCt8l1#uQog5wj|IM8m2T_~;wfZ1E*yODQ%gcEDHBD4@ z=9ly;m9}wEGBfLrb%CVJizEw^zO&8H#nzylwh8FMLcatzE-6FLM>? zR>9I%**tB(Q`Z`>k@acu?-nNcP@ekl-h|ZEep8 z?|bv%h7^YUA_pia>ExM(iNV0bN{FN}!>-f^+d<{hI!P={JQYXwzaosYNKU6+n+EyV zgl1`q#DoK3-~0L2zlMxcZYyti`0O#wk=0Tk0_5%fdR6>L)yQPmXr8q1>uaG34xn>) zLWv|!V;p!|JmIW8J6824P=&-H8osf*u~I)h-d-Ui6>LAxI`HjtJsTsn;{O?7W_*=r z&-}A1M_3wvps5^V^D!|+gdoCv@90K$;IEj`u7t-O@wn&ijNvVl2H?fwi5TCPJb!#2 zOT&#qt(tvcQ~z}?)j{N2elHeNH{9@eFjZF#`D4{Urg?7A?7B35S*D&yw+XMWM>j3+ z*-aP!2ZWygg7z@scG_>EJv644-~>=9P79!oQg_7OQUu}q`)Ob=Qat3wj_g$uRX7Tl zZmfoHteADr-MB3E-&pJNi#ZcuM~eh&=>QLSb{K4L4*YO5pN{039)stvNluqh%m31- z4;|YWr)vLOzS8<`bY4U0;T+tb+4(;VS%FWZPyph{Y!E!}SPhW+H?*jc3a*-07yAeF zRUM`aL(;W6{pyDue*>N}QC$FdK6VeFwEe)gFx2~eqbHtr{L=WoeiH+C>EqO|?Eau; zzN3%?XC+FZ1do_ns7Hdc0!ILQx>+_(vJ`zIdjV^L9gGxc{ccY4Urb{K{O!F!rVRKL z=tGI3MKlKiA;1@~bRP#dY~vLIcmq<*0R#df4A=%S;=t^Y`py2uEX}Rt5Y0IuIMR4p zuLmm(89aaX?cb2(%dJt*wi6DG%r}%|>M9}Pg4)a{``*jx5duaL8r_E%J>Ju7N&9ec z0vC}6>SqhUO|fBJA!5R|z6QtnqJR$tsi7MtHU(g>#)r}qHh|@t(1#7%Kn0A6aS!14 z25AiCfh}wuJ-CYst)^0yxLo_*{>N_iHH-Y2V9WzVe*pn+p>`waeLqvwoqRiR9h`a` zY=p@9;7|uIG3c;Kpt)MCzLKLLg;Se&JLCL)?Gx{f?+Xz|QrY*=t0pNugrkTP+h4yH zcq}_C=IK>Qpf3RtMoTIAsG;ixi~H1n)iZZWt94!>K zzAM*LQ=Jz(+UP9Rk>zEM^HG^YU7MNd#znZxdw7$;{5qzGhU(}9UiyWvBw}@S*zu99 zUH_V@bjp#Gn4UILEA8-;v$m~jXJ;_>J3v5Wlid!#jHmqfDTi1H84rdaubLdCs{97M zq`PpU`5Y>HgJLPL!ubnfR?hialCvbf9+hf(^q$Z!9e|4~!5_<2S1b6W{Os+j-Nq&T zE_lPhFyrUKz8S|rv*9_I2}soHGR&*L)6=1x?sW~zhw|uzZ{;JX50hDgXD?2B@_-J!>8KIwDVDB5I1$Dm{lUkw^=?9x!Y$qVgaiFp) z(y?`{)vL^UvTvqyT7SwAnTVZ39lS*oR%gcKZbxix;;E*XpfF`I;}9e~+l4Pq`Gcmp zL)FjhR(u zsNGK{_DZw)rhDAb6ICI0)yWF(el;OQI-fh|t({nCkOq(wZ%%s?$ds(br!K*eaBL)Y z$kCa6okdeGA=s|Dbt}4CSG$I{upo;0DVCmi5zqx1ILrUIx8l;RTM@Pys<$AO^zPxW zGjT_=?;(DBdHdwi6~$9lwhbNQIQQy0pVQ6LCu_G_Dz0&O$!r6IjesN+x;GEVM9fhO zcaP<8U-RByY>+1nm^E-A?Aif3Jf}XY45ks&H4pMKZze{7<`A&(9YlL+isdJ@7mOOm ze>^T2QA!Y+9}4!|az8Lc*IAD~zXd5o&gf6K5k@^kmqW9+=A5Wx#+C zwc}OAo9|n1i;Y%oK89ZE0G%sI?OZ^42|teWexw#{(lbb`+SgJpB#T$tHNc92K6$NL~(YJ^Q*b!$d|pyxOv3*mKOXHhi+!>UNyeD-wanR zhk?3iUzeYW0_{R0Caf;=OL6T~1tWGI1D@7JKTC1-t-@wTrO+U4JvPc)7979Z9yCz7 zwU|PjO3evDd_JqsXtTw++m?6=n*s8?erxMvVXyISc(pLy@ID9Kx!lj^O-(xTEzy8% z7A+;R{)(+9F~p1H&-QFs96Qn8?>5`M!$=44#z4BOF%jjub}OMJw8963AN|cxz8rij z6rqI>MY2OV(46OHn1a`FvJKPyix6feOOhJ-9OEKNirqtBvA6?Pll2jh-rVWXolMZ4 zelwm{tXo1AnOnVgHXcUHAObW(w7iPD3y1(w^py2HSx1o-65tu{jXTWM6x?R#F1YFm za41^((s4PNHohN`tVD76^1Mchq*{{me%D`M?N)M-_OV=6647e!Y|p@SsQ>&lye=&% z^+2rz&>gj_xzl1VIpCf5BH>MW8QmDK>9A`p>W$ef92NVB$_Jvm@&qiDWyX{5MMmJ0 zI+c%5DXxa|iYNRwQZN?-bBW{H+aF<~hvz?D5CDvivJOwb3Q`@7e05*>Chs+Eay4#C-?NWOcI+ zms{P2{f307iEY2!T0pbxJDkd{5W_d&h#q`Cdhz3t;JlDNx1qsTtGj{RJW^zuJQ2@p zi7ty^y}Nal!P+AJQ)DjUZ_%x|OHAhpO$gMt{!qaysdLG>iRrPfyXxK-fMfJ>@jhLd znz{1A$QMsZ-eG@^3ZO+&Jinc*EgGhOKd~DgCCi*MHSe_d{r?J}Py&)>qad;zRTWYE zC&_7Y=^&?3qD3qaQDJiIh3GSdB2_}sr?OaY*|~9K-I?30bF74~(}1*mDatk5CIbcS z*i)I*FLGjEWCW~o#ogRm*irh4R%>(GR&@hKzR%Sq#xl@xT`>A<^&1_j%7tLox3;0u z#odxuQq(C$$ofx6bEn+~ckXPH@-4S{I@NI{QK~w<6;sxG9m&K7~v8S^m7fhA<&_?D71`C ze**FJmTQ{l@r2WR;3)1Jf!zT6?>%4OnTukjmw26g7)dK3v7OcFeaY}Z0JRF{)mQKy^V6&-T^wpfITp694ca1%7QDhnSA=tD+RD4t2RPFC~rf(AUc6TU7eYu~9BeiQuL@=72xhCW& zBYg4KI|kE1XDV9`uh0Njv}OF^Bo1k|$^V2#w-tOnRk`1(jIFhisiogOcg)&R?+`J{ z^+q%E+u?rtO)8QX@0}_WPSY5=2lB8JiS^aK)uccoP%4XZ3!w47*P0rjui8zeJiN93 z7;m4C4B_xJ1l(QLWnk7rU)400@(j^QOXvuES?>^Y*hpVFz=6>cmwbl-bi)NhP+8_k z1&&*N*m!Tp&8#ax$BH&W^X#JU-#tMTVe$ad7rYM1?_+z1kwN`h4Iq9@@M8?v_<{}o zn%pb|C=2mlY*a<%Zk*jtD~04SG1`DnfBmfj&Ynq4DmLX#1nd5U{lpzC`?t6cWL)T9 z{3+b%K!L^6lLLqg_E1=QsRh6(rZ-#N)mqW6)c2KkB5n$EOD~Ul3a_b6~WAJZyRO{F(Z@ouDoNUtF1mUEjClZGqQK4AF zY5{Lz<}zKg$RvMUl`-gP-(xW9UvL<(ugWO>#&w zZ{}goWwA6~45%dr%%!EjL%Xz!B#ebd*b$+1ANY~98i=6=2+}Zq6fQq+?}zWNK6ht% ziww|ewV6NTSx~($)4*BXJtbrmvnX2JKf80U3^p>%e^k<~QOK>AVI}--chE=FW>c&D zMkXg+erk^qP$*B!4HA7S@otn!7UY;uWu3>3qw7ets0-RfO@89s?bwrAWTJWt_@{X} zTFk59V<7J~4g`4Zr5>U+-X-KG2OiPC*LLGB<|n1vEcXTU7wgWK`Z^CzpmaBk6_E5F zA4&>s{^*hNjeF^}kQ+)vS}5S2p{MGNZ!A2I6Luor+M~~jr2|g=0c|&3oHd_Y{;5|tx4wQ#t!)b!vNQS4?pEw2)jE1q?u-=WJD>b zX)1wzpN{gpi7mFN6_*p z&Ar_q-fw6Ck_82*^t7AR>s4AtS+(_FGguij`3pbo#Q5vWLMErC4aWmN+jrKsk-UCj zbrE^%b2Wgd*mP9d&_LR4PzkC6J~!e{H~DySB#$BcgmBpmW3lzBMBJRd_^WI1 zSXY=j=hzg6W<+X|l|y(Kpi6GmGfuF7!{SC9m^P7FFk}oycT#i87GANrahH3huQ&W6 z&7tB2p-T4U`Dh~v}HI-9Q*^z@ji+x@Qr z1{vg;DA9T&>-nHmRVnpVidv6TZHT?roibKE@hdh7g)TCpU?)*>zgK5O?c{UBf5sOI z-`JCsW8e5+5uZ8=9Xk;B;??xL50m;HD|TwcBSXDmSb~V@3+6}69{#{<%XoEL4O6+D zz%K0boz&;bcGC2l5w`7;u+O0>9`)SoV>Qx3oJQDXD6}N6u0oWT(C*}(7%PgT<`C$U z=$tB~%~>-^mNDJf8wR?TvbcmoExOcS&FNJuOo+0(m&?ALjv!7NCoZEsrUMEpf zgPZFbVzwbJ=K-C|?&%k4a0|U5Q|TYa&Uv^>(94c6HHA$F3c~|l>*D?wy^?%X!jM0# zu0Yc9x(5?-@EN3_pP!DgbLfB%(K4n0>L_9dl~q7?5W8obSSi$i(Ht8EebF&8KLteJ zAe9JzA#{RZ5yk|pzI+|jje(mtRKx%A0rzi-Bc~|kAR>1U zYzBiClKebMJ6=+p(PRGOvEYzSDMFX7ig3wr=&!EJaxLTvn+oXJ3 zC^{*?b~nDoYN|2Vq&{vD1p_WKE47hG#b%&X$KT4G7w1I_7=PW1;Wfg;msSE%gWw}+ ztvl1E?+>Ld^)`&jHW5JkSJPL5{_i%9!hR5{PYXv)b9CX43~5BDT8aGq8wMPn5O=_% zR(->>5g`++WlWnsEiIM2YCR{G=( znd}kkyT{LPT`twrF5EiB_VU^0ye2j%l;3lpSQr(C=!079q}zsnMKou)o3L$6hH`P< zD`Q9A#kb1%p^?1S(hENhg!K}PwOJ{7@=$SBjqu_!+~96KzoX3VZd}old|<38vDxs` z8~omP_0V%g3TH<u zFKO4Y^m9L>YDa%gv?#;b?F*?5!#w+An{qQS>s00+aDSt!U$*PNCE(aI_f$I`8S^M< zRlxixlsRr8zVcQw))%ly|E}fFHML52<5Uo6Q4&&-Q`k-RCn67p=s|KtCLJgn_uE_| z5>+EKm7EIadQ3t|Uw!3dfc%XBJ-(N9fa=<4D>O8!P5}}#@qd+r>End+2FlMllSvn4F0bkIqe0EiKHomf&{L(r&I6k~LegsL((lhH^jz6LloN|y@f^F8 zyXxY{;b+?2oJB3{WZY&TffDFKBTHyeaUc4y+dEdQVnKB`k4x&u5UnYAxoJHlqx<>x zh@mJyx_JNOQBX|zK_2d>Qh2Z=jcJty2(4#4GSD~CXYFPH`qyrj@-71AM%rz4hvEsS zlGAEK4Nc+pI&o*e&lX?lz}-Xg+gD0B!4+<@nem~=C$LxYGkXcW&1Fubf)?VlVB zgV0A3iv+8Q6VnC-iIRW768L>>z^+=~(ZH9!DiJ5lMIe5xLEpISxc4MkJS!3HN;9Qc zs?vTCy-NlAwFL@_~)44&sgg_|HcC z{-^m-vRR+^98qrAy@wfg9^FT@TCa4anKXq5Bp;uHJbn4imK_BF;VBozuw(M5TKdw# zysI37Vs1ebtDODoPGbrC@R;0)i9zDdp-o?fF^NuzOLbyh1^dS#RxkE-fM^AD>GvM! zwlsaX;rIzO(1@~(8s6;)79{<+Pe_j{@5&+glA=FN3l`qCdR%TeFKZd6w4RHQwkaI2 z-ueebsYUSi_xd@@Gu1{4mvpDu@FVwm*z4NcfCrH@7kd0aDRr9EQLF6lF7oa@1yU5$ zA-k+GJ?O37USiHJsy6GRZlve=o;}YWxNyj>KwF1Fdd{T_!)c2*!kS=e+Z2{=vDekP`dzEO=JBw6BdYQvVJcZK z<~BKv)|K{8x6$x%GTGPy0$<9Rps6%Pjd#go*NFY$Gf!{8x#9#YYJR$rMpu(8jxE#c z)65Hj+K@npH_lq8ZUeGiEz_BaDangGoL;|lEd)cI0wR&CE0BB=$5G6$QDo*32U73p zDV(PHG=&9e44;d0XWLX+*d5T<*9Eiffs%dB@w+Axf(Cw`s?+0xpZ`uNT$MSO=v6+6 zcuJ;}iiY_zFBWHgJv~_gcZw`*k?pOuhdh^1j=D zU~LxfMZJnH8n?hu%}e9X1q?gUUUcy^RxZH18yg6_?N?M7q5_!7(U%7gIO7IssXJtU zeu#zHDiBq(NH%m1HA@J_<1B$r4#MK0=U^@KERe^7wU<0O}4iUdoQ#J_XCvDD}s$ zpbKN;$Y{UXyVG0+(Y$5LWrK~NK?+w#c2HPGixnsu`RWFeIdhU{Q5*V^GLr74pj7Qn z_AYH~&bAdP!`56Z(F;p4!|w%hZr6nPVdZ+Z&l+~80Znf3(XT366s8uj305z8R10@* z*9~?wB+)o0I_xA1jHjgoBVxy`Zz)=AYguQk$v4CG)y5~-L^}i`t+N-?R*?pJqW5n1 z!#n!>h-s4-(O$)nb9X)UJla2&hKke|97o>A*wxYKET{6AE42>@h;=C6I9XLjIkW5&tblyeTYc zV518tdCbi5$`sqguK1H#L|HA(7x%;rrYFdMle2OwT=99}{n8b)s>+$&3$)C4mgHEa zw%TD0!Bj>WcuCSkw&9d&TdS%Dl&oy+Thr;a0Ar{s0c{@rp{wd$f zeBxeLR<|0Y8X-Rg41Y$*>Vg2_?thgs|C74IA_A%T_Yp0E+=zYvLY>S-a6uwv3~TOn z=0bn|1U20yIWHHgRvcX^K9IVY+>2jaO11~nRw1>OM`*KbYJk%qlz4MLPj3Yk=MhYG z6&Bim&4xGj(Szdz)=W^~JOJlkZULH@pb7HaZ%y=dW#1K|Pf8H=5&?-Y90(ji6V_2z zXW}j7Ra^I_QVRc36e)nx82PiP0P`Y-HgK&j z(46~S(ifd23B)tQGG{-sEwI5iqZ%_v69{IzVyancKW{T#(Q1`tk%BMF!hRti zFjeH}NGQW!?$NWTpBz74yz+Td?Od`&ab4KS&~8&$OLc~qqUA1M97$1`9lP1|Nob1f zbWtLyH$6C|A-0-x!z0q8JX43rcZVj*r#50rAeZGMXD2R~f)Z8jNhbq-?;fez5**~q zPp>yjA@wG_2fd6m5JzNoC+p*_*7I(eVozVfxB4kHhS8j}!UR+TP}5cv1*CB08)Nst z?yIUsBcq}=9XUwqymyZy2rXKr674UH9JFKA5WlJ!VQwCWPi7!Zd;h|gO>D6I;7~F} zH9UE9(KU{g**EOHlBi$Zh^@fe>mR(s7^KfqdvkmW!c>lYi_s&so|9csC)ruZU{lh_ zj?pFQmu&j8HSf07^vsuR!h$cf71fTPIlL`lgM~|~bX<}nb`s-8J=)P9bO-ox3Wz!eCs`Mb)S@NyO}#NS5m(beDr8diTryt3f2bgavR$!L{JI4Ww~=J$e^LyY{+E z2&(R6_XIE2>O1Ozc)f!l_k#nQD4&En1O5|dSWfwvjxG}m+usE@JRCZIVTxnTe?S+j z><>q(zST2sP5=JSZsD=i8F^Is{6oLLu;6iW$Hf`R<2AFwan7L&4lwZ&*jjTelijBD zAiH&{j9v8DK0tGJ;{ddek|1q57B#^acmLagjPwl-tUg-v(m$-hK~R;MBO>$FrGV3S zK;<^7Zj_NTW%k4T<9;Gc_u|?2q<3EBYHCf-nVysrHgP4zxKq?fL=u0V}Z%) zIl;s2JAo`vCY4`GeMnq!xc*%hoU;7P?qWcxH7-K5B zs<7Opcrm7|6a{DlTpBwr*7=LvJVo*BG`#ls`txCMMKrj=O7K8A#f745N4` zAopLq)_&=f3tOo?LWb>++3E4gNj?;)mph9&G;^M6L!%0|35U2Rxaj1KEt&k+otg2j ze{R}gqk>-3+`j18(xPpvZ6m8|4m9}(B>#i=ydtC9D+O2J!a$!(4q{tD(W+|pemK_J z*u#&rfupYA((L)Oz=e~K`u(xP1-C1C>$(Rx?$LkjMUh=JQ4)o>U3Kp$q-M7%@@d7~ zmx=7V9&1)JN|$7t%}MaeQlLJoYS+x;zy16-(-){CPb;dfC7O2(>32D)>X87me>?>W zL;g&-xM^yA2Gcu|>1D-DE-YCL8H0RMP~Awf=t?5Q;YxyORxun#^NlG+H$_Gxd2CC* z`3~7O(XQyhE}vcerej^5k^c%U=yP$hj;Ez;in z?^;BxUtsZW8;)E$bC#X-`Or@ZplDG_tE-|=kb{lOj8>3?`LC8cE`TPWcYQ>OpnFbf zP6-ezQEseT4kouBQR6PqT6-qN?Z=&nHsVooY-iEhB>m>|*d7Qsl!uE?12f(c%k6iS zrr3aH5YXkHa-`fjD>-6q>5a~ftOi%=w`M}ZW;px`7*vY_rX%vvzw@##d>I#qzFwX*igG0jbz!>Ql<57#Si~<{7|M3$`Yv}=l9`FOxp^6Xv+*a*` z8;f_c0~=Y=7A}{J$soWKBeiFM9eMSP)uTJ*-dXC6M~sjC0)>vW31F-C%3KuH3sizs zaY5Gvftuc5>mb!1o4TRcxK;eAB4hDqCGc?w8^)GIT@hTLCZ37Qce^vR%8R)C#gb@oODoOT#iKdj>Q*g9VHp;j&>Zlb zh{(YdFD*rHIOLD%5g`8E^l{8Z)1<&e1!X2b0+E7^eiUzN5Vo( z5!{+#a}y!Es`i`B-rk5>Z$sk=e{Zle-Ttpg?Os+B z_RLl8x^j$sAh(FTv*4ZPI@Q>1ygc=HY6180i3B~dGWbcTS@;{0_@w0^K|0EqEJZQl zZ{tn->gDDQ>ATw7@l0l(7yS5Tvf_l4JNbO;>o3HvigV)KYB)GNSL|M5p;0+s{C);Q ze|P87#V2GOC;GZKI`&=6u$S&1wHwiw)TWLi+CyW4ud>A#OK#&gO^SYN6iV+lo)hZi zlSRM9xc!E`D?CrToBejiXz?S(kg=;?iG`(=lxbz&dp2sx11Pip{i|sH!=aGrMcqHe z8Rp{OwBG(WUm;XlcZqb%f8ryPCd%LMjeBYLUT@m6@-Os~ca04{1De50a1vrFhQt9} z^`ZsCKL;;H9WQJo^q5_oFhVqs7n|V{K8Gso-#)wVv!bmf;k zcV^#QB`%3G^uIT)`2|i&5Pu0FQU&Cc6$U zsI0+O0aqFMxMKyz%L44~NT?qmfeJU0SC+6vYi<gu;uv~jWAa){*g4YIT!$Y&~b=ia5+%$v6tkq$R^wB8}j5+jLGu+58E{&o-a*i7G`!J46+n1jz`f)mh|jR zf^f@(5#9re8NFT{r2B4u-drt(Q;|)A(O4v7q6rbY9#tswJyr0r)7z_~uOZPe=%=lV zidQLpy2$M`p6^>(Ir*98v?uj-17EGeZN-$D{ut7qaP7+n&NO+V)^_~guOczpoVT6pXfQEYK0{IK;k zoaW&dxE%7FJ}T*xV8RE9T(-d==f`y~ru`}ZK}1Cog`obs^B*7E=dly-)RILK(d2re z^3;qbJkvO*L?-rxeqW(4IO7ZL28cYqLk zf3a`fTU&SNgx)gTMDpDf`>LWS*=bzozBUvVLKoHgkkOdwQ<(g&fz8N4S@I}o9)pap z5L;(Mj@j-~P+Lx%LawdDh-j%ko%P z4as9`d>aFULD`1>&>5|p(5E`x#p-`x_U5Q}OQ!^@GC!<@jN^Sv&^jUM7;k%1K0RwE z+51gNbWNRCAsf`AImK4~Hc7TjRxfU~S=ilkefH!v8F8*z8*X)6&^Q9wc8{MFdlM!^ zIf1Rj_%r$nZ6+F;zPoz-J7G-NrmR77{5b1N?h-6z&ra}}8Q-}4W-Qg4nYM$EC0QAz z)OLa@^;4{MI&VxYTt}*;NhxEcX(P8?0e8|@O{!(;^6}HP7oBGvPGpsrT|8%GQ0HEp zVyAA3Dj%5F_IFD=7oKGWq?zQJbuN=)$V^V8tIrx4 zphpGzMLc8lk*5?1ZUr@-Y zhcjBglxz;{T#vyvc)!Y%wfS>d6c^N+1{bm(?bT3i}B6;y8PgMuB6>s+V1nufrUpvXRS`gv9`}6fT z2R9Y!6XeHQz*%q09fla#6_=GF1t z9JY!f8l16-CX5_s>T1hdZCCLqN1FHbL!T6N5MoqNv1<0}xwuN;r_iS#Vn+;ELrHr& zpPk?E-QN(qA8MsLkifo*mi>Gyh3mPD?l1NzX`5NQ7^xf5cP_ItE-*-0C^{VYlvJb$ z90ITshN(7B0P3&a1D18)f`6tOEXt{O*q9BRBn&?# z_wVS`bC*=&6TVQFNJ!0M|0JQ+kBIWW|iPn;7N>f;2@O@yD@h<;4k03 z%osMK*Z{IekZe5(5(#wVVJOQQ(f`BJTSdjuc3r!Ty9IX=JVeeE&Y^lRoJhHAYvhd#*XJX?$9${v_S2ku1xdac&tu zCA2?915EplNpIzoF%vHOY~pZTp>M%IH3*tI0g#yVE4^UELuF~z8Z-$e>&UROUz3_j zh8FX2Qlk3nzh(N3pPQ2BE<9XUAQ?nflH6}ew@J@_$+}BxdYiHgp7^fS<3vGDDJB8z z-pg6_Q7mfU~-cv&{Gep)O&j2x}`@VUU%$@ zd~X&QkJ3{3Vh3YDllnNknC*-ORJX2w&+Lhcp#qpKWd!WJeD_e$6vWdYd+OPQ>ZVy& zD6!Ig1f%B$H4(UZdcLwKk<@_^zJv7yj#8w2N4& z;o~BMjI*O*6)9lAJxtU<2|xthTs2<4(pL*Bwklu`+lMx<8{Q;(_TOS08%z~Ir7VmD zq$h}iJS=bB_ZNTH7Q=swa(&D=7zxg7eP$Rkk4pwzFR7H*)vN?;73d+RM36si|J=hl z3oRzvYn`u41={oBoB%S`4b#XD)WV-k#s4Q5!w~|g9y;Ko3s}~1h-B&V5YVlx+KSLbkgbG~b;V@@ zAb3M)luCSCd3mjSYuImg=l8f%hFfyJK%D|FKs?Cks5<{--BNT@k4tON4_H8<3(x-0qd z{8p{&NKd1Kk#an2I6O}@c?ZGn_LaU-&s|0j9w+9MhdJOj%4U<-ULMem% znuV<*Oh&a=-~Z|zH&&_FAf<2Zs;ZB+lB){N(_5QgFAqJJL9lIEpdqpXkGyB1T<-Lbo=RkJpf$g+Zb-Jb!R@6_|t! z4&?S%1{5LD0nJN~Qf ztjh<9dwtpz2uu%Cry8BJ|NO7espakulQB*Pe`pHldU`zBU~A%+@4~G1o2eX7wNqOr zQjE8@%<`@eJX%R>Hm$ib1v#^E`Xad;Xj8L=< z!rJS9+RuMClNM19s6j7upz@A0l0E!(F9#7Q&0v9{qZrx^BpcAm19r6&Ej3VVdRvXr z?kQ8`&idELKZd8%3bCdTNEU6-fP|HpAltTVc5#@_-*v*;zjz40q$qg_1RfqIL0$_^ z0*O?XNahq!hD}9!X#8?HR-2A`_GzqxuqLhgMju_(pXO&T{L|K z-SD+pqa9s&KlZtTQhVWnpa1-y5BFrt>T$|XmND5ZuS`cISc|~d ztjilUr^!Km0V!zC-1Lqstq^(4dBiD)AXibE5TfpI<%WVLwB^x)gjZyR6)SCz1TUTT zbL65I)ee%i&`pzgiIOsZ9E0U>5c`TJmy!Vg@KuR2E9ZHiL>bPcEcZ&?t{m!3vO*!> zuzycu#yo@I5?q1lJZ!EFUBWYkE@gkePL8p??U{T}m4efum4L!eTA0Us0CVCbf)`eF zrSvgR)|6Xlg|FMOHH;dSsH@j`5sR+P%m$BOXtm~-;8JG!nv#zi9Ss8C#5<1-fa8kU zMTp4POh_d-n?z%qR0WBwelc)$kd&(uC%`7y@hXe-Tbzj$Z(1hx?PfAL%E!P>)L@CA zn^5vhS3CO4{&co-Q)#?YXq?AZY5Dg(Q6^{rRH$KRBi1_CILZ8|v!5s^M)?JHN{e9U zz#HpzS<9l>z;fx-+$3rrnS4U3_j7>#zTkNU9O76}p`$q`HL^_K>c-tB6Wmr6Zbwqn z=oH^QO-DeT&PYPNXgxnesM?ny6cSVCO+_VwF*atYXmK0bJ>O-UA{Llz%&bkX~Y5Us_7t*8HizE~?7>4i8H^-Q=J>G_7FP4I_? zP$r>!*n{>-j$zKvwTinN^~!<-poHe_p(c2Skf?r`%$JZgjh}iD#WtZmbVAd8jF*HZ zO}1wKjsWi;QPK(`_Clg^rv3*~S*+w_lBL_1^CA4xmP~YHoAe|C+ak!9T$nr`uPH?X65NxWZItW{R(`S(^RtQkyC%lt^HU`4vo`y)%!s z!4NK>p0LuY)V4LEYND{dm<8hs>Hd7=LW1exsIJJm`7za9l$k1iqtMt(#`y(wLu)j0 zGi3=QIe+12R#;E$CR1&1PXL4Ug@Xhd`3E`%DaOxJ>`ZM)fdxxr!b;<=Ncg)+GY)xD z4kEu2WgRYTnU7r=b6CO@Cq@I)pT8ZogdY~;ND(J4SwEgsq7vDe9vg&`?OQN})9N_* zwdrC%C$d=#!;&GrVr41A*4UA-DLIfQn#R~c@ZXKtgqi*aVr&=|cpx~l{-8({3z8mi zF-+@ciL;9OoI?5Z%VNRrOC93_p#wNkk7)vsq`lmbx}{#E2~?G`S6mWCPVY2)d}Y;& zy_V`WJ2f?nDJep4h({Fnq?15*eOH^7Fm~o~7c)wf+2lVy<3L0|Dtb!9AsK@= zC@)rK_Okf5zfQTzQQ7Z;LlKI3c!w;LG@xf|@c0YN=cFu-2=pmp{EQ2pN|N5U6+<+A zs!R6JWG~O=rf#n}(rI`$$AX_k4G-VQkAZE4DYK;J2Xh=_t9=a**;Wz z?<;k+q$@+GDmmQ85~`&oCEJU())tgNk^=r~esp%oq(=_kg2Yo$B8}~)m5V)$KpK!J z0T~PLd`TlB$8cliN~SK1`L`~Efl%GQ{4nX-seMkj3S~y77rXx3>46$i_!@b~wJcTU z=3KJGu4{K+5P5`6*yz{*@=9n2Qw}^2)jhtE^N?M1ghI2vnUvVKe)NvDbvQ0Cbtdm zI13}6_D}1Pv_@D>un_6~;Mno3E{N9!_V7^qRZJXiz-Gs3E$O;|g9t=739NJ)fxSG6 z+%sSeK!-@s^85)Pm3daC%LC2ESp%ycB2F+LXZYh%UO>xRhnRm%mr`vd%KCq5R9ma_ zE$=8z<+<)ad((>h%TLi}o?!_Uo#YXZW+qyWMvYH6S#$GNAY<_Vsav=WyD_*Ao5uXM zYqLGd~;TtG7AS{k$Z{jpB#ou=FfFsm-4?>GcEfr_F;*Y1WuEu z>c67CY7Sl`=;^*7;_*-_Ws<-FO5Ren(m$~+l(r@&kyhHn=4O>tls9=_Bob(^A*ZEU z`-@cuQrystHSJ+kg{~}Ibnj+Got_=3++zBi&z*QgS_y<}Q(Rzo+&*i7KIyR6Hkgua zhX>Ej%0}Wx0Ns{39U(-~@w-F6Hz&}pfZs2qjFXzIC||7IJ(VV(&F@v^_L~@vE3V1+ z`b4X>Tel%^yc)dR!L|40*Ga=`A1Qj#7iKtRpR(%0Z5NIt;ip35VZc9DSk0**H2)#w zP?axyKc``ItX_O$80ye}<_JV5ioN{bVTrD7w3%rwF#8xoaXK!<91F^XwjN3xe*Wqk zX-<$8e+=%loABQvJOh-U^SFIqT&2r{3?tV#n1{jdTilJtzcO{Sy&K?wrS+YSo)tm7 zd5b2NSN^X<>hQciVeY!4CObyC5VN$pL`o|DFV0ky@M>pVDcG57yNn4u(K*ClrX|RQg`E8gprMl=}%J z+Ttc!R7)bUuV{{b2)ZnlZBxg#;51*6DALAFMRHSo?mZMymc9zz=YZN5h?S6UAOYD_ z^jxbqC}7PlNyVBnCycgc)odxRi%@w~yKzJ>Wl7Eu+#+oqz)`p?+^l5>T=$WQqkD;w zp$J)%_2v1+6Z#H9kYGzK5_?$WO`D&Wpf42FKUJ7%0j+{eCea!SqkEl|90bJ8;b%?g zge>!pYsy_)^<&rw8m&LO} zDOyT5w3%xcj(m>F!h*~^+?PGr;oV8s&sQHO(nc$XPeqR#JF);TCBL5{*mC8c_%bHi zJDC~e3}@gY%U0F}k8|M`Sf^;Er=aTq_0|czSaF5YXLbWkimch{!=1r#CxSe{LV6R6 z^iHSP%cu7}^Y28T|KYknS-y+5AL>u$d?zenZ^jS6H~ny4H-G=PIdM&nqg&ru4k0-q z0C&|X%XArIxAae(Q6SB5GR=XbCn?YLe$)dHp74^DzOgDiT`F0D9Qo*dhIMXapfoHD zlM(2~%vW1r9a8s4B8jSSsOn8&kzzU;*$+BmKTPMV8v}##Eas`a1LvAcn&;R5>TY(` z>xEnHIn_dMGeiwb|8NL9!pItFPcyERdb@jdJ^xR8s=R0UPkYknSTs=(7#F~9%^^r! z)1i2gktDvJnw&2o@j*}Ke$4*J_O-HgeJM!Ub8>SaPpdmLC06%?sK@mNF2`CMXj>cFH3Y!V}|h* zIqze0k$}0$6Q-=+yAuS5k{w)ZJdlkl&khr*wHGMXT3hYj`BJAwNZuzwsFLX7e6>y5ZxvsE`$BX% z8b^PLrTsqVR%JQJZ`;l-PZX_iPmN?6|3ih>4jxlGB(|&mALulzYz8|ijNqt#4qs7x z|8#+9a^Z=^i%oPVNI2U$dx&Igc9Kd}(%8+I=nEp9%Y23$zty)Uf~q`aQxENUJQ&7d zQUxi_g(L$7!G8SYm5#czfm;PWj+CuMd)zHv^_NkK{dkvzXFy)6K^w?$&veM2rsO=} z8fOfQ6-6DU@IlW_{;8BVN;*^kQ!i!4_p5q>hvHh~{CSyy99&()`Hx8kcdQS2n64LU z<#+;yynkfK8_S@&gJ^x&#@B(NlYdU^FmkJtyhKTaJ|KrYkyy^8#Ht1QuqyVH+7FkT z%n|C~;o)nm>Gpp**B} zbUY$_?Yqc)D7%1Ks2hn%Ur{l#V;+L)yyYYe9^m8`yOALAR{d`|W*&eSWLbD6f&oC< zegn;oz;uF?!7dl|6QFf1(pXtBq(MGK(G~t@DeV1El>$)(Kv89Z7*+)s@@v95DCX(@ z0qTiB8|0)X{BF`|8>11Ux2wNV@ab1!3H1{s!Z(%#7 zHgn16eI@MdPXxP>PuBP-J+y_={?TNeBwDDP^xyDZI;1cB3X@cxUm^By2A(701dl@# z7;woVJom?63a>vZick2&&!p_88gB_8`9EZPLH~}obA;dB5;@4rJk21GlwPodY zNy{hZGf~GU=-0p;H`7RItniV*)~3+uTCnSqh*jbAm)9y^-~b5yM1EiE zuJJWo_H@QSpIBnm!^hP~#^=7Tfq!*EWp^n8#TsXkZrGbm6NB7Pu1lxvjA|Gij_@iT zTs#QHfKhNh%&UZU)F(~V%EcBT<5zU>0HU8S(xp!$G4I3)(Ga*W=b$>!mOmPHGRpazPpbL{RT{G z{$J6Bowjc=#Emzo4}scNP(q4L-L`I(%1sC=O!n{N8Oww4xdq~q$js2|yUL0AN#JR_v9 zN9itm#8Nq4liXpcvRnE9SX$^7oa1Lpf)1zB-7sT%{h0Nbm{dA&nJS%*dY&ly zLk8K~Wcfv|eADvj)i8xA|9>EbM#->4S;!dJc2t?oX~T~L)biTZ$u{+8O50v%zcoUz zT&fO$nEzUj6kkAHXdy~|4=Zh#TN8|#UR(NpS1ntq7l4+_NY^*5GGmGyt+Q0sDTEyk zj-A7cy*qFrOjnkM2cdf@iuN7%=w^&9eQXcmt)Uk=IXO5GkK5L-|0%#t;yFh697*Z| zzKM#~SmZ=AzeQ909*Z&{0j2z_yuasIp*!bEWg)D9D*qcx;Ye^n0KC+p2)3mz?OLbl z8d9Y4KA<%y1~R<97<6}4$QJiT7RB-&%pPD+Ep1z+>j-4tiPQbaY}Cd zEEpYmI3`b)C={%C#@C-qV}aUhiy;i;-6&t-d4##CEbTlo{f6CWtDgVWsgK}GP6`-a z(h~Y5V{3nRAcX*hsp{EPOli|hko|ei=nSvL4{@#vQN_)Szj&@QRG7;zo$|Kacs61P zoj%u0GIMNXOVa%~%X@<2&6WOz<{+@heykAVScK>i&Mop=jjqg| zOtqotCz;zAzzEG|la$eCCm`|pt3c`Dw`qz}USQ#*tut+B8wo2bj@{#eJ3Jq(qJN6Q zT!f+!w?(fiC7%P7Q=BO2Vy2pml@xzD05o_ncI3JhXR;FFlv&Qm0 zTW4GvNFUJ+PP;uF`Fu1VGZ77ZaTI zpirJk{*hSTKcVU06D^E$p3e<19t|qBR62t=lRqS=z%9Qpbn9GG+T9xTH`)i0F;Orb z*&G=n?qltNv&-jOsw5Y<0h=s~wtHO0rNm(r4z3T^U;>3cm*w%U#vTj2#F>&G6&||KR>!VJ$ zgv_Y$*LV@~z-k5+R5yC$Sfe8t;p1+b)+E&?ZLU$r@{3jqXVF(J;>y3OC)vZni;5V+ z@4r6WinQr872JSiDz$2GwB{jaC%1VETuIKJMTQVp-PlfSQ;(AsiE<=?v~sQfAG|(6 z_Q2k!YBkAjE;a{^tq%8OTEgn9{#55POeF@%Pb_@^d&ep1ZBRh|^F>?A-e1K(HRF#u zNj@cwT$eY!bFCk^6xh!hy$e+lidtlgC&+l0loVmwwS%%_p-KqV7!KY?ocvye+$c;f zsZHHd=!j0|5W}ArWFBtzx{@%Zus~GyIE3_b3a7ydJOO$hc8=&Ut%u4iLX~!Bz##MP zf-}2PON127p)n3fB{K`205UxWV|w@Gdjj=A-V$b6_0tNvf=4s{o=_m;UXPs30REp? z>(S9j3YdIP{w{9%_NU>`V(wKp?%={tZ#OvNUt@7 z56}U;5MS<-M~@MuOdHzx;dzp>>dRpry~4T#A+t{K@26xCzh5DIwS`u_Hhhseq9<)Q z1e09lDX{V#@9^N-U`-q-4{Db`_Xm-0A^^f#gP(B#canSR-n^Zy|5D83`Haxuh*5#$ zx?dg8jc~)2OQLyWpnC_+oleFx;1D1wylU4Yq9C(ZrgA?iJb*_bylOxr#xv&ofUs_r z;MX)Kht_o=Z1HcYNnoh*LV(DPg~*o`jtM%zlAy5>NWcTo!8|cw_yGZySWrO`j$2_KLM$E5 zyxd#>sRB)aXJHiZX&fN|anBm|H*#;HsP8f6ryu6L9+5BHqNtkV$jIxWMq|BM?>B#wto zcH;|1iT}W&61vU_Uu9&ap5?q=BSzBQC76pn%OcC7wqm~DtlDNNNaWm*n+TAQ+!z$NqJrQo-*ie?` zzeffhvHQ-5LbgwJQoIb`2Z9%rFXv?Ecp0Y#({c{7X1`jXcKK%`i!)ooNXfVV9^rWG z{70R-@9t_pl>{gxyCbV~gG zofl{>L_-CY*1|LeE{rR7y|PfCf9S#2)lrX^lHm+wnDKa=JiVt$>eW@jx(=xzbnr02 zB*<9XnmgX=soh&ogsEE03p^V$P&P7b|G=n~O1|Q3Ikd*nf-h{T!#d8j;mBuFWhwPT zm2J>HkC19Htr2j@;)!s>j8M)6uobqqcg)z?(l$l$*lvkqDSL43Cn^b#MR%-sDGm)7 z=t>al_8$%<6r*qT-Ywsr>#^uaIm$#-gxZxL@Cg0BZ-_Zgr2a7{6~_WIF94o_S1j`P zFIB=TVybFukHln@?nKK2v1cWmxn%ebRsG`Jt%~+E>%M~xbl>&ZCyn4CH?)zov7GbV zW&9&`s3nj=wnWGEGN|UY))A+6Dngjz-CR(7ZlTfA(BhLWhrrmXv6(#?;5}#c)Y7iD zA!TC+Bjp7n%Fc6AGGjp~^imaRM;SzuC{`N1m==JrFSdrDVMdXEfa#fsnklz_uEzjj zs#iUaX9l{iQtJ^tz+NebPQdy0p zA*e_PZD(P~ZAda}yPF=eG)|FbLOQfPqq$~{|HL98ys}UrlJ3s}^B3g#8g+Es9EI_1 z>PNRpi2jqwT03l4OLMI@(H?Gs@zC79pddpB+)c}YS9P`_$zlY#80*(4pPx$nf2u3lUT93MZ=zGp;I|j7i`K%N)4Z(|c%!Ig4Kc5B;#ToOq^j)@?q!M{@i~%Q90$9C=lSgRp(*Z7QjDr$fs= z!NtcSmq-x4LaAHioXag&U)essgwbGCxQ^2izP&t^G9BxABt7M``FDZ$ibcK^xl7(5 z2Ov%P>)uz)%b|D1QKIn*nC43T4+JW(Db=^qY!MPAO#juw>~fpP20EQ$HGq3Xa`jrG zF^k#X;v%tVtv1pzYN&MDKQiecTg-RxBw8bo80N=y4?iE4WvPoUVR*n3Qhls-@*#NA zYS~_uDgG2^Nn;i3ckRr&JYRFHZf9Ga-l8`$d+_kdt~%&-^=Gq%E45ZqDD8`eB_wQ- z+=b#{(rcZp&m865d1!mAJ-LQ)yV65M3ERgd%MVr~dOTA`fSV_VI&tiCtB8?nGd6ka z$Z!%i2{gYt17)A}?B$5-T7QEk$7@K2o<2cPZ3cd59|_RS{1JXe2g6j9VwGb><&ivU z?#|1oq^h*9ONPCm5Eo&0Xq#s6mX6;*`K#o7Svb_BGDN&Zn4JV;sAC#R$1>@(C212e z1!zM|@|NMqRHs+^o#Pa<-Xkj_RZS@vllZquAc;!>|gW`gh$X=Ie{G$6JhikKNvO#4%5X#?MJm5-cxX zW(7x>hhPq#GfxQ&#rbU>h+cRF3@gASLWg;ABO__$BGRjRltJ%313l+a1ZX`Z-Bwm~ z)h3O)q7oE^P!dcypx=Nahz>3j^hv?zTgbiWE(Amvfba72=ut5B8dyo}3z46|0}tYl z`D_;l>unlu008vR{-JTQ{K@MMR_(Xi^1>1)^~w@T1+Nl;XBmf_TZ_Dmzcb8Rf5d#< za7|t{@jrD#aEc412dxto@UJe~&ur|t34M$B_qTpXsl8M!Zh)vI?~KSI+*PH#CDp4^ zcF@jl`U^-nCcN6)|8-=N2tI!|GYvAhRKTc-#X|k-?yjX6^Vjz7R_pL?MD?86EwzEx zz?_Vei_^c6%7*ZGcc%A2AQYlOYNOQE9oXbkp~v)fgP9_LB4UL7?JK#8Z>1B%{f-z9{EKncVKUw9GpvPZhDf2?U5c!q{{SU zh~Y>s0BDG5tPDa8bg7}vw%o1^CzT~D)7UU0 zjid`na4x6*i1ToO=aoj20vSs7Cp3Nie$tJkw2~-l4R8QFA+EX!OmI%&Los|vMrh7e zqlAl%y{S=?h-l2O^rS0#Nu1ex$9nCL-$<%f$;S>k^a4cO1a+YQw zF3Q2f-nzf_X1P5;l+XBz^DB%7D{!P8uv7xb-At8vhXqV6y1344&LJvI?B7y7rR{Ex zkwu1aDq+`XB9^Dj{3BH^@|+woF=HF=eI! z#D|#Wc=d$SM5j{~MSJtbu#z6T9ai)rP%TIYYM9!OT>>! zCn!_ZsOuvD2!BkO#dNhqlU}gf7}!dmzc;7$?Sr!pb+n(Jm?X>m9ej4th&K3qiI@5K!S0o@*HeL zlp9gm zw7oL5#r|%f!9a#C(zKU2_R`mTnU*tS^*Jz$_VQ2b)co`q@f$;JLt|^u>UZhFPaapl zOiufNh&x9D=YVa0Iuu&$agjH+M*-5KK)dxyd3^WDY)5k>6Lsw3r!PD3D|z;yV}zSQ zGbv+7b(r9_rpA9d$J)$P9SI?&#N%J{oCQTDE!V7A`#1*W>fARxSSfrFtijGt^OrGf z%Yb^bHF3P(2=in?oLV|fd0pfQ=+XJ+C{%597{A=AQw-REhV2yTJ-tYTluAXyx+#Pz zp)&>>6#qs8%!D9(9@<0^Qo-|xdqrz)RHjcaY{F@~Y|+_mm%il#OD<9{9GG5nu?d&! zxkK%dj1$W2mGXy@JJAdOkWf5-AV`f0B_l4b2!G&w7OANAI@TfqH|#nzq6 z^$=QQ_wVKQjSmADi`?TC*$snty$%-`t7%PD2pr21^aBCah9FIJ{^*R6>a0>c=6xRd zNhxCs-|{Cr%kd8iiyHw=vI1K%OyyWUtvoiS#g+`aqkw~;Bsx?Ury1;1{ptePDf7EL ztWev}7#-fP_xq=YKhJY~J*;J@+zkC%E3{Y$IoeFbV#i>h;pIR|girn4f&mpCERF2p zDq~quZuLiMcPw9pBx$L>)l}mue;D3FaRtM2W3EXZ!Aky3r7ZT&odO2&JKEWA9CCRQ zgE@OS9WLu9{$dOhmE;$?jm>H6C?B_2Cm7f7Qc8cj$hMvv-M!~xrm^sztc4>?g8VAB z7nBh=D^ruC>bu07ZFuFGeOa7K?r^ts&dGecb7{6SZUt|$9+KgKU}kUF?laL*lO8Vl zntS=qpuiW;IP+nOxc(QSf>f!lgzP4GEq$+wkE%ZGcKIlZ{fPG6*%^ueXgq9whbp|$d&w}&-6ICcG`nUa z3VR8?216Q0n&w_KmlG;cxplUOOhfMb%*Ma%pndg>=ZU|ns12!zvnn0~crqRC>pmtHuy65iB2B2t? zUso%ddfYaE|8yulYqrG0|tUPRV8QtY_6fx zN=`)kC7uIT9>+v**>Gv;;u8rs+S|#`zC!luVD;wuMqm3q=?66Thv@`t(hn(~t^T@u za(VSfcQW%ls)eeCAEM{uA~OOjfq(q;Yj2aR&{#SQsN-;jcJROp3{qG8_%LL0;&V=aYa@K zSxgT8+{7yz2e5HeN%9j`f3f3ZNNsH~l}r%DB8kh5_kuhxRtc;2)XR17`&j-pl!UDh z8Cpc(A=szAuSj_mL4``VuaL10Qo&R2=C(t~^4^Olj8`iA%gmH$%*3qmeP<_?;sEsl z=2Q-qyVNYk-c(OU9XLA@trO$A$8LuRcY=|b={ za7w(G%|KvqR8u*hA4BbVVb+SZ@OCon8y(@aJcjHEq%uR#^1w2kaN$$Tf)7#Rv|^hH zeQPAHcmjTk%-CzzQ_&CJmHV_kcT*9<7n6((CVI?Im}tYaB&N&X+a>zCK1Buue1>Pr z))Vybm(4g9$2Z0_OZmnOoM$@hI_g&bslj9$@RLCFeXX@GVCa6dk=D&D%fG6tip-AX z7yN7rJP|F+pZ^j@70aQaK>%{cff`#Igq!^>CjO#m^2;KOR6;iX=z5)ih9J&AP3=J7 ze!8Z~wHbO^Ibz(3!)1V=_?`kB+eAen=gXPboaXhl(#a@tIALZJYa$tVJj)MvVcNkBceBz_2gx`gBEyK~+i%d$&h6^ypo~w6 zepkhNh`@ty8RPxUfFC%er>5dld zLa7ZLF3;Xe26F%&GCQ!07h}f__s1MnE6a^U0|hDZME|>NiZUVyfJ|S7cZK>%r3!lx zHEt5lt{bJg$?f9EP<|cyf`E*4m2qY~Z}+jn{9(d88J)rdQ=^zXHtF+dGn$YhVvyXc zJ^lliRGP#Y&F#@W{)|hL`xBvP1VgC~q0kQ&XQ<;7%YlCj`JZ>@W4z-{s+lSiRF7_c zXoOtqQ1>D#5yIYc+V&F_@RzO?IQ34-a8`9q&=Bs%YR6GiDfjLt^p)+Irf|BNnc0h~ z#oGkjk7;7BTXQ*W>I$dB9NYW=@9gJ4{h_h?1$nF&uN#AYe(C-A9ONnVz*Jpi3Cyf?dlTeW`Q)G~7W^S|U?x|jv(xS5FHBZdKN-V9Nxne?Tg%-~~2%@%_ z$QaC$i4L($)1eOKV)`jh-zp|6?^iEt2HU@HnY17y4*Fnk=&cSS0F4HC$sty)p{Ogn zQqQV28nR#M%5n6m4#r$2>)-7ZItK*I2Kt2ES-i1VUVRxb^rH^E{3L3V4Q@Vf;rw~s zc>o@krE-rp^cJ^8spAG)`f_cVE9gfJm!Q@r^zvT519;U!iv=>#YPHfk1J#YnLaa#> zu0>^XDD|DhHhvjG@*F;_KF+1BekZ2d#H00*)U4v`mE#2;7yZcrL;YN~LoZYeClM?o zsv78V=p#LIt2A`qZNZ`0MnAMkw=KK{iq@YvF&{Br1TjFvGwo$=?=piuuHB}^4@EBA z^IH(o6Y)5@=;eZ?b0+^P$J38~sF~m#3?87o<4%MuY_>5)0jFGOzPJOPd@Cf2<*83N zp<1tB4UJ(iXw6ulWgEt#JtsE@;n;xDyZF4rW=LWB@WsWVuuJr9h#~nVH1o85gH6Ow z^1G)Q`G9c9hxYVb0G|W;T1vy>8#nDYTZjXuy`Nh8XNMA0VJxjTY-fi?lo;GXdbbj3 zJVIh#l&3u^UpB-?$}V%=&Gz#($H8x>b6E*EF6QZbmyTcpizd0U(4g^B zIo5Q4@N=kHEr3*HfH8=Pnh8jkCH^J?u}geDm$eE|kr6FKV3#qddv+-OZ|Cm>N1;F6ZH$hS`^gBGRo`h}e-!PdM%{9Up(wOAN681(JyMwj zc?!ov)Sf;1XP=Fiu9UmdQTqsx@OffcpCYE6J>SaJQ{LsAPG_PA)}kzlm{LRU1%&cF ze}%x5sy(H>EBYJB#x5&_UfSMg{^|i!KIA~s4nyZgsO0~5PKBVoy$|+gukgFoa?vE?qkX1Q|r*3z;yBqz_ zA_ZPRCP)*OS0yxDm;8Y$XO!mMmpe5vhYBH}7-c0gDKmc}8$t9$n z>@o*tWD03XM)JLDXZ*doA+(m z({5N-N)LV=ld^6_N_1s+zv%K%h`=9x){wf-Lq)W!VkTU}kClu8+o}Yv`2@#?g@#RD zDU>Fl{jI(uyGp|_Dsq*vA)>vU#Z}Zh1i|FE3`$uuF(*MZt8mIFhBFCKiOKeByg_}f zQBz39L0-l(G}I=Nw)m9Q2;RO6c+KvUf)kNAa^Q|;P*v;4u#-Cg^Q9i_=BA@)^a&^1 z|B_;2$xPXtzK1QB63hKFWqnHIDz*_S;?Z#sTl!E16OT~|gnmCR%~WGIceI))O+~1s z*01?KzOE}q)s{$CKt*$k2tymd`%og_sJqSqri`Lnrpo$S9%m#1aQ&O3mLSJ^UMBH> zKlD2g`L*3S`f>9Yga(g>?8UrtH2r>bu}7WQeN4OAC#?%Oi_=cj5W;DD2l376b`>oo zHg(32-LxdrOQLFoUuU@jlw)4^l$82D)LY5K4WW^QIA&isrhB|4t{4~haT1xBsZDrA z;VM`8$FOHzLgRm$+bojW_UrRJ=TUYOOU>P?8WB)Oy0S7bRm6U!Dj0Gz@b7`p_D?$BQao)d&*9^ehoz<*fQUR<7na z@-tznWEKLMpSm@Pfm+WFKz;Zld|CehR79u){JHRwm*k7Vu7d_C>`O~i))C}{##fE_ z=0Eq^pWvobk0So&c4S!y@+~EYJf)xRZ@81LDJ9!Zk_z2;u9PnVB4RTk$SQRo3VcFZzS%V4_;)cX}4U_^`?H zV3^?TH-_^0%Fj*BHlCtbd5n3F$GOM)2hLJf{F@;MyK#cP2naq!0Z0Jh(S}ySmX?1RW8G07N&E%oQ*3-PGczr>+4bV7#Sn)ir3{<; zb?Mcu`AJv2WYzy1cEytJM0A!XWZz_Q9a6T~F7sB1$WX+x8U~gVd})(&=gE+u7E%k2 z?Yy6KCaUD6J*mS+Gn6~av7rqrg-@jp!_U#Cy=mkg4^CF=eipAXOiL$066rx zXCzJ20@G%s4&{VIxP^Ftf3kAyy!gb@T1z-pZ_b=~6yx13$ta2+EY^$K8=7;=8r)NO zk#oIHn{>ld3fD`4u(Cg+rhH52FNu5`)}Pp#EqK#Oe&#K7Q~ImSw?YoQ{?{pCH%;%or zuH#&zVS05#ojG&p@}z^SspZ<1ezHgQ5g5Oir$UR9Xk~$kp9QW1TLjEe~4r|d1mYJ8`PGj~7JR#w*LU$OjY^8?k|H*gImOtyuuVE__ZUr*)cYRc0aJpjskG zselSwx!;*s|J=c|xFposoa}eJMc-(RhpAa5Hc&x=`(jnotdk(q=JW@#g4&{%|5Q-e zeGN(n=R@}=;ttvX?nCYk`edfM%;S><=Psjv=V7+Zjc$C*!QAg!pq9RQf_wVxLQGmn<+ItPg^=<& z8hfdK1ynSUvXq05Y+miG8nF;y$uQ!%iP8~14vH!)hf+PlkeGCARzWkpV#%m5yNWZG zkO_kkl$GoUFWsA*;=N{^C03d21@QhCjIx^-ahdac6T9P@_scg({3VU!Au*S6p*+HI z3+E400WLN)xnB^JK%>&!4p$}j!$Kpq0JoIi>+fjs4bkK*4!QjusCw>T-R~9X2H7iV zMY%O3UwMs1=hlb3z(nuAI%vFyHy|QDOXA=Nx2jTTUb??zKs=glQjVTJs3|5^P%R=% zaVCbuxt*{qXW^z|&?^9kVR?4uOMd56_N?y1O0oapDi^02Y0r0{_W5HHsl{XWlAqWIvAez5&VO|&-X_I%`&bNA*q>k zVL7QP0gc)IT8s8(sG{Sw8{4hP7ER$=8)_zsLTW?Yd#>?Y*cdSE(PtU_Os@@rr z`h?NQUqj*y`GhyZr@RDI8+VzZS=hBH4Yv$W-ZM+HbO;rTch1YynAWT3C~gl=a z(oHNp%yzs{Nr9x#OKPtITyeG~qD=3^Ul*4%9-vds>C;BAQS%IDUHgRM)W>I9;7DjD@CQO<5b=NlSDLw@D89Nc-t;kN)mm z)!iB>&Cg=m?AXM5eUe@i>6SheGS2YmM6m?&q{!1GL=t=HEohMX|L~z;J;$Y; z2vE4NH{qVappJP4YDM)GYjfK3N14#cNjjF)(=y=FID{XvrRms^jFNocGJmgbn z0GjVq7Ztc6g@3zlo7D78JZ;j0%By0H2PDVF^mBk0Hw~2(KSh^jFaM$OiO^Vf(rpHD z%+0|xJ8AA>BXOkL4a)uON*F4I0=h>Flf*j#?am7ouRDT`+K=F3j~QvdE6>CyOkLd_ zury0zGCgk7CQbb9EAZd)E4G_wh}@r2);ELP@l_%9N8LBnsXSacew?@&vjBl?`mh$L z+(4Ve(eo@?p)zvH?=Hfik>#u@cpF$$4%c6-H@WtDETg)N-Fs;Ezt7=?&c1j9i7V8( z?&@|!m$jEzJ|f6&Ve=+C5H?`m4QN zzoFDJ_<4u9-Q}=hY>{r#J-C|M$p@U~3C0uH~W} zBFa5>10jjd$uj&O^YJLas(%9U8wHI@AHBV0shSgkHHJ^xgGVo^pzsF@YB2A>?`Feku8WWDv()$UJ4?`&p^M%4)?fpFe zaZD*Rnl5d0|6NW9tOB+AH`6Pb~6-xHgW&l6R6+%DK+!pm$k#BA8ly({fb`H1>Nvu^kCAy*+|pO^AzQVbv-BawVxL#`BWW8?Wg1@=!>kR@kS`>H>qUDOIeQ!T z7O-4O+gvYM6LXtqsm;zuT4*!d)DZOF%?{S4max`k2Z!bv)P*@VMXhb}ap=Ystt{QpiJA^=v(n>knE|`R-%m>5QDRiaE zWFyE5uur`iJk+i)X1+?*g4oAM>FY~%8zL^0Dxy-j?W&X*7upjY{V@JWG@~qaN;9M* z4*FjUkYDj3NRP-TY|?%paaI6!z6UOy27FjI;yWgYj#`^Z0NvHLvF~9JeLQs2{CzCY ziqB&xT|qg~IL7ev9++o?L`er#T59GLy@`Oc>X`%2>Vl!0L8Um3fvy9q(fBmu0)n8l6|i>i21)C z3R$y%V(l%bs)io=f%dyv-Y-z3M=A6=iMk4k>ZIMlJ;Vxp0x27y;)4h}B<^XEB-Tl# z4&XOAIU0g;GR@;5fR&7e@P^6_s1_59PxFO%#3=9i?MJgMs$Zw=+nlI5;>ft%ud(FB z?Di3LoxA--jP)R!+6E_~u4DwDPtZW8#L#I1%a&#P+ad|w^H6r7fWq9aqG^C8HMu5G}8%PF$#9J%#`sG2i^^jmxr_MLv&r=5b2&#j&Q>xBSE zGE%|*z4>~>wSHSfDKLf%1{S+Zg|l)VShJWPBnjg*kwms(~8es+EJ zY)g1pBdy8Pv)njTp_KfNFf6sde?7!mNPOLpWZP@~VnQxH*J=ILEy4F&XofWp+;7uTR7% z@g>Wx)kKdP#)97%^@$K&6_Ah;P|=dAbOld$hvJZ&}PVDf+n@K#l2XX8=V?K$YN8#36FtI|992 z8Tw%=q~qXyfpEYY5{HWIxehmWtGgF&ydawl?1)4$qrEtjbXOvGvehUV1u2 zUy7o_;XlA$OqUbezcY^^*&yF^L_#3%C_|e0BzMMY{;q?& ziEm~)N}9DtycLqECxC)*K|)Qiw7orMdD$>J+ftp@%YiT$Rbe+6u2=Znlm()>E!AS6 zUnlVyK@zJ@Tm)No29s^yTof$U6nC@+@oZXQlbgncZJ{=Sv(InV zBbwWxc;n`iV~M=fgIza0_nSmwBThvA8y@VRo{?0@tZ=S<7jkG>j^S zyRGElTkiVuKS^cPDA$P&SC;glzEs8k0alFN*`h;@FGgZIi`phq1e?=N%T6Pyl!Tk|-8cqVO+TY7TfHPC2nE zk-K~U=8}l2LOoeKJUm>Y=7sG|YLwt7C$H4+7~mPeR)-E?QWV_j9IgBqJU&dsC zpP%O)G+=mE*}riOcJI-@&qgPMbc}-g!k!Wq5hg2H=aRyMO(_xgd9luBpuj+F;xkuS zq7OgxJtLGeDI(P$6MXOC5{qul(N6u@9QH7KYL)FbWTYpp<;i9kI}dha)UCk6q)R0m z^aMVqRn4L)>=kzMMeqfCt*!>3-;%H@3s0MR~1U#PaC^sO~Z&8gt4o ziDLTMBBgaL92mkhgcJ4y;f)cBe>}kO+>_dt&AgIzHjYL0kz1bh35ydTR?h%GN^L~! zjTwpHb8$f= z27vaOew_NERZ10g3m2?tA#mRh2mb+~N3qk4Yt&NfijBeLv#+4ycfju!ULJq1d=uEb z`ft~B<+T_1{S{n0Ej9YAid^D*WhEw8Nc=3Aov>jqOJSO)7jR* zVUwX(O@l^f3HQ1euK!V;nQvF>Y`<5QQ`p}C-u5^P!52SoGFKILXQf5LP8eg=r&$fr zEttu+7|$74K+%uoi}18q2k)ly`ziCSUjp(I@xkf;77|%$LkVw2cJ0pW(Slz|fVXCK zF5Sa{ujLo@vq5<+leVpotvZ>^DA&X3Z^@#4631x3-9O zkQRx(cD-KSd%g~-@dW)6+ll5(c>khCWyI7mvi=hEw-Rgc+OwMS{He87un9u-g;kis zLn866?!Dwk5A=dtWS2|w^*i;GfN+}=5<2Es4?dgOSkUBrbqN&1^Esd0bs*xFL~vR` ztr*UAdiNm&QM*tDpv?-nUAfW=M@vpyeo`;V=tht@nQ_(FfQ3rW0+sXw=oc@i5;u)? zC;sAfzT#X@>O`yhw~?`Q4U0%|!?ksSPahv+s;-ZxbP|A@@3~(fkyV z2WZ}i=hg-*KU5WHe65g@$w`WedY6H64Tg`9+h z6PW<%OJAGbToRDNa-n62DGEo1r=iP(5ka>jME1b8%@b4;BqXM8hAD`yPLttec2OFJ z;57U`I?M-yv2$y5maoxwqNV9@f^ilB{Iy-pLm~r&Q#hVNYWh4v{U^N2Z7tBQ=-Laj z1e>iIS7uXZx7nB7STXVWzUk#z^r^uzTNMS)qe`JSElT0p6AN`NmQH*hI?Y8!w~(h< zn5kEGM&}H<3@W3+{8f~MTD>S07dIolw7{-06>>AO@MwV!lxTl)R z$X<8~SXER)M8%bVq_$%Kp_`k_Lclz9bKQKb8@jl$-vshsS(IC9GNkv$qwDBVki(^{ z&{7aiM6}Xdlk^SXmIQ(!EJb{LIm8h4wc`g*4ONDgE*G)E2>nbs%*G2F1Z!w(8w=&2 zx>C#cs3w53ZZW_QZcJN7LXvl`Fn4K8>tpS^4$C+A@N4dJ`3W}cIEQ7=ZSs@l2r%bk zW*_uH-ph&NPeK#xXgflr%zXh$40`Pjs8BY6xldabfPz$j)WWkVVn+316$LDxiDb|gaI z$RO`KA$lAU8tEp8{ni#EQEljNIZa3bqt4 zUrtvdm+wiqKQFScSS%y!xtd( zP-eVpuq92~361d{Kz+xGN=Au;4Z5z08l$VG$Ko273jD%EiVNO+5<7l)XnoKb1KVRc{|dvTup^eA#jt$u*?Kd> z(cQ(ZzWjR5MgG0rhTgUq85oXWHKT@WcdLKzmHYlkTS8 z*{?92l^Ap*jQPWd?|IOnYWRy)2K}Y4rLX24avrZ>W?JMpg7!##dleMwWLpL)B4hmb zhunh9V!7<}H^4?T@yRo@Sw zOTG%LZq^d#ZuCKvksu=<(9u+QTg!8K_Sd`u5%=&7cURS$^TN-yu=>za>jyG53txnIk1ApZ%+|uO?%U zIDo7`1mdcQh2Rztr+L|9@ZA7iYEtklt<*3r%2a(NeU=-3(L+p8hXD`3AjO5NS!kG2 zTW4DuJ%M5)iziZk<=?loj5-<7te=q+q|a;CkBc!3t|~Qe-pm zyzlu=CVf8!;`R{?4sADU?p;y@+_33|kvI5s(zHyO(iKm^9oN~QO;xgDSl2g+Nn><( z)OP&Ot~}h`D^;g8S6$!Cd8%z6D?sG0-{M?VLGF01!c;X?bSb&uIZ9gXpeBETUg__? zGzYIcK2@f^avoYDJ)-zAu6A8X0tPS|KbH9Z$P-*bm4C^q8FTY3^n%SW-yW^jF(%C)^WK1Aa zA@qT!ieWVN{d0L@(Ag8L2W?WK}zuCAP_cqbbd4|e~Z zV~7cYaDn|ixgY_%ag6d z4((F!|36`UJ4|V3PdIJXd?TRL3!40YbJY{*KJo86cw)@ffWDFX5Q3+>u+?K!i{DTy zq^I3WG{uTm%QyA6&Wm@@P{c=W{5cpe;eUXo)O;5s z_fNXEG=@H!s}h#zcCN!unMZuZm9LrS(}D;XS))_}t%r{%IZKpU+GZF` z-vU0kIcTF&FoJHQ;Sv>2aRoQ1OcspV<8ozzf;DzLwx&8;((7+K0`GdoPHO$hElu)AS<-3?( ze$JkLUCG0ZQGMd8J*BFQmytIs6!K0VKk6essb(()KrbhNRgIYavaET@yeHBrpQ6Wx z!F$?mzLl?1-#C_geZ+;Sy#_?T-*~s%%6C6TR)!|oS}m?WD{#?%STApR(HXccHlnF! zd+Z^$%dEG&q?;nOZurVp{5JWb#RyE^U3cl`?xb2R!1xdtzb_dz18f^(KLWn-7ox^G zHbce`-x-W0z;yP0zBa8vsxe2#A-9&X0?my z8hk$_eoQdUXMr`J?jhMQs2BGr_y?^PJOp-J;HyZ^{DJ%p;D}WB?ls83656U}r}Njp zscK`LjZfV)MLIzhx+h7rIa#8j!EuH_D|HgUtK0x>OJ5e^tPSs)N|{5$h2{xS+RLlu z*07hfDd}Hia!1uJ^0tB~a7XyTn#}Js-jUHf6kz>ichoubOxxv3=}}}&(z3`M>E%-@ zM|97X&YDd1^EQkUj>!4XO~<<`!Y z_O5nF^v@|fEkz72K*Q)!A)JE2)};P_3g(rG$h;U6d+ieH~0*_zeHm$LHHlPj?+TiScU8 z_&3<;w3>WtcN4TYEcrY_HJ6{;Y26~C22agq0XDXf=pvER+9I2^lRd+6br1%?cj$Y+ z=w3wy-;2Vz16(xT+L`Ir@l7(keRSJpA@NsTg@~N*l0B&tEp*k-9m?xyamen6`VNR? zc}EdQ1Q@NM3BA}oMtX*l`~R8-J$sWPZwC?`gU=0i-+fCUG*qE!sG5C= z@vbw~FGyyHAKv#6!V;4zzzMj>(4DvTaj=HUbo+PyK*&a`LlCvp3CyQ(R_rHYW|c&` zeM^IUJik|M8Ng6_OQemEzUIN&%OPB;S2t=+E0Y0N$Z}`-7$$v?pHWX3*z9araW5yF z9A4u;9&2=TG=uioT6;uW#bW5~T{OPMVY>?}N!8jg3f7f^mW}f)anvKY)~ScvVK3fR z-SCueTcD4-+G(3>XYYfIF-~yOPfl>{Z|M>&A3bt~(b4m~9~%eZcMPrzBSEnjZxCTF zqDo{dP(QL~nSnlR)sUg3h6VXuZsTy9dTJipa%MS*>(6`Q~^*#YU<} zUm62e=3S|we!i^BqOkm18tow!2mb%+v0%gpZ(WO%!5S$%;^D_tx?=MGk?NSf?`>v)Q{dSwJ*L^@T!+( z*!$>}O_6Uy-?bP^*5iL5%$QdaYAnZg80B*nihm==yVA?Q7>wZ-hifp{2#wXAFNL)G zU>w;+leU;; z{qIhULmZ8$`rVP;F3=MwSIq=DjZ1DF*TC;Y1He(CdFo*Q2YED8sZr~r2`2dey#sZ- zU^=M)thjT>&lZWjR6ef0H%GmX-BtQU2&;NKMqs9e+5ZDz4MgedL(c7A2%W0}PwKQS zsP=E45)}bkS9z6Yejc2e6>=XiqmZvgd6VSaLWPcJw(VLg*>&Hj(uWvq%NM={v6`1S z#!*Fz?pw9hiO-9`lnqGDQypfxf2-2Uxn-U4u|3~g+n+0 zW)byx?cUyXHN}s1G+6bt(qCc`=-~!+KgVn>?qm<DZp=^2mtRe$|6jS{2Z7O%kw;1N!$5q!H= zK^2}w>2?$WYpS#gCkxCQLf0_aut&B0Cz4@##k0CBbtmb6b8kdZvM1tblj5BAljM;a ziF>zUv1yC^%JkYIN4mEW4`VhtuHwPF?U=Cl3;dX|jO&3@+~2M1)8+omEFiz7wUF5U zT+t1lQz0g;WP@x|2+!{?$TF89g~Le~y1G)9lnPx)v@8P$A_g;&c`)3zCsqFc>f0pw zB7V3R;F!lKvi&$G6suO1oQD}KpP%)KP~Or~Cb_CUU&c)B@vlF5phfyK`PB&`o^1OF z6!zvHz7wC&*hp3|D%`6z5INVZ4NE4##})#wr^yNoVSz?EUbY9+5l&N^>}1c$qClthEen zDXW=JXac7Hs=I5L-|V3G%sln0#J*2r;+lVWT8RITK%sjg+Lj&KLEd%G44UZq8~rQ1 z)$+FU7*THOSp%^y4UnP!?WQ=HR%7!^f_(NU0tp5DO?#*nD!VC2@XYrKad8r12BQB5 zILJwUK!JsBrlICUgUy+&nb;SaVgCW@LNcPpfX=14zP^6i)w}vdtw`LREA{+(&DT>W)kxCaiUBg~O;-gW;PO!Wi>RCl$NtD?DR|Zk z!kkU45bhCNWVOS!$`GIm@3gdbe_XyPomFzjK9o5KwG``d{Czs4wqVZ4$Dp`xjn)FT zrF+iX-jpIzkLE@lS=X0$JI+@Gw1{QEIDk+>C7kO-9>%qSKYluKTv5BAMQ$xp@}G^b zGmKRVU=NO|Y8kJ68FE5CbFN|a1XR@xV%Ni!bI(-6=cdmL(s`E3EgAG=n!jg}z-Q;@ z{xi+}6kjbesm(*$6Ey;q*}Vkj*C)Uf*L+udlW~IVnfsO=Waat>@)p+EH4f(#AUraP zW;`*4QK0-!+vdspzkV>_(4)~LO%%{7+G55r43MIV zL~L$;-4Bc=R2(mfS^zZOk@bx|@{wnIbQoIjnQvEmM76DJIjaco7A@Yhf$3FK{$6LA zCX&Y#TBJw<5XSan0DRAmob2XV7qe^Ary0R*0g(&zVd}85;(x`SjvruWCLdSRxi+m; zf3}Ny949RKfUK}YZl|;sE}S@J$2uDX@{GVN)xdz z$UPS9pAne*$qnh#j!Kn0?1|5FmZ6wEWXZ+Ju5wy&_{pQYg_$0NRj{8WP-8Lmxbg8X zaa+HL?vUF5YGs8N_B3QIIo5G}33JMI?6)*|R6s+6Cs^9rV#ntQq>nYBtI2=Z&tWD- zV$Aw{@|Badp!tkN>Oj}`sECcX7Fa9S~@bD@5NOB+BHtp&gg?fTGZ)bjj7 z7HJB($w0V$eDpXT7S^!);Qk?{uNl%O!!y}q6wWiTAb28HneaF9VH5!jPrwsRP!)H| z{@)F4V63usax*ao>9J=~s^qCLo1XO{6?Kz*|1E-L$Gc3{dqc5q>!UnNsj?2iNZ@T^^1)%=89kfB_}U+LNec{1eR@{XZCB6yxvI;E?}T~7mm=;E)AzeLmlt!TBv?!1U(+ zBOhQtkE|qJ@Ic->+aW|nF~=HhA(XXrxY*XI!ccF5)-X0{nE3Z^2dq4okf*Fh?A%(& z!UQt@2=Kf^N4wwc#P)WI2%j%yw6W;kS`aaq^@K!2&wy;VIsFtFi9%M!qJ2MP$l3gI zvMa@v%hFTu@2zoOyUW2b?{|9kQVFE~H;+TGXsoE6Ag!MJ=sHOK+0FR(r*ErAdl@|H z_agb&n~sYg2>X(8$xh(eQHK1z_O@c(8~aUP$3)!(ZFW7>Xi574A)|j+-WBmZ_HDJ5ExTweyInaX+Y@v&v}>Z%D7rQ^hG-y0|DteM1R71Ei%J*NzLTXk-G_#! zP@Ua~$I^r9u0eWsZHRFER+vU7?Ye!GQblmAj((o?OU$S*zEMIoLt{_+kfkc5=p9zT zmEVfCeaY&v%a?Q)A0@t8-uS`LkxDYr05sy%Dnq%c!)?^zPhLX+pN%sH(j0C64sOuY zO>Q4$q4VTvFlvC%#)VD?w$2vWZhN0)jN3tOQv^0S?vAr-@6OXKysLr9q0BY5N8rZN zS$^_0eWam}!lm!NHWpFfdNyYnS#yLqrj>M1hM_~kDD@U3zmp)*Y0yfDV$=*k17-pK z_^X%I)$YWCHCEWX%x)AQZp|xKf=*6Z)$1l~r@m-WKh9#+BhPeYgF;off>8V6L)>y+ zh#!R)<61!3+O~u9hR}A9Xdr*0R~hwLyw`wKbo$iLd8U}Y@AYMT9~@xM#9SWEy{eYk z+ho(G@DiQ$d{658dv5U`AW=I%O4#omyN4_(3HQG|2lq{Jo0&uOS3C0g9_A~wJe6;t z??)k92dOuv6#r!HZ3mw^cN!oTZ|MzSvJ-~5z2}hUCG?%0ARdMwbq#Hs5@h<25S~k< zxel(^=T})3a=OmlOY%I2y$Qz1Fhy)WjhH5R&Hl1kW`sLUSrG~~T3Z%bA}khL@gHim zHt?4E|5KXTz$;A3 zkTn*G?qbFf%}$Z(TdT`G(|nl} z{YyuQ+>$Pc`MW_T1#dx$`*+>KU|kJpBa~XShKOohB)@T4FN@mmqy+HU>nu! za35*9!0F@902RRNkd;))2mo@`-PM-B{SdFX?ThvP=mu$l%|M)fad{nPD{xKd=B`GH z=NcuLAmOC>Mx0q_IB9HetjUcJJ1P`>_aPxa>7RZ6wOk#)v5vll)1CK!058Nl1bKhI z`)c9)W?LnDqIqy-8y>%TOKgjP~&*z z^g)}ESX~}e_sJ!zMu@|<#1jHqD1F*zVyDF|O&u@(uCd<@t)xFtW^!(JcB-MK=YDH# zO&+YLKQnSlp5T6Dtkc)W^kMojBU0a!lWvONV0Zbe}zcvXPtR?lw zy6qR7W>eQX>pPVsK4`qXC->`xtTP95;T7+G8Xea28gcrv&_a%~SObK7`t*KhbTWP3 z!3Ay*cDNHCju*#lx?BC11>O0JRj6Y0^Fgx^dg6PgJw+%)Xc{rAy4W~ zC}+O$>kD7mTboeuBK(9jT3Cc7Jc(5xvWcLd~y76p56iv7Y zrw@C;%sw-M2c;vfSF>S?^TY$YB zIK`LzSHQrtKL-4&9JrrJPZKrA3J`CVTDm(RZTXWt1|Z8=hqwX(?i7Uny_K!Sh0B_q zMRum?(&#k-&`TO`EW`DM-Igz>nVfv$2nKKTmZ}yT*OOm`jC2JxP^UmC>lxxFb)M zT58DXh*;?hq@!tJ8FS*OJLf%z2#v-nFaeDM2cGrs@bEt0DL{1`^&C7YbrZNP(wLBI zAKBBU(;A1Pkca;tAo+dAOSL^b2KeKLH@Q~7fLJ?q&qBaK$m!PWbpm35(C&?a(%8Pb zs0kY~;B{|Ks_vCzNvL^z#I@sYAs|T0-K|63yk>j5?M<%6CIy%>t}9ARJzcqFn4Qak z|IIt$%8QZ5TfAVghqBq;wtQ+ZB?9(%Jz^p$W;@hd)q7e|Qha}RS=%d9+_+H7@zJrK zHj#wH(En&X5L}Fu5O!6~W4pXUvJ9OsCXY4!#keU+9)U{+*Wk8<=cGSE-NeoofRm+k z4&X>6Qj=P}c8JeKt+gR6>NA#-+;?yWJ*mSA!YOWVL+j#M38X6#uG~a5O3tCUr+BCw zHO^Mu7-sFhZ{E_Ia)1)RGKnhE2_sdV{WQ;axeR16m4K5mL}QGf1VnPYN>Kbb#8(ts zUO0Yy)e^~UyHNHCwMc-+X&EPXnR?57JfhfbW%j_>!FX}Ft;(y2eAziZ zbM^6szM<+-*l(kzJ;8OW82M^*yymU#Eh>ESy(^;Jg`-5%H`d+P$@b*P(QWe za{4q|Hfl?j*qpF~)o~hKZiQ{p+tm5noLIX#dOGUbHvBN#(O=8G{nuU)BQG1Rg;!3- zl=Ie7E38t}t|@d)yo3Q)-Nz`?2^N9q6CJoKw8^Fcq=*oA%J*B!3RxQhJT*Brb`+_kq}=vQ_*i8%8@tH$BrPk1{zIuzwdz{4~d7Lm6^a)o?9a z>I>)OiEYJCc^CmbdJ+N7FSj^%(fJeMfVyJv{#VJAVNyZt)ktYv3#A~7haFVTI`AY< zO=m$sXX7hJ|9H*~>)`b}Gw(4gtWwuViTpM)LW>r{iC-j62v zSK%t2ayZ1NWf_u3Ux+ryXN#bE9<>9$HC*y7$DEw(tMW#V=d-}rs8Ge#VPeW$f*jJ6 zHA^{(t$U(7eHID0y@yhDk=kMQEpC@&&&FB=wb0ZB(ZmVt=UF63G}edGgLVY%(KN|F zys)d|C*300Mt?xXXR?Nm;O~SlLgetcny*gI{;{2y!Oj#uLBXPg_YBq01+e(mj@;7O zp@bcjhm3y2xOP|!XAUmM5rRAZ+3(>-_PG6OY6X(8zuPOi9$rwrS&usgn#IBw;xUt* zz~Fpm=b&xk{5|4CwU(3zM4mCq&80VjRbA?zd>afwt^UN7$AgY3SYHkIDn^*7Qv=<9 zlmA^jFZVu`UBd8jR_XaN7z6>Cs=jarU7sA^6MtTU>+$abq#0Xste;kZf!S~yu~GO7 zE`c|mF@;Z5sJY961bcoeJmDp(cH_f^D!~&6PS8TJT3`N79`DwPR^Ydv2|PEeXP1nv zLEVID;&1opwU-3p9ZDQu8E83+F_|bSux>9C5A^6dcQ|dzd|K$?6Cpf2LPv7jwjVBD zlN>>kvn@&wrj$jDgD+X(b#vc~V*Y13V6j246)NUaL*teu(q&oWu=Ng71X~+IoBMBm zUnC`r!VQd(d-_G4i8v@%N8wKVtCA$2=*L^Jgf0+XZ&aJ+Q)g|BGdG2n(jT?oJDVEn z9|AEK#Ac2Yf7L!AN!iC1SI>~z)K1fAxb&!+6u?tI*fJMtn3g?kz_chOnOAV_xw6+A z=i=_wO5{18GP`3>hq{wv>|-z!)_(vEZ)(l|Hw<2wPS5NHk*phkU4I9OXNhh96St8j z-%efX_~g222nLkwccq9lfOmZb*c(_zqsC>ec)`D=y130wT;@9r?d^x*Hetqi4t&*Y zvMkq^-%8}?Lm1LB-cB}IS7jil42I%-E4kle##z9>!3&)Zq^X%&HWh5hy&m{`n;m(w?j#EQee+b zLx+W`Jd6Wnay;dYLr8lW@Nz{)!b* zx386fyO%Sf3xTc0w7v9YO>yBw0E4@+NWd_-(79_)V$IsHU&6WnzqZ zFh>xh>orrYBPCXDYiDK_g(?s*r6nt&FOX+bMmY1T^2jmbW#WOx^=KuykwRULM_*5R zN-GU){`x~#7SL;VhaYM3%8^1=vH%`&P3!uyd=E2VwmJh6Q$;@l!HR;nIpO%NHSwv3 zkEv&y`WCc%hg*5Vd!*HUp@p4PKE$f39qpZjEmJ?zLl|xLa88ClQ&J}c|NQ{qJZEgr zTH5Q*+MrGKk0v$x!u@DSa}76k)|z)ivX(tKutwGUfbcEYzAGzBhPrTRZ_4sS`F9IJ z=V2YE9n1v4J(GmW-MRGKCFHqQZG%M9V&bNI5ikqxi+eZhQ zdx17onPBCL0N@gP;o{DMWt(hw<_FNu8>2d05t=Xa$7Zp| zvM=v=apr6faHu7MyuRj`XIC7j|ILEMM*Ku))L)oLD%1D1rj&1?7byJ)L4`S;&Cu7W zW*;6cl&uE}6>GM3b~fMC)US;jpM0q%bqoF_Pf`Fh)`9z3PuLe`~TbnYv!ypw2D3LbhNDcZjxHfY`^iqE&3StS~Tb><0#S;BLp)`Dv( zA38`yu^0?a_Oc)#75+T%A}d(-C_|A*hAo zNS&xQp0U=|_)olJkV&~p$%~AG%c*NipVFu9{cLK#&v%ZJu;yUpSiZPvOED=rJH%~7Sk0@{v)D+>Lnl%lF7`8 zPQMi2EP$(#3}2HxMJ4@b&(W&BG%@D@)|$0&h;VLqSjO!I5}$W`Ob%9lHYs(k>i>{j zv(o=Va=NmB_Isvo;lq>7Y1F(!o1JKv_I=YT5m#k^RK~0gbOC5CP8S+5}P^ zwnsQEi%-11l65m_*eLE8|BuZ{Oz_Vc=yyXNdH6R5CwMRQ4p?q7!Q)5EqS5`SBf01%$X&ymbeLzcgk=J z{toe-Df|x>>LbB5}4S>U)L$cNX!f=|P$L|6}Q_qS|cOW*xk^ z6nA$hPH-qK?(R_B-6>uuE};aM;uhT9-QA(MyA`MfcHabkJP2lffpHI6RbTUlA}~^^^STm+mAARY$Ze$$YRzAP)>m4J(9A zKrxtxRh6=y0N|=h`vMN2V}1KV^66SR?B!)^x}QaTjNx~4F9KoGkG^}93_Kjw+ZnOd z-yzq#vx~pWL;dQe?Z0L-^&*n}DNK)81CE$PB4S$IQ;W6VS@OCf?jOKMDZ!)@uKl|% z48T{VK(u+03H%}bZ3s2l$1f?m9dGMNQU=_CV?b%zcd>MknOF^8{FZsqRM^ zFB?evLp!pN9Ma9HvJIJNq;U@q_O)2;f^?`_BGEPDCZke?Q5GSP(~zGtD)V%kETmjp4_F6)i1U3YZO`l%m*lDio$kb^J2fY=3qztG)_@wG@GYc zhI~#oI5>P1t2nOGhv6x}vi(v;)Vvf+X|Zj?dzf;76mpYkrrcvR0**G*>*y!eO8X{>D9Vu5i zTF+gc-?MzEJSWOVmS7wYbLEcvVbws{+A26w|AOkDXmX3bd4+i6jD=Ag=LSX8co89y zYAUiQDl!l2(@iW)jq8kfFeQ#K2eA3Ar6-yQm2#4mFK?sEy-!VR88*b!gPi zrO#g6{JC_zAl~n@PwSBhIx5Kp}luwGm!_Mc)t3;Vsc{{xUbGeU26N5>lVZOA;QR#Eyd<%>Rg z%3Obfzcn9PcN4-@zh`O=4y$Rv`k~|(G#0G7JCw7vZe~73JIYE-0j#o9r#h`+^kr)V zyBA^rTOYm$Gnw^T0f&@2o)?->`p{s=oNXf;Is~^?-#52Rv3yL&r8v9(=S#_#LB+~I z=!#LkFos6$PnJw9-xw%k!+94^X-utd9&ACH zV1UNC(dO%n^d;QT>yrkPrgE71oQbZN;7YrTjJLiPFHiVzI5Fe0_h{5~-@yj4N=?p` zCLp*XZWmLM|1HyVC_JxPML7QlSVIHV4SxSk0scv-B)Gd+RNE%M#^|_S-u_SZP2nbF;15o_3v&146@QvAGkt5qsVVpGW`q)P4I z(1hK>xSihD*v%r#Y@7=fw99Wp+jfNukb9EIbK=n(A@5nmC6sHY+mF+}+Cn=-o2VrL zx;o7?*uOFLL?@$jOMWtBNsri zl5+gIG4_Q09e2()0BM{wk}&ZQ{v-Xt0Wcl!OIoMp7YKBsJ@*)Gj)RdhbY&KxLqr;c|V&c#>s^it- zPF~KJI22K3Gro~p=zb(4$yN#+>V&I5HyYFAr=AStSd;tq%YhP#MNQzoFR5&hh1_Sz z!xXQ};`O%i&c<&H)LWt7zt>06wbpQ-;CtoRHOHSpb0n_uKT@2BCWUqz_*EJj=UMj} z+QJw@Bz{U0A$9O;+T9k9y`?+^HoEM;|m~-j=-<-p!v4YhG0Tq8S^Usn?cO! z{$yX#;?$ub(8|Vce!suG_bo0|(S&V*OWzXr<9v*^UB01DtFys=9-Yhi+Utwnwr=8{F0qtQ%{R#B=R6g%PU(;VF_;$Wv zMK_cUK_?xr*nNNT)3~l=>9P~~!s8nwS%m&$axU<3#}lO$`O3%x-ah&ChSKQ4iJgE$ zRY4<`Y^w$e%6Qj?*sg|$9ix*2ZDX_ewG2o1;><`qrK>bxkuK?kdpVLPG<_W~(`JH}8_d23*o6o=+-?oSM!W9;voy5sJz6WhuB>HQKIgv!MYF-C)8H zgZP}P=rW}XRt0X!#KFoJ#a$g9t>2@`Dswz_+QB%Gf?CcIYvYR$zdzlt$dx2=5rgK= zUIsubOVRG6XE^-_ZG`Vs5Jei?k0bC{HDW$}j+B1E69DVKmN13hDe5x}0*%^0q^#+& zpukM4BXrsAv8Job7!Py|A7okCL@$@y(mw3>o7b(NGGfS;J_M=%X9PRV3)zJbsoUS1 zz{~WM!7(~;X`wfm+*}QQz?Yk9b@!U^6{ZM5j8KP+q@Tb#>WlvS8rBdAMI_+W=aspZ zgA#j~x($<9k__r%Rd__Z9K0n5Sx$OMQc~=6L0tHbz8TYIK7B`f_MrG(nU3i`sqn=& zZ@RDm5!@Q5`c*JPUK|7W#DWnz!aS=ggHSj@huhCa1U;joFcucUs;SKqi@W(uz$U1L z8Wh{icvEi<24eRw&F1--eV03g*{Xi;3Ul<%=t;jQFH`;wl5i&cgC)ACd6qBia(^#! zI`wjEC>>J4eotobqqR9?6y`u_Ms6f=#T)toJD4Z8nnK`@QPtxMXU(_7PcU6;%$3mR zc*)LrBn_YG4*yW;%O}NgOR>y&OHbCy!Q-3tZ}Y@Ca`PX5RA6Oj(?>cK)tL3M|8!v} zmuyN4B zW01}sf111yDr3t2d0kg(# zZ8}!?-?;rX4Wh4$7m@Z|4zrXFGi~B>G9kP`!ScObEL|PyhJG+1#_t>S*M07p-a{k< zLK$Cm4j(0vy?1O3HIl`hb)Hc+=3=JoNK>$UxT?pb+dSuvv+vU^+-yHB4vkMNPH~&S z|8bkoUa0Z#vntZf$QS`LY6R M6`a*_u%#N73*^{irb6^?@r=hT~advI5UCu|o#h&vM%(9?wM6E>#uFb@Wd>SM5_6KRIfq zGy1T0!^-aFZbS8C6{LQRsmh67$Kj9RkC1qNb>)G*ESP zH+V|#Q>7CnXu*LsV3sbGcH-a%R?v{Z zutR+rYtz?H2HQy^3swe53G9k+_v9j1nuA$n3qw8%mxO^Rd%UVi*_Gi$xD{*DckCF= z+nVs_Y7xC9e=aLK^o6P#+b#g>%sf0e|C-9;y(wYpnu~C)bY~ zvy0ca-7{u=l2Zq{L6S9D;W3|-?@slxeMdeexeFDQ4e}5^qNa`2Fq;IXUc`M@mpEzr zY4}GqMZC<}9?TprD)VS(!!sn*q&bF|Io86K^g(1Nwt$DonHJ68h27mGi_7=mpAl{fa1BtKWpoiFlA0%A8oaAcq>U%E9#U|wtYRN z=a}zOBEgovyh7J23)By{@$^x>1(SEl1*DX%oC<#TTEt0nC}71N#hXM%3V}I6=Qza= zTw{>IN%Ez-9rsg$wIZ5Q>L`KrYhehVgziOsR47q!!C&jB>7KIBzQ@R6TVM5PPnoVD zPzV|$=G%s>!)<1i+u^6vg&J)Qn+5AInH0v!c5l0FLN2DDvMj59HPlu+(!~i!w{ogZ zrV1P&>d@DSDHpHaJa3vltfSw@=^o-4JVs?8 zcz-(YDo`|4v9fl`_pII)UH-!=){_(dlR>75I}eQQiR>iy^&s!o&)FXvQ=f3>`g_@I zjl0^wQ&Lef4n}{X8JP$LD3}g|Y@JZI6#eK%z_a?M862e8ZB-?>*(Qd31dc!A-w+{3 zAeISE^-P5K`q@BD-+ut@k9Mac`bPf%G>$#@aDhG#1;Gw*pH}2>3}U{ob&)5ty{1Qv zS@YaAd5?D+q@{+?TsD!tHz357qc0Zvn3QsjS=EhODzHF#H6q6zhL-4575&%a{{XgG zChEkFtID4@L)v#2J{e}j*GxQc616OUuj0ROJkRu;kTzL@6!&|;N3uV}^L&vt+*~W{1b1r+jGq0PV~arl)fNRKbi=~8r_Ev!iUtkdZH z@6bdSG{_nittObW$|l;~2tiIFpf+7=46KWTGW)+Qe)D%#WR!5Gm-*3Y*|(qI2X`u4 zeo}L+HReLsF@7@3?9dc3+$S(yx*coA0`db_&g#yA3O%ObcAAX+q{40JP0x%p7 z73&Mqo%Gj++u~Vvx07`+uV3HS?IRN8?0EyeyTi;+P*Ucp|XJ0Btw#U6bJ_<W*H?Sk;Y|HR6SBRjt@h;(R z*K~zPbC=Hp6CfcpYep1CtSo1;c^IHLgE%Z1%936?FS_DU;=QG&hQqyYGoAEmh$xyfo}@1-*qNc**>F{v{bJtC{HV}D z6XOc=DnN6rvbwr<;ycgh{IyGJx?3f*V9p9fWJGLfvDWb*`m+q?D@_0?=;6v~{?iAr zg@`<9>h3d!PQ1NWiN}ZiVAi`%J@0v*A+i5VM6tA?KZ*pXkiWw`Iqh?IK}#PwpeEu! zz&QfImrc2NXIGcstx=8g5hv*gQTa3~@z-}N*F=%Z6l8MEObO+-#F2Mnh|fVjCCL59 z$0S4YQs+l)Hv@sELerr&-kmXvtukG-fti z3o$(&a60x(Bne9$L<@32lcw}lLHwJ|f-1m%I2=W{{+9^&tSwob$XlTf?~cQ00xeRB zM4Z`iZD?w+;E}`u7)l|9?jaim$st3;`)P3i0Q7jmH|f{n#BP>8H4?&>N2Cz+)I$22 zUnFw8bbW&P;8d-MX56VRkSrf?=K48ay?d&qSjTAX1mDGQwZ)r`NQzmT=E$e0@C;JH z8&R7xqVs*RO<1})6P_HJbeX%(MO}vX>M3ir%z4W&1$WuDwld3d8_IS{jZ87b7xHVo z&%96mvY}r#y57&o+B8zm+8byaeQ<4a0ZZ+Ml1~LxHEukLUXQxMNw~5XpQJg<17x2_y;8T(4}?a zmLXs9TmY_#Cu|TC-Cb3Mtl0xY^>E=dBP@{Tl)nI)c>XhLottHUM5`H8S;SzG^CC@L362+-OeMkl3gTUaPtGFJ5E zxkBZuudBHXGIRSCm+y7V%QRqBGjdT|n*;89^;?z&tGB`-;iTZ>pzYibmvBJLA-rWN ziT>1iRl{3H=fIwi>C`CUR-4d&eFw$`o-sw!p0g^|Y$Rq~&Cx@6^8D<)piiWlLW)we zZx(j)5eHDVSHkbfB{GS}auGy<61H;)L>099;kTCQ8I5>u&54rGG=dMW@+a;8OvJhW znTVze7%>}>XN(I4UGYk3^~0v%E6j}oNQ3N@+Z(e_695TEh8a#k|+VMFNa+4v!5MYYKGNx9UNI^4n-XX`YCWJ^cJX`>^Q^-UzwN@+*;3 zzMDQ{D&PLS&8AE|KMX398|cH_C>0nK5e(p63boOk-x;T2kZ8Wc|DtmS8JwvBs33iN zv<0UL4i&GVpHvYe(1853WOFa)_>St!jz6jl(8`o@e;+T5 zpSZo-ec5c7`#IabyS_6}`JIP$b12u~)U%OWXMonNYt48pGB2hYiD-o8zi182z)MR} z_^d8l?#q|aA4B-(ZEMvd#~M5T@F^yhzmVuRl3mP*vk{pBaKY-Car??tk3x}nc*Q&0EZJm;oU znlIvYDdT)|gceV_&V40&Xz#cwf?)%l}>S&D^as1xs;|H7CtQgqk7Wi7Jqg@?v(ZbQE48Hkf>AwEC+(BmK?5V>Y#NExy(5X-SD}RqMjdRP#^3kVKJehImG_ zefP+-woRU)Pr6CGnDCbv3Z;d8u9Mm0BQz>`F(fYu!{Q*zwwCIa&ejyyF-n;wYXAai z&JsnK$4)VU-1u#^doihG`bw5mlAlY7&CG_uimU|@FValnzvIw$#C{TmDMzNZYP zq!#FWyAhsj7P~>L5MXC)DDQrKj1PelohLHSjpfdH(iVk;Sn_X4khK=I9c9Cn5dEFE z1K^jC3i|ddf<_{l9oFU@tu0CN+Ts1DYd=ek$MB$`(jxRyYz^2-wmfO-apb|o zCG~OZclZQ&#tQtr^*Et(4H`2mu`!|xveX#L){Y(jY4;9qc7^wu#k)!AeR!!#69$_* zdN}C)lvG9xZt9OFb|@pw@5-^k>VXn#e7$j68Spr2lN)Z3+jG^a!PizF8B-)7Or*7v zH+wV(V)NMb%{7Z(;vh;}(m&_~h)h@A(riG=} zm{=)csMy;|S*;hVaKX1OF^s}UR!qgt|7%syD-|s$*`|AoUTnYMhjae2+1+DB7vk}( ztzhy}q|=~`CnwXzVWmjWcHn(kWtFF}?oM*`da>*rGU!5LR{HKa@IwX3k$n`tm|e}x z!Tce{^Fs?gwdy07d+zlO29og@-)lsyPvWX~nA&4htJHVklotYceo;H7yBCoP#Fm4l z{)mxX$&tI8BHE4iPI$shhKK+yaK!$BKTh}E;o2Hp8D^MI0`pX=eQ@78qd?JL?jrE| zq3m`VH}>w&B2qcgnd9adc{{Gb{Y-gC5jnK4ho$@}>ea;uD|vVBd_LS_2nYmFxFzYl zQ_Vy6t`(mB3*;IfW?|4`HN zd~uYy*{IbAUPeKD$^QX#!WYP}@KHM^@m$46M1!<4r$`+MM;_#dMXfC~-}+CnP<~5a z<9jeLL;*_uQAX(M6~)#Zbjl>W9zR5J$X9OWgD>A!&E+i8_P&jAn*E(4(mv--vTwZU zjdnb#YWvkJX?1qv&9C(CA)80Tj)KR6vcrp ztpCUEH|J*Z_9ds{uMJ4JF#bHJ`WfYZX}>YqYUt^m{xFmdLF}aj@Sr`xt*;{EOv5`t0V*jZySOr!t<_>YJV;hUx}d)P0Bl=|MImB!9=1iuWGUSv#-jhNk=Tx7?K-?jDWC!Q>5 zjOK~eP)KA_@RVGr(mdqeK@j!Dn0q+Qiz*QXM>HHlItPuDq5Ao*u7iInS=7o%M)xuH zi3V&dbqGu~(AVJ?ie}FoYjf%wf(>Mu9RcQ6@kN1CywtW@uC`puh4YGDIN{!sAt#uw zg3kdS7LFPfc;zhB#seM8bh8GAvAM*XXV zH7JIZd*0nY60@xBW3q(!V8cGrx>YfqWUVL(RMq zO<1c&2B>K`+?28bmV-(gP#rH(dZ)-+ahNjR2KEGTHg_puIxUvl5<3(QLZC@13sH?! z_)O=q_^M6b6)#fl(nH2U9TtA~uJPmgVd$?koWH*MvJX?%w9BWU78>+3-$X;YdK)JP zQfv#e*w2hmpmBGlTc68-6W%!Ab%9MnkE%2G9Pkyv_UOtM|JgfUy)EwK(2eYvyeH;L zY?xxPg_Co??80mNp!hRepcYRzz#L{Ox9l+m{J?kV;>9J2V&)Fw&?ExxrI)QLI6#WZ z9NC5YBl@YfUMj2v)=t$oSD^b{RZd*l0xI%HqMpt>&xJHg+ML3ts60dzD3 zKl6dX8Z*6lUAy@nuLN5awqzC14KRUG8P3OrnK-FEp;%4$ikIGzloY^GUk36LaU5d;TEwcw`}=U?DQ9E#n{L7D-quFq)n1aC&x1PL{fU&K$j=^Df4l-DN9hv8@BHPx5fS z3b!4S_<`mk{?cFBcITc%-LBk7FX!GZ+{o`Bh-OCPG#g`)Co`1R`V(989`*>_4K%4& ze^;8+-wEH+@aw>v<~Bt*YnZR=pip@}{os|#ch#uHdVE=xDj3QVGmAe!I@R}OA}6?R z*a&s8rN8}{ji%T$^@;#}HE0@fs_$iB-kl^C=k?IUPe9ZWaxDfx=eEbS7Gf0tK#_Nb%b&=-u=cBw)rf`PNu&?ey(cHd&LcbsVRSrX;6kMM zhI2h$`QD}Kf3%pVeT?U^H)ATE#~P)JH6~;zxf4wWR^ItQbeC1-6^l_!7z+yubCG;i zWthGK*lm30p#GW-VgkMHCS>qmkbf_xdI ztWs+V?Xy;q3^WH$&iTQYcNL0kBL~0qRDF1NuJ5}ss;4(p)EjVw zP9>ro;6JiAk8gUy&*tTNiyfp4H?1w=H@%oOe@bdU?p#)w`V8Pw-eVy?@u1AyQ-kA> z;N4#i+29{uKOcrJS&nRL6ht2Q#WKUgM5W!W1elBxc`{D1>$Y@Pl($6CmL3!(>4!h@ zZ%R_zVq3~oo;Q0XIDGhUgbTCmN&W;-pjE^Fd5&EGz=VE2~v?tGx9+2o5W1&C6J@q8&q4=`t-imTe2VH&II zs)X(QU&&#FSMEiLe^!s9qqPzLwqn4n3rq0Cn)lcz&aNV#Fd@E2`bWx*DWdD6(MwVJimat@15|Q1@aT7<;z(EEiPAATWa52Ya71C$9_y}$o8HlVGX%T!R(7AnO6l9LM zd$aDEO;KsB&APaxdZF#KjzjjOEuI=l(Mt*3jO07^cH z^A=`_th2bLT-);>z^)Fwku@zBhAOqD><nM-0ee_KQL`*rhIkva$7~(h$PhWM)2R z;1xKG2NdP~lx+NI(7doHJ28Jk;{V226k0>!^6HV|jy9Z>=mB6a7p(gDZY6n#RvBcu2oSKU{*P9hpr_Mol|WsW zfK1+7>Fs-g+LV=>0946M5UpqN*F1eQP#ilQQxp-7s}UHGBZL_luvk6T@?1@x%*Qo1 zTo2PVcA*U0cA3p7J$ld^cc!~jr0!u%7Zxz!IP$I%zE>3ewJ|!9AVF4bLy{O8!XhL; zbLK8@)j0QuqyNI3rM-!vl1qsZ_LjmWJzN{cRR`uoiTT$vTTJV?V4KvIVG{u(ST+;QX@RBgT0@ z;F|v9dpcm$k_dA~kMjU~{dc$OQ=#>mfQ@DbXcU<|)8*N;cK;hGQjji%>+Kw6=<~T) zm~QoVfSWj3QK&oHJs}A#3t8+1CSKY#Mt2WSMbw8)24jbH{u6Xb3s-tBY7p8NxW6$= zvQ_dJHF^35OtMO7IOk#>*VE6gVtT(xFQAXY$M_E?zRp60kze<_0;Fj%M}EGdG(eI) zx)9daKy=nSAL#`cte1D+|E~Q_-~UeceN`+X4`awy&h-1E*6!0zs|da7pDrRpo#ug( z6lby+<*gh0oJSk9hO7I*{9NV2jjXHMhJq-6aiCZf6nC{B*1l+OnwrChXy@ZUniTr( zUv8&pc{LSx>E6&S4;~i)lAFGcJcY&&R(Q`&DAgg{xAYTdQvEDWZGLm9e@Cp$gwT$k zNT>60!W5%a;fCleJe#|Upeq_4W)7)`aX|m@vlMab0e_;Li%|RlZ2t$F1w}DpsY>KG z0C0b)ijywr)YgOEpGjn-EYf<}{S~z_94gf*Xb(uY8SK=NU=AFglDpDTMw3x+PXIOCJhniS8BUoUr5@ zzD33m`&K`BnWc$ss3!dboRsj882^Aa->s^HSO`;+T! zx;b7#;1$@JvjhjVl0}o#=w?DD5Ack$opC#T83ic)mBg6mWs9z*V=uO~nV>T{>;%G0 z-Eb$ac9{KoVNI`e+Qc3O65kqQq+5ilpSt{46Zz7@5yadX zA&ZBP)wTO(Bkx!`p{D~{9hfC{_z#@e9UJON!C>Iw>mx+d0zGw9-%v9ACjL44M+~D1 z(ls|USf%v7l69V+V}8x;W8;O1N~^lpMK~fLqO8UksQ@DSu%DXrcizZoq*AuYnj8;* zvSLNl={oTVJ9y5+pa~8(h=+BDHU?$m>OK3RIyrquK9XpR8#u_ljL};IUnhyW=lA4+C! zB;l)lWtm>3;wAQH4y@GH73XjA%|Rj)*_Tu!V)WZEyTCI+Xx>U&Wkq+w!+DJ=3=PDG+#3vX7ASjmEOaQ> z`RZ>uxp<3~&xK2CMfL%yL0?#%I|`83)C7TySh^qT)BON;aG`M@ULc&#F^JCF&YW-^ zpQUSD^?2&K(2lf-PYL_(@=~ARgN$WOQ#cydZHfM1@Rx`nles{vr08Z^iWJIrO^q!r zFv(xEW-dKxw@m_gV1DPMWH;m#+2kv}D6wBu2FwU4DE4PGetcy)%C9bOYodpC(vscE z6xpuk9cY?lE>PBR{Rd@+q(sx8IiGph^+wM+BS{Zd?2dkzA8K47BZ;A*YrNdpaf+6< zp4v@bo?NRZpX_jPF4O5^__Mn91lN-ETwZnEXYjQ-HJDZEKk%5M0#%qJu?sPB+UGRR zTPz`~IcQq0A>)bX1u>h1>5`NKmJm^AZ>P3FlSqo@H+7RET^ym2ESVY)N!s!@bXcy^ z&PZ$Cy_U`KJLJVkU{_$5rs%^k&1PfY7&y;Ll$rF-Jax^i6*)!pCtf_=JU;&%q`#EV z8T5S!L3_bgWj|RwyW$aCx4P z40t(PzGaKQ>QTPFF`m$!x_;&iy-44dITh%SR7#ig)J5(_^q0^+eP9q^In}y=I9#%= zqL!Ft6THj}|Nixk7d$UEp(Q>nf%F?M`CD16j6tHEo70}c421~aB{bnv@(5u?P{{@4 zn!u<62?u@7p+RpuEofQpTn3+z#t&cWwt(%H#j_iF;R_Vi*N7(&7=p)slfJ2()6Pa^ zk!5!zl}0mTUlzvfZ5ccIHqY8W-ME*4C~dS`1ED^<_>#O3$K~+IZ%15esx$!i`kelN zjw(|>W8WTa;@mI%qedvl8vb?;NUELl*R+4EWVBXyG_fDrnEaL;=yGbfFn3b!W@)cj zwbHkyD=a2<0Y3QR&YZ zy9e~bdq)v1qgGspptE}KmO;Wz+B2077wHsi1p?c-lL5)p-a>{S*L<|p#_ObLwNNw| zOd)NAG_Nd+_}ihi^j|35RbcRx&L)`8ZAjxib1{_G`of3CqIFuD8gy0-d-*YWe$O+m z<{$Y!F9t?BF5Z5L5@J-q*ZLGeGX)gU?OJ7cTFSE)C6u@Ddr8K0p-zbE`=S0OQ%R#* zhyR?lkOBCX0elcm{!BAV@Z#0eS_#VM`Vw-p?lrs@eBr#6Wor|YO?^e%IO(N`ORY(? z_scL&4436E)O?}){;bsDIPM(H0D3=J4;0qA2oL;2a$WSh7)NxJ?$!*c7`*isZ4O;n zm$6I>mKR}C?O*xS!o=qtyf)vxY7c8cO1Xq`_ z7kAe;1&8)uu24gW#2$y$MgSpA7ji*;Q{FyOnHJr$4B^Qr=HZqXi%~*uSddy=Qoo_Wjmlt5=M@mBE7! zW@2aCZZwwiucTeYjJg1ug#f_pDuwgH=lMP-VeWem|7E;}@ z1KkeTZumD`#vmn^YSSQzm zOSKp3jRKl6cj4Dr*z(}{OsF)U@rsZJHb`~NK7jpfGLd)UL|tVj2R7eY-`&S_93XjN zUW&yh*zxretU-xll$3zG%aPsqQ4u4Ncfb;W>cOto>Y>~OmTcO2vcuhmgg_dpF^w?usFY{0Pm8X6e4F7pvnB*zh3Rk zyFY@&JQS^ksD~`}s{=cPzQY9Dh0oxY(1f;u9>uhGQ`~OdHv-a-LB@Udh@2$+lQ;Q%|?a9 z&uhtuN{FtmE-`aXtn3#ailPT>QZj6iv{ij~<-dRFoZB))5M_q~yHyY)2#cg?-I%Nk zbP4EOi)kpg8UK{AO_voa?U z`Tu39?&*V=Z1}yjSIzmg!HQCo$E`^v!tsRh)ZgAFvvX&JprO}mK@)% zw9kF6qmra$YgiKLIkT}p2aOJH&hmN5(C91_2$%u}WiM>eO>b_76u>*Z{aXf=eEL68 z+i2mYsz+X#{e0*^n+(~UxD`R|-rJ?vp6G>b28IYsJ=Zl;Np;CGo`SK>vi@eDp5>)QX z?v$?Bg0*iA2JGBOYxPF<$IIMmI>e?r^cnUCv>NIf>unU;ri?;N295hZ+E?GfE})ZWXBCyqf<3hH8ZP z9!@81nuzV^?6j74-v3aC5h<1>?hivx>hZU6ZoJ{87NtJ_0A^VhFTzDcP@4=jE-!c9 zLzdNv6|y^baS<>_B?ZDA?FBw%K9IhL2eBHh4ES5{LdH#H=sw5&j0x4{2VX588!0d~ z5>ofl`!dHN9qU&FDC-?k#;YaCn=kYu{^=`!%b^k%;mr2clxUzG$@Ixva-&h6hhL3R zJwqX(sq`Z*uNZbnvqY~)ZV?SCr5H!4DYm})>Vez%5KEH}OM@x= zOI4({T!7ItVKclI+BX^SBE8*QsqDLDOkum*)+)D4H}|2|PI#vN2Z&?IA>3t7iEdd6 zj@gw5t2XA}M|UVKuF}ue-*;pc!0h_`_@>@w{%#y=gEim{r1f{v;r1?Dfw?&+n|g6X zxUE<%WwpWoY9&h_VNE*P4u=Vp#%OabH z)@|pUV@zbjM8Zd;M2pZoc`5NiXpwuvx+IVBP_evQXQo;-)3n*kIhN9Lt=g09jl)GQg@uHX zA=7+M1KXriBZEJTxk{0dZAc=`Z;q-Z*_8ylvFyINip$EeRFqxhkvJEH1z-IDQ|hNvmyL z5G~Z(oV3&vbCfXL{;DfgO5&+>F+N3Qtv{QE=Jd9FEXny*2N#-?v9!di=U`49GzVK2 zpv;Ya>#xj%FuCDjX%^2JVBAq1lXM&+29bZrpKh_*xMja7T&oT0kMZ4JLVBzCe=MB^ zTU%`xrGsmsP}~c&xEJ@fxVyW%OQ3jh4elP?-QC^YgS!`hC*REcfRpP=a+0&3wb#1W ztR~Z;OivxqsE+t>$jd^Ie<68`J_ZFw^T@C~Sbb>r@yE?d*~;GjF< z9+C0aVCj8Zt5$}KxQ{sMP&0Y#1^%pR{M2xu9`y2fPQds^EP#rtfX7G8c+1-mK zoDz<`803g#%yIj{YxJaUchPm65TlwX{A>Q9k`(@vN`G5Z8024V^_n5T1vCnGGyVRc zO6h=Ku6x3#-U?-y6NHGv#gC2%hmF3K+bD`wd(vx!i)OFez0vc-#rF$7-yt1n>626G zTpv8fZ~ut@btK*uKfK^e1$SNgL23!W+Bl0{n1LcxwkrM-?|-HIiRK=^L7^_}BI#l%qrYGqneJ`5k!<^s_ctBBLt zs2~c(+(Rwp4V_jE4gPLS>^UL`v_ICgjdA9bL~>yxpxZB)iHPn3E0r_tLM}zjwCRaW zkavRCbG7ERdIEmvn;>(w&#fFgFiIyH^Z<8r_N+mY1=_}Smw@Q$3!^@ne`1hTWWLlG zX%>53Io3IwKD5bcm_3}k&rtZZ4xO=D;&1)~v>}g@%VLgmlI1wPx9<^O5u5_?xPF7n z$S&5&6%K7|#2si9+HMdFhj<-uGr52<8*aktyAp5kFH4Ar4bx-^Uf-}`FC8=KuhD@GAWEnR>3hV1F~+$ z_Qp_%6#)rlsj-h|A*>MCqP({@%n+H0*wN+PM(A?il|)d_iE*xsmmmvTiq27mS^a+s~K2$i8`P^^!_R#=S zY?qBv>BqLyXk`)%c8V_Plq!2M&vJ4Ofc!d$sh&Y?qlsC4l$0bKavB7<@|lXwu^+=> z#dBnmOK;3pS+umaiq|G18yS`|fL`Y}0#4?$A5y?}cCEvli|Z7sgpde;+55p@#JW#% zpU!Z)SyUMbJW@H^IRLjJzaY{|pMb<^P#&28J}NsACa1t)%NlP^&Z9`iC|rw5N|%EV zBTD2X+w-VcB|Z7@_L50`YKc_vpgECW&gBq6(~*bZREh?yhXac|!uz5K@8KfYnK&;2 zH%aYO&nPLvEV3)^oeq5~E>H}(;6d>!GquPx;`@h|V0}P>IybGEau0_q{KFs%4veJU zR#Veb&gwa%I`n{M%Z^Tn@*3cEKRU^;*4AD>56&JMtgceUWZpDI>4-<#5o z?E`beyp0`thTQ=NL)x(Wn$Yn{)ZMgoD|IQ39d%Sm1R4ih58Oh!nxTdxMbHSv0}hOY zN_$u1D{XDft5)(ZRSGotS0D_0K8tewR}QXK$_R_PfE^1lQ=BAlNTr)XAqz#i{V|?V z!bIU6nHEo=k_;rEk1hQHqafa~P;I-Wry{R|($R;9#Ts{UE=6Kdjgz90{?}_Vs{s#I zh7dP;a5fH;HsIF3Q(ob&65C~jQ=h*bc$kiS7=7?JfSv(X5d;FQQ>6oBPAo!(te6b% zj#N!ZbegVg9XZy&=gsTi>hW#KJgE~mMa$L}m@=4v($f!bw`OsR(p1tQAGqS|DWs>FS7n!R?VR^CwgW}np zeGuhzn%f)Ou?c8m445VyY6GBBWzMe)+1Ad+2Ft&9!&pg=;-vmtTR{u2itulscs8wc zxuHsdf7@&7aqE2vxQ%q*Z%^JKF==N{5E9dqch9mVkEZ5plnZ9cY)VPYFCm04P*Yv` zhIP%P;g506;usnKX0dey%FF)j?jy2vX2;^F1@^6VQ8y@EVjy8Mhxz~0B?kF`1rd1h z5~vX<|JUdvLIR%Y?wFy{b6#3yCQ``ei8&aO7bZh6>bJ15f|eT?NlvFQkQUS!d~`xX z*y>Fm1A(_&hhK2w{p*n6xj)U^L!n$b-j5e@VQHqf7iK&Jm#P|ha^Mi3Y4$?XoA7%+ zw00Yt3`u2AWf9UE5{sI0U-G8FHJjk(U@CO{ui_j_bq|r?`lcZEu-mJs>`waSU>332 zHnT*b&7h$9N`98I=l=k`-{^eY--UNbNfS;j)Z4#+n;-2LU-{{T%$@EKFP4gz$W`P7 zvIv>BuAFyt+0dE=?yn*wInkt8OzUD!zqf|}l0tTBg)+u8p?Bu|h5q5CYY04*Ym6g4 z4O~toaJWp~%gcv>MaD-pqqdBxZOE7dr)wt!-;7HqDI68h5)Kk+9mh+q=ARj|D?OpFK^0rt@ zQCz6FUzw9x58II<5wAERG+9eFum&6;J%&Cy`<k-enzP-9A7F9|xV*2C`*;v#9F@ zU5|VuZDfqg$tpZ*B^%KHBJsC4Fj~;SuU;E!o`IIMiaGaEQ6Yr$o;?Ux+R6W^I#e^7 zsL;4>%JBB~W}1v$eLGXzCSQYLOA!D#P0NBV5xfQqrXMZkMihiC?*!^^FR!8=s~q|s z;pA(K3+PXU~6W^Ds0biD(9D&Mci+blzC)o#+wP&!uD>zZ!S6-+G*so*2x@=~{X&;0i-GPp80Ar7pxO}lfksH9)|$y7L3rBZHmIF` z$**H&|J|+@TG-VIAml_yPK_@n^;Q>3O>bM5Y-?W^==)V$*$XJPJ?hr(wD55#(Gv5p zp&y4YaE3M&Xxqt8x+$E`v*Mcz|BwiZZyj=(ugyizGG-F3woBjK#mixBQ731+r);hK ziT)*hqkW0!NHKY7ij5-dBKfBy&WraVu!8KCsve>YG2sg$otO-2D_ znpYU~HhZqeEN0m-{EY5l=7HPt=PK?_#>IQ==Vo^lUL`AP!$i{_{*;_&)KV{Fd&@Sx z<<^Vzyv$N8{yS~T4CHSiSg&UhoS$~_ASYrm9v5qau4^Ai@~p~L{?Q-Ze;)2 z_tV+)vP9+9W#q3LED^Po^JU>s2WUe!1Da~2Z*oG=>j*g^8C1C@+L|@_*tpKFER0PT z6Lquazue#P{R&+lmi*r0l=?PzU;SBRwYA9zK6azSf`0pdlaMbIrxW%EpZal3b}7$c z2QCv9#q8~^H`Yiqo4{>ZfW`yN%`SxqHP}_vnmkucFBLwyloFV5IX8(l41HG@z8#Z= z8Lkh862j8sNX}*RU82rYf#FXN3W6r+$w zj)Bl=sKeHADY{USZlTA@#sq6GlP(a7NR{SOu@a+z_A-8AV#V{fLcjr>+A+ZfposH; zucWdq;W9$#n3<_UIGL!Ua78W^r0=t|2lwjd-pHXA!iq!`dlFYv3>oq#JcT!SjEAEp zd^@9(_02LQOEWFl>?htqZ&-uPaWlMft_&*}%YVKv`=M%7G#^@-jvP_T=+ok98GD;@ z0xY{NuA7{~bLL78wvh|j!QIm?y7$_$>Gl~GyOH8kd0xMp<1u|(AK|F(Dl-hQtkxD2 z)5nhk_8RR0)o*gFEX}i0d?^r{BZmD zarsDz`7bQ&KFOQ-)hU@AK6;`1tyg;Hpd#%jhkmEkamtdFKSNX8Y$T9Qvy-3w+A)F( z3UeE&>(;X4fvjvprlfr4IeWx`L&QG~{+YPI4!jN5?%$K$`|tm_P#^ABD1~y=<*`*F zb=2c>IA{*1|Aiq%z5J`fy0SOvv`L|v%wQh4x4rdkTzU$XXkIjoCQSbx9LYdSFgoP& zj5$_!d6D-@sZ%qS@6WLUsRSrN(Hdfh1>e%L2||Yd>`-;1`rMpot3L z0%s-2Bbx~B4BsHSt&}^NOT4p;u<#4U+Cqc!N*T)QsJ5($izAZJi4LCA z5y756=lx;qeLURRy-MmH;I$-_Qrt^AuZJ9(LxDQI z5wO-aF1cV50cbU$$+5!O(ggwkpFnj4@BU-lCR$p~dJo06AXYwx)ue^}0PGS4rJR#I zl!pP7W{e|cQdz!gT@=Sy>U=eg4x;NFhF64hBXD4LeKx9X*O5skkeV=hba|g&j#`ZL z+>cnJJxH9S%+-kVM~ma-AwhptW2n^MnpUr!*XGUMy8|jPIhU0|mx@L+K9ZG))N~Z4 z0X+}7sOm3*;I3M?vg-6@5BiexDM>X_TnQ15>4nAiNE`2#j`CEhbiv*x$-EHJ5gwtx zYI1lG<<@y+J?%**=GAr9!hpvr`3+Dn&#=NrBhvx+VyM_ifG9|3tw*c4S+n=%MLG=FfzhVav+l~H6EsphpwZb>~@G+UE_k? zkLO}E50CcIFjyHoLYkN$xK7QMq`anN)$jw;pM5`uj)sk(dX%hE+HWxagrcetF91R% zl!-Z(luDUw3?P+)cDF!9sb=mMQ+$nNOsFVTuQSq{hA7YOBiTD_yO)>5seS{mO#OHU zW~3I-K>_X4#CQRa9w2!{yzsCXqWf4{wP$UA);3-QT=2RA*{DIm!t|LYnI=!6Q2Yq~ zW4C=x_QE71r7GRw&viYQ4YHy5sTD0PQQJBhieOy0vGpuyskL`{s77a7?fmza`daVR znNM+42#n512Fur_M#)-C5MchTsTl%fgV<=8O7KPmt1`M!<8}+&Amv7jMm^@wA29P} z;T~5=^h|4M=Jc0VSN7f|ca58<9c&R1JJN*IRl-Ao=G@n%`#TFK#+%=InyKVABqR`_ zM3{UpHDW>ae#PuVVwu!~_|-?*5|^46@{tdTxhhwJvd1O$rD(e5K%S^7(*)z-Eoctl z)aMwstGKi&b1CnCiqtG?*fU)Yi}1i!1b=#$JPssb4b)n669LF8Ak|#sew& zm6m}5v1HI9s~e=Lm{9kB3wI3HKtIsrT79i?J12s8Le+x2W6=ulcFl_Wd30KA0;;~; zW7x-chTK1iCxb5TOD~yC3V2mZ7mlw1udH9Wa;iBM-Q!KC1ZFMA<~b1(6vL&1KY^B4 z7Uf*uGf`&4R#~ZIdP)tBB5I8a`kJw15W?NX;f4Cng})?d^Th=D@PP6o?X|hk&vE`# z5qCFw5fqQBvqL*eR7<3h3wHTesTVf&ES~dutfw(QBECX>>qF6}1?|#3KHVzd#lt~e1l$)A{ z|BC|%I`esO4s1R}swEJ1C5hT%vg{vyz&%vxl&@BCO9{+L;_TG7+WU>c||o#~v*Mo@a!TaMZlH!8R=@vR^;(@%&YkuO|Lgdn)rB+xH~lVB0`0<{N2Va#dt@kE5w z#@gny?M;*qWP3hp#!Y=aX$a|)zfO*b#FGZeS~iAEiOHR#Q-a#z;&0SCp`Um?#x3yg zPD=s0ml&n=Ne-M5G}~DIJWA}V&>T@(&1bho|lM+1~I6)l|YRE>M_2nCRs^!Be35) z^@8M8i&wb}5&5k(^iyJHbEE@q(T*iM69b}mScRbn8CRn7A{{%-0a2G$p=oEq;r|s3 zVfNKu=5Lf~I%D+T3kqw`&*E5b;V-(H6QYCK&92f(I52A`=M|)mOXOLKID87I)3;iX#W0jyMAHFVnCKq`= zp*#;u7{oEVo7cXL*m?3KdR8-ZKBDsihJn3GV(I;cQ^R679Rf@o713gIe-bAN`2S5_ zI7IGNxpNVQOw3la(Ejh3`>f;7N^8(s@N02@w`eo7G;Xc+KerYIWd93}X$-w=yj)gg zlzbww~jrU|@3c338D9?R%G<8|=_17TI8*z;$IvZGS_iNxpWUwP7 zTr0c@I2qn&m`rFr71NxLUqZR6?BFnU*R;BMPN{eAIZHVEpqk5rb~FqXm+Dw?St{Ek z>*f;N#$kdmXRwDiURAf-ueU=p4pf}0c*+EC*Jp?Nd z#0e4dR&JXw!q$;J zg_Z!aY2nQBq;@UAqSW@Nb=*HOt$o1Y&ZG+Wr5Xu%tSCmOszrm`ig(cmkw>c{3466m zKx@3qKguB~fSZ7!j~|om5ttgzzvQy&qQY)%?{bg9Q-ioLsjpwgj7U9+GkEiT z;U#HueRI51`Pc1F|E#j0W+Z6)V}-T0UQD$$QzM#b%U{0H+82AM?rl))WvB~}1)8$q zn$~XaT5=<0r#-}8vAr`j>%)dnz-7xb{B~reTY$-_m@ZjA;l{S&Ds}S(eD0^ZP?mzD zj^_a+ELaefD-uR``1B=pO-VKNZT5(*(+*!EoH4B+j!~bFX~tM@k_t{E&m@` zvxr*$WJPgFgJx&if+3yOP3eIRaTSr@7vriVABL6GEjk+;b*G)s>G?-?{jvZWwM!M8 z4A8ue)Ihx!t5gpX>ac)C-m#YoXQlL&e7zQ9!>Sv~npl(=aqy7B7WF;c@{5b={ta`0 z1y%F9(dO520@W^vKf83$3g%d;6r_@oO*5}0@jrkkE#Sifnm%@2<;*DhRVL=<^F0rU zJ}brY^24cUn@$krQsMqzPfyCwTn!~Lj>6AdymtVux&roT0?XKq*vB4pIb;b}vgB%G zXV2hSWtOH)m~2RyU}fA1Ba|acmXtp?5Saqf*o+1av~~9K<|rEa2yFNUmI{H*32GDD zz5M0vWNwE|sTuqz{uFM~NThhb0J=1SBcxe96e00ni$Iaksww5<-w-AohAeft%O(nIu zO}NPU?JlAGx97V`qTrOoebFc|3YV&7-vhF})v8oV+o%~Ynj~=HjC^*YQ8jlsFI&54 zp{8RKVuUraUwU;ieap#2OlMVE`uMinj4jkD0qs^+(_)ciMEm^nk){f8b!iK*QCL}P9ty+fJVtU#9JCnyk5HQ2P-1&`3{v?`F#zfOAGa*`ITZG_t?0T zQGO#my?(hbVm6m{;2!$*<#m+16;4q2-JXV#3u}tv<@zFZffbOlQE)-Wv7}%;MX(vRd?K8p0Qq z-}XFkV0<(#&E!W9yOFcN+|Lry&`x#G`)wFP zC_Xq(UNBNVMNv=?3N3`_&o;C)jEjYEq5_T?OzWG>Ik- zzabk(yF(@$u8$%i@Tr7G?ZZVt^74pw2q{z5y^KzYFl29VvgtvXoBW5|Tj*jbh3N;E z|0rHYB@RMseH$durT4{@d_sfD5=?a)J}&O4P;%~vr5|Zeb)ymTO^hB9Z23*$cbW*& z4Lr+%zLWjrem_;I6ozpk*;H58yC3~lR3!t!ax}zw@4i?CFGnvFIX?ngR$~cGY9Syd z64^1cTf+1ur_E*3!dT)Yc0%3UQX;u#kHut4v@!^pS!0?w$@K2^tNo` zvbT+|BYz`RX3BuoY7_;{2gJGsNT_pOw$pKuv3_{IXW?48Ri!GV*o+*f> zIL22njTX`yce_7roHox6Q8^*=gX3aw{f62s-&FPp5s6jo`QA!DaLoinD*@cr5-jsy zh5P&&Y?{BpG}i}8R^$=%i38utDKD4AYX1YMF!0AF+VS#M#eQH5YS>_22)F-hl^5zz zwHV-Q5+MrT@G`8X^k+HICym)-AauxeeypgYOr~%k9l6qT{_PGy!tII0vK}yN{1R)B z@r4Vq6HwF=BH~6Rf!Cf0wvN>egieu3H)upS=Pxm6Uac?JVqY8~Cva6ve{`j8xHKo;9-kEOl|=^%bUn z9X3BLC|l!aNWI!k!3@7ZrE4ODQI1jh zDzVHlBz-eYGtU@?V&9eXFyR!xpQo#p#BUm!o+KJ?U3{P>XU=owzv1_b26#)PrtU7s zI%z!;>E{&d>P=g~N_^WW(%O{zw(?In4O0BQ!|dTgqxdoD=>0!{!%fjA4|SxEpB_0+ zpZ^0uBW+h*+wNMC+-xeVPTBdUmx3#5mV5XPD5sUV0eW$<_CAxVCq=L}%9I zd|l5h&0X>qy3a6Gu(W?wD)YaKRX#b!v?b>Jdnl>LFx$AV^I+zAE6dI)*0xeFw=#hh zg^mBo?6nNbIU{`dmFE4;`d3x;J3KX1=w3@ zWJfxHi8EUPYFRt({~DTCE%34V>puX?t>3nsq}#~N!Vl+a7Dlak{`69D~Zt}yvHT(@+?RimMlZ#%kt>)IpV;?*@51kXKs$8c0SZ>PX(URZ@eG_4hi>0xCMB_F% zr4hR%0qli}7nW?-h;(IR1?wbD>_*#>kd`_gLbq(A;9@J;Ag0bJB+QVDhhitPdfZmY zzQjSi;DF=U zm*Ykym+K1)%5C-za5@mThdsx(dv1C$Z^;v&KzG*M6)}76%3K%~pum<~6OMF-2xWQA zAapWFv^SRba_MjO@DMWVpw|k~#aEg>(pn}%SinevpIIyE{K7t#?fiD^ zsMfY)xbI8Z_H^-!;+rH*?S=BNDSD7~=Hnp1@MH^JoVv$PA)V?c4m;mwpO1#mfQaLe|koH zxKI-y|Fh=XYPr9IcbjqSIsAT);O5IWAKg_Pn<>Y)R%^(kLHE@@qt={{S#0jl@Q~-C+}Gc6D9f2t!5UU8#=!?uq=u zq45r*-76f*z?+=<4M-R7`U}sS^>7qpNWrd-%<%`%HsgG%zwLUqd5;Y$zo=k&591wL z{@AozW`wD4hg)7g$^0;GWnk)~`hu-Z)htv{`zFrNRpWXi5yEUo*i5|cz((?L7YCDY zGRN_}3i#`(N9$Hb9$0 zN}4wp$vipUA38ndN5JDKNy#Eys|UR|S29d=AG@!_8;A?0+*HOA+a%Z!W%?4%0c`@Y zweX)*pksOGo%&u|lrhdHo+i0ywcn+4=2~Sqck}6uuO?KCx(%erOtE81! z56Dn}xh!!MHyZ^uG6eC5vc#s`fOobH(`wBzOY~-C;!j!AoCN|$p6u4R?h z`NH>cIAT75xMsTV^Kk?ogym2@HXj2=iobEZEXokt4tw7-0!>%=GwCqd{QjgDgqD*D*I{u^{hM$vXK~4&AvzhC#gQ%>QWzbde2hmR)8Yc7l(S z1{b)|_b*@t$rzc~6s`WUut0`lbJoK6QKuKcizdl~uI-wI8ZAoBw`ABXdsLu==cOJT zz#B$O$tAPh`Nh^Av~VjJQCo_DzIq`W!Q#ZrY%%FD&&8v3($gNiNn*=Yh|JNb>MM}_ zM56jqlwek=MJ)IehO^boI5-SG2s9G`=s>2TtiNz;mzgwwl@6V-iToy>)YcL#@g;`Iu+nfHLp8 z-8@M>PE3`-@)TNlar8Vv7L@_`En@ckJbM$L?4FYqNsP5=}! zI#02X+qq!Y-7OPlp2Ag2iST*&B)jl#dVb5FlQ2nKYEXP1+lF6fwvzLVymlKH?a--P zCaK|$;pnvBm)*i?u2XK~`A<$jiT3gm2Xo4wqHgh=pjd?domVXuqwOq!k4oYrn_LwliAL~dj2hDp3-Ed>>v{ffH~NxHa_ zT0#bK+?k)>S?LqIXci6*^m)2BMBkyQWBJzn-pXEheD*2OApQ7j8kap)tx(PmgGh%H z^9i*YS%o9R)WMQH@w?9}vo{LY2UIvIHAi9Mb-(hL<3|~#>Xw=O-Xpc&+2L!F;zteF z8msKI@H$UEz$Mcc4jp$~O`eytyINsm<7phqVbrz_QiR(hevmzXk5T_s{$(~}z(0_x z5mIaMky_?_<{>Mj7Q*o{w*OHGy{O)61Gp|xGpL$;Yvubk$6ae|bz7%rHgi?wwhsDe zR-}vR6M^a`Dc_rIvgUMuL+@j;?Ox8lacH0XpD?F=(m!N$*cdVQLsNjwrk^Ed#O&Wn6OfD5D!zu846#k~QJx9F%-sQxK zsPWsxYdxGe#IN(8Y2~-sMyCK*eIE^)e+EO_Ra;~;5%i9rGJCMPP2zxP7)8^+Y5SFj zhqqHfjKk6I?Fni>0gWKL8J8|)R*sXXgdANpJM8DsdAKXwFQtW20GK{{Q=QL@{M z&9OFmRzQ>;i4U7nTDm&Yq#K3dZrvxAI0b9xb2Gj-f?0L^30 zI&J;I&@g@4S-?6ceQ)-n_14Hpk0Df0DJA(Xu2`-o5h}p{?R^h6RS`(79uv6>PD=zq zqx|zf>?nzm6Dgzi;>O#AGRQJagghmtASp3o2{-KK&DEUz z+XyuFAz0QF^v87@dri**OWM8l(O&qTf}!$8FATdqcqeKZ2}m|l`$nJ4DJL#Tjy zkc)^|=MsMv5E|4aBab$?@y-0Vh5%k{KRg^#0f4-2?tc5-lfRz&lR|V5Xvpm=t6wR~G?IX1^uO+0kaSPUnp?dA@};O57vlmI4ilq8Ypip|qxWT71= zm|z}7ib7~hFm?oOE?V1Lyyx=ZtQDyB^;60fv#!sKcWkvomGxjD>)F;f?jqr*1go#g z1pfg-BnVIoPDS2AD^=$k4x8#aVx_YA+oiU>$IU{LJcqdAF;6W!ZxE8BcVlZ$+UNEF zzFPPuX*v|GDytF-CHK{AWVHq=S{({d8TLF92p9cY1=bIG-S*#=nCmp^=;Z4o_EZFv zQHCS!Gk~5fcIOL^zkeJktX*}v)07oo$DTbc{e5X^zwuh_ac**yq9fd|fsj|CW2g-I z(k@h14R+vV+vmXaOL~oLuE+Shl1Cf$S8G|rVT~S)Zc^|32Y5K?R~y@@p?;V&wpMTA zmg_bQ`88Vrxx?{qq^CxdOCw&XrA~t7P`uzD7;p61c#;(IZkNI;@*sGHLjqOV- zvF2Kn&k}s!&(`aJ5^xA1Z`Pg3ATuLxpbxs4Jqv2uz6Fi@tUs>+CYb9;Z`O{mpl#8% zz-W=oZ2BM_&}jlB%QJESA{&w1FqRP*`BPC*)s`jbotE!0cxyJ?+cEa(+cYJ@lGg>F zdbzA0J|5v6?P-KC_1ksgO+v3?9dM-)@DI zjCDQ#0}N_(S-f~t{?jy3TYn13S@IVwR+_!vRK6X%y#4xPi5-~yAAlD|C&m#|5J}tT zu(4?6PqWA4OtTSnfXj3G^XZk+Vzm;&=D|YAyTGbu&~tkDkLPrgFL8BPN$5~R+6vdRQ8CR`Y1d1?J+T3k!w#{!1sC(eoZcPTvUdThdb#t5Ya659}+?O}%5 zhod>h(Or<3yzDP2_n}~wQEo_#p*zvOU@c{S`~8VVGV>yxg00~t>ger7k?q!+Z}UE% zA!9wx^toxAO^j+e9zjt=^tt{jy|v~~4Svs=9UDYw6_<42gbzgq^G8-43pv{Z^hYYJ zZDswt+72OnQ8<*-P@nyMQRzvI31aB@x0Gkvc8A2b;I6bXKlub27BUwP=dNSf8WI^H zefbEf8aX&D8Ap8CiE^Mi85Fmtb_#Jfy0mVr9MIr)(g_Dx5d$7zbCZDu>6(9K^-y#{ zLq1l=LQ>=E>M%i3${co|vOkhID>GBl-46Dd3$^{{zV0?)?=lHZ4`_o23-9>go2^ub`uPI@?kAH< z*Ynz2p7Co-AMAFiH3>jkq%o%v-m{2OGbbk_y7buzY+Sll3=B*qrLf5N^UPVJVzMAN zhm2Q3<@N2Se+jOeuikxvLVb)87`? zR(yhWBaL4teqAO%yv*a#jl!d2T3<4~;d7WUXg_|S@DQim=O1X1*^&OOi-CTLmi3^2 z!qN{J1}ME`?2X0bp_NI#S0|G00@lKqvXH;!N>9c+0jXyz_!1#PVZvB4-~Lkg48E1X zjcW8`myAkB$bB(0EUqJZ=wILri?o|4dKxaY zo>EB+VE7b2J=L&L0MfT|LCWaD<|T~1w$G_zSaG1l?iur8nBXK3$P!z)rbbX$^8b3B zOVkul?&=r6b6$NEu2%nQRyY1wt=v~lN2;E`R1rP2^ zds8`4kYCm~Jw?Q-TvxQk6!-~&((+nTrTk$l9O881fz(Fsfg-Uy?c>R+Pq&aA5)Lw|zWQTL=KD7mv3wf1PnR0zgg|kN&`NIA2+vxc| z)<2^VxR2-W^&I-cMnJqg(-f2;XHw!a)>F(D&i<$I{u5L20?Pm+_kj}VHnh8jb6&o4 zGi_8kIBCy04Lr%IfRo>bVYCWH%#fz@zmevf7h?h-CMqjOz_VD><_AQI6c!dDc9n7t zN4<$OF;-*bz~Q%0n;ejK6J@WOEDMO+PiW2ESC(SC$IC|)+zjsv+VJ(>m^hJT_#jL+ zJZ*n#JA}F){cF*MInL?(&-mQaatDi7(*DjKd0LLOx)U%<%m+L?R`XtZ1^dVoc4+KH z>T&UMi;#3wbz)Mv`0$_#C7pOIe?D$wU=NnejkGnX0XS*u!_Q*m6m{kC`4w*N+$~a_ zGf)k;EvM11{Oq@O{y3T|v>^5U=k-{Yd}CJJ7KiR-@rK~x)f3vkMHbVCZv10?*hLlk zI0_SZH}*BKlB{1}SQJzouR1FS(2T0gde0ziBUnQH2=O-MC5sTZUJ2bm2J6>eym+?s zo-m!#u=n|MOeLK*y+F-%2_jkmrt~Zh%wheBvUYchfNcy9^np+IAa6;;g`oZGEJWY8 z^&{z2r5AU?oVP#==g}yAS3qi4&-gpXaSEu8Os;Xj5OUm~Gkuqf;pgq_^0oi1c;eUg zlfu1qh!nD4S|;sTvaZE;i?BQcoMOrV-rNYYt(~#CF!$x?=5zXlp7`}>#$O2$R$Lr9 z@^GXG_|*lU0)Pumm-|uiA2;x;agHIzm7LMahLA?wl*gtq_uUOe@`2Nq_vCLT2n3 zLG10Ga9p+DH^iX(){QuXoOh>wjQ3^a5|ukokyZ38^Dq+i{ES#pT-GI+7XZ`ypt62b zMEtPhK%K35K`vac!QtS6?xi{_Yv#SvKboWqv~JyJhqiHz2%a$7Ljw78noyY0e*cMO zdJNk?mj_ZUm}dp0J@O@WDXKNcNuaJHYTTX*C03UFX5~mCRn0v+6~ug6rUOrvmJKrJ z&&inOYz-49@jQ?Malgo4_|}D(*w*b2wgismv?&NcpuH<>OPp_}w>$B?LYn=U;vagY zm0rOb=)x<{NTX0_(q3z&zNNjxA)i(H)&yi+ikO*)@JOh&_%y}+4$YxPeChlv><-75 zG~hVhG+Z%hNlj~xNiP0Onc+pRFzf2S*hoZE}62s9;g4q|T6G?DSyuz$3v7nVyS%o`_%FbTVI>d@0)NoF6Ra^dT?_OONlyrGWN0@>CJF&4k7`h%+fm8rTxo68ie1h{?RfR$-M9OBz(e5V+5)R*p_Nu6+^9&_ZR6i5*7 z=-X29#s1GU8`v3=2T*QtmT2v?a;HdbHH6W1`-f}4b#q{XZnVuiTw5tnIi z@OpqGJNt$(5$o4OCFwL_OpU~$@tS#`5*68<3!R?ltPgA4)x`_8E*z`Yi5Zcpql*tN zo>U4uEf0-oO%1o*!b!elhhA4mJxGFYWYhCN6LOyRvKE9?zUM?4gM4#mFZ=0#?Qg`# z%0BOa0%AWpDO=MjSVEJ=Sw}{mr~mo*HY{~3q=sV(m^k&Eydzk6M(XKle_|$B=}T50 z$8d^20+8?1^G7>QJ^<`CEo(Y@s}nF)A8g+@v2swJ-QhUI zg&hE&idn*>WXPccBQ!}Qtj)+@pBwWOqSRHWCzj;D-=gx)-x zsK06MBiemXk$L`zy9qN0z){|d035to6~7lqvqQdfq~D>1Nm;IBJDND;y%ygMdh3HR zbIhnM;(C^owsh#FsL|Pa0WVNah5$eL<8&xzH2mFH1tAK*E?&q7eD~9Xm8S+#cgVIp z$lq#*YbSedI6m|idR}3Gljz_Rj z7Ek^)bk-}-2PGHP7qQ!$A+nuNR0Ynbi0veX)VGD&7uQDly8cwV@_i`g!`9;qien3E z?3)%1sk|rQnQUi7->?d|N3inct@Dg_AfXAPSM4Rcv$u~;;XE@lG@pZTQVG@>7U)~0 zwoHBB5!ZZow(QEU9Xk~wTWA=#``+a8`Ha$kOqkN?X|EnoZ9HFXvQUA&tLhKI2rX-N z;~aSE7YS8h@UbEr(Q6th$p5l^Y*UtH(=NGR{&VbxmrqfS0zB!O**EvU5s1&<62~M{ z5w2~9r;yZg5Wp89pV)w`P1l+WMX9cBPIPhIq&%vcrO4IrUm7gD_$f?PuQz!83)4PG zB&Cs5tQ{%{O~@~KxOnkeWMZEgEZ+VeD!{(BS<60c%PmLdZAXn2ki9?aQDwD;A1qgt zJpI_xR-UK9-i$CZOh7o~)5$O)sGRjOz1L0546=WPh<`s-JNZ}=4BaG`egJMUG57Hp zDFW7UX!*1KHJGl~`$HvXg|;2LPnx$oY#-Flg)8;j7LxArPRunu`+q%hnil6DN{=MMaWLd_zR+e-#TSA;A+{}-K zu{)g_3glcvjKxu%;Zp0RWE%N49Wi$;W`e4t)u;=7VGT!{V=buht5ozrX(m#UWa zXSB$qC7lv^!?2-0+d~RrTq&@&p~9FMn!?;e6xQxom8|EO9DqXL3hcZ&EB9ZYf{zyjiZ+jg>S9|aGxsig*TjW4fE1oy5 zCDNmTSnSQ5TaNViSYZBpe2mAR6ZQl8_d*09{Z}Pw z0&3u#v6%4r{a%_yo7&s$EVAsz_c7w7Z?kgUj1`HwZPT~i5%fH zm$|W|&#tQihPOJdR+2*afM_dk!27(0xSKtX%c41($4kt=1t{%g8EERi{ss9K&(su7 z3$>E+c1~H-fVV~s_Cjuv4%^^*vscMfHs4emEfyunh;z<&HQ)_FL-<2YMW)7O_Bub9 zb2fG(^q5)}zKoSBx5y{UGT7|rPsZYxH|(2a^1O3tGOKNU7Dw`+#+8`PK66r>o8DeI z@J4bp?B!^Q2vt9WAN|f*MIL?nvc(hQ`Mt+>i-R^FA$UZOHY5H8E4Z%&V-E8NQqe^j z4*Z3t$ddW(SYthvkLBN;nqfQnUW>HE_k87O6r;pm`Dh^NeN|EG^fA(qkD$VU`=v{l zABI#YJj4a}51ey%60)Q*8H*!oYxTiKUjmT~j5UUr&eqg4s7lfHMh(uyGHoPxrzCr! zCXjoB{-FUm!R;ZH`YS)?xN(j~HTVxa0b6Bk)RjPqi^;= zRVDtc?ph0qFG@0R%TjBB4)H6q!ay=wO2n+vbR0A4p=nQcC2&+OT8A)ytlE98~k&p2HyxRSIlcCudZ*3x9&cHfVAzbjoW$$b~v zUJADk$~T>~DZ06zc-X2&6*W(`OG`>W@ze|19E)3pA?xqfzx4#s=LbD4w#^`Uhe049 zswXvl4_gnmTKjd7=_C@4mT0$l(ZD zlPMzml1YpS47B9Nasg(}Wr?vb(qWfv3 zXW@})ugGBDEqIDN#-(zAlHYuxsE%IRDu1q;`-)m`@HTyPoPHHK2q78UHMi%IGRZ5p z2`F1MdU}HDq?-ScAkdp_4X;zB31n z$hi$e`GH2+U(o&(Z)EGuGxfGt7E-Q7FaxcDv0*eM*PJFl+&NfQxRv11rrOYLV30m` zH8AO?>fO*!W4%QJzjeWnhD5lr4wq86LTEcJH4(xcZ9=VV&Ita(5*e&-t%->0H;F`h zbBZE&dYj=bWZ@qmAIQg-kTP>tUSuNaBBTtDg0nTNK!2X!?p{>Ij#1qtpP=pyS}`U? z&-zdjFkg(%Zc&I66T`2Xw*H7kWl2~J4S2QB97o6a?lm&*IWbW$a-p*H0|M~nW94}Q7f=0g@;=N)Cm z6aPNhM3Nr`YM%Ma%`NO2)9gK-TrQL;gg`4w{Sp72yKK2OrTfe7NyhzA7M%mZh|8X* z7$qs|<|Rp)2XDRimBM~ven>9dQzzasLePtzs%^fe(azN*NWuGXB3*%2wZ-|16GI>| zZB3I-x-v{-HfihStLzBZeI`#_Aoyd_4wCirC|ed%xZ8I0^Ng1)j^5XNNQ%I+*Bx8p zRwBHR;{4^Sx28>pBo(kuIoY(oD5;W1Q~NBJr!}fIR?qXC@o8+FtIae2tB2!jrBTO| z`R?ER-EUr7O+VbA!btLK_;pgvI;E)$-qF4@_|sLbBIB>WtzaK+$ho*7q49?0M1xLH z{{8$bD`vwDqAp8FYdWi0*TbsJv-2J$y{;S*+MV3ZEjDl>crw4Z$E!kW;#-^;B5nvW z+VqA_9rv~qO}DCsbo~xLpg4JcVCDK->f)0X2g%8=UKAky3_ThQ;$@SZu#i5dc=P9< zDYqq&RSI;((|TrVul%Ndym3#Fqe)YZ+!&^BI=r2!wqF0aYD6f&QLPkB!K6S${rWEm z_X1h|%XC=BBbl~NkZ;MonfUVfW~#bpWG>Ieg(aENAmpcuogOW6kvQY?jxcEYvIXYntY3}bE-zPJzcai} zR*~pHKh13h(%Fl!+A{oXiG|p=;-ghIo`rZGeUyiKGqA_HSj?a497oSoww8W>N>H{* zRztIMaBfU*G*HSin>TyePb)!Km2)9^i2+_y4Uu}^!W!p}ov8W2CAaRZX(zvS&FCj{ zUh1i9ADn{N&JZz8U@SG7+0Po~M~eN7Abv68IE+JRKc?Zgv58#WZ{H_#OrM_~>ae`> zA!Fl^uYNCEhbY7QzQdriY4>TUzbEsOWzvRhQcbV_%G2g+L#DC45J7`MNKD@ell|;E8u1vl*wV4`+_q+b&T&c^)&zEqoZer z8>|VSeN+8vD9_f92=y4&oJ&6{KogW2v~g)78{mPP)>i!Xkk05lE=)>ljP|;wUVXyW zZDmn{V8g>J-K`vgs+HB*rKgGdspIFqy?u$gn9SMuBZ23OSdSN#iz{py@x&RzwEq|a z%y6vt@^C4cZhhtzIJmc+`QGLzj(7dP?R zc^f~<&;UyTB}r7;#LXvbDB)7od(SX}>)`m#8m^IG$SI9>ymfuE_OSZ&aH!+6Z*eV2 zH|ba9m-(biP8q}mXV3j<%ik+*Rk`h7$Jj*tcyUFp8M!I1JkO>wRUSK=3rL#2&}1jW zvy`+>)y6|x52K(gB}$$5qb$Ibav0$u18K?hh_*9QW+g^nx-hLS3OA$=6TLb~9=cht zHN2_N)aNmt=aHp|%zCmlnE#T0Y!jFix}j#Ff-Xi^6npqcD;xIqKqO% zM+XBh0(P8&k{bzSTkO41+t5#y^?&YMzYMW;vv?A?^t?6fPM`R~w**M5e_zkls*Kvz zD8MQNU4DUq#yTeseI5-Ckv4|Ny9d^W6&Tnd2=`$ZqiM8t+?7#eXls7v)h`reG_bbkG!;UNmrpmKt*NCU(ip8^Iwo;r?JL=r$WSeaeziytHq56 zqq1y;X7JhYT-#re7 zYB8QKVZ(V7GLkym0^UjQbOW_5^*(*+qSdp*)Y+!^Mi;KyKyA6C%~V&I8QPB-aH#$` zNcXh64}+?*Zh^mV5P~Nb@tf-B!hG(PKp@^9%Q_rd{q~aNI0c=H!c3`8-Gl;)IQTLX zcCH^ZYPhBk8w^DfKZfcR(#K!}`3p`1-seiEb!)eYY$C|=m6ODwsUf$)_Rm79!DkU? zm5^V)+0dD|2ToN<8Gm25+wJMKwSh$BH>YdN@k79B*XgWtf$n4$5CaD8d(XFjK^0E! zC(}j1y>Yq*9|Qq6pQBU>LHAe_Cq^{t4JbG|-^uD^@jLkA>7n_rJ6%lTk9v;YA09y% z3W&)=NcH;q9Xo$bLfuh%d)L(5rn&Gm>GZ-c<2ZRxTgbJV(5@%(n($I%E~>u-YL|Ef z1FdHLn1eGJiyWoRn>rTWe<_m+)4y*(OL4JE*Od2@ru&v4s&9)!$3=wiUgTlMmfS-X zunv?}Ji`{Q26=K3_3DHP_Bi+6lA%ell4)YFnDxsCjKN%b;Qj8;adco89NW6usvsQG zIsEE99v|=V-K*u`ovm});20FpNpruio5Ow0%Tp~om`)WSu}0B3S5P_PF+V_ zVbD;Wou#;|n}#c>`hn}GN;1uexC=pYR}&2|d)aROq@1g<(hV8f z%}{dKgoVMWNI}hStQ0Y-i%W>?-Sp6g2Z4)7hAT}9m2zOgGv?2K)HQY!u>IqmP1|Q{ zMtTlzWI~mG-0BA54J2yjEt_3M4_Whkv{tl+Aww#$wCG1` zz)pBfm$+|+18b|jQK)?%!T1sDFDQuFZ69_XkFhRN%+zHsWR(N@+}0`j41tx3s`65; zx=GmAX?||nzpm=bIsO6J5PzR^PTE(7i9)X+Y5PzvA^*v83YfXkc$q?d+fqP%b4dS{mzI|n7!i%FenhImX})(Z5M zd(F5A)9kk@x)JX?x@Q7iL%yw_AoPF-V09BB?84mpT;#LE0OseybWJ~wrSY9TEcdGk zi`};wnyyKYPgw}ei0A0Iro6$AWkZ~4{j}lmUTke`CCJM~R6~?|9@}IMQmksgg+W@5 zbX^+1E%c7Y2PSIO#QH*BAHzrYs zBpc>a450(AjO?|JhV(0KK&VeB={Dt^9x3;Qxdyk`*lddwu|oa0sB~qSp@|0K!}1m| z_~kst4KAho;m8N~h`*nL0y7cmzh0SbB*XZ@NJ2q&;DP^c!m{~~K}H9~z3PZZ&46Iy zDk3}vNfpH%&Yl-2g5UrEfNjD0T>(O)%&V{Z% zqbju&-#F!5UlvYOpE#)gqDihdB(|}_RL?8TaFgz9&DX7>u>@lUg}xZuHw45X(F~I! zC6%e;B2bfgow@kD(~HG6IF&UjqSIdTVZ3lN^ILSY6+ja@7jueV=Qc;rt*)Pv`D2{o zK+eaNmuTc-YpR5G(U9jD{9<YJtFNKWxM*m zL!u>7x|@jiu9mISapXMby&)dGPM)o)x9`6Z;q@zA+>v63rUHf0`pPWJP5r4p7~?w; zx8u)PKD_dHlt$zFV{o`UB3}Wgc1Nec@_QI#+RZ4`kKuX`Qmk6Epiw#I-V&_LywGc# ziLHkvk@F8(u(%(E z5T7wVss}!;jHWEsd1mWGcEL{>>B(W{hHmZdm1~Gvy<; znG3Qu-Jp2(QAaQ0-=tw2yHqwkEKVkH$KMN^aWG!vq7R1$tQj=g2<|pvp(0lX`)Z@F zVFVs#YOpXYuG9jUzBFl!E`=D9%X6hmBqolbvayT7!&oc4F>O$pjA`O<{SUyXs`k_u zTKey%eoj&uxy(%#oynAYD6pgRaR+K`C8}hQS%+~o_&ljLVfvipUqDb)3DR^E+7i-iqQU)MU7MSLmph=lQ)^n{(+}pus~SB_1n16rdrXH>uxCn4rlk``Y@V7QripAn^e@B zm}iM9*@maAqow>&o_edE1TUpv@#9J7bbYmwL3m{^&t9oJ%74<;ksT3l9g{T1Vkjni zJLNC5_8K%fq1=OJ6{KyGg+;X;PD^%moer4)L-^&J;;S>&!biN9G|v7! z-5CU{eCf|M=HP)_$FYZ(LE4pT68ASIg{nB2qE&CJ zTNHU$^X^;UIdhDu-@{j=YNd-d(UGGN5DI~!^qA$Vm9`ThoxdGIN_h4B-j(kIR>(u@Oqf2eIQ`r4t=gq_* z1x@)Myjq0j4m==QReP^_sw(~`UO1J1AK8<*u#)$6a{_$(aw_ALAb#S4>&7<4u^Hz1;% zf3Yf+;2fMmh&&Qy{C7GyY2;zsliPc$#SQ7gx6JH6YKTjzj9VXS*WK=jEdGL4O@Pb6 z^C-5zpn|QxAQV>T&D5rKvj!lq`CxuW)zRBUT3jFbG0wMt;l{e4HFmf)`{3Yo;aJ+3 z)^#CIlw@Vs7`i~u3O=WshMe$foEF~Obgx|e-$C&p*O!iJ-}#2|=7x7mHjy?QZ?nn! zS&o?Jaze?*8q6EhTkNwLzbQ*jhezp|Bqi-mqkP=%Er11RJAwE!0(kt8MoBeb-to|1 z5E37HT9_0$k;P-nshF;y@PhKQ3#%lSaGhhBf63kvjRSmWgQbQJsqLxxU6 zJ+xtO&U0ud+s8NWH7T`>Ay{@x><(>@L)bc{dAmzJw*@b7S1_*(%6SBDr|8XcX==%^ z@Q(k*o**&cXNw}wFWl`Ao?Z5CJjGmnxkXjfmP(NL8c&~Y)KiLRtuq?dOcAyH*4C${ z;YM&BJ@J;R^DNX2#a0M-7K(kFtNtJJ??W??>|1ohCQ#gZ;%xFz$Rh=V9J?C8iKEz9 z8$+@HFF3~bUl1Nl1NY{PF=bsJ$@lM2?B$l%nvh)9I}75ffLrA7S#bb)d|!>Ml48@MPQu%S1mQU*aI6g^7{4(9;qy z+5R46Q>+ZSstP>qr|07J!ZPuL5^MOvzY9MSEidZq|0G`pmEs7I+31t5I&F_J22Sz%{ z%r(^cLOkj&s#{I4H3g#2YF^y*>Gg@{0&O6T2hi&0H}zU>?Pccq_pU1&GGmJGR$Qfx zf7fGq^!QJAuyy({n46&lMQ^5kLm66OTjoKn8FBQw&5+sLusfo;7vzN$DyI_16b?GO z*-VI(Llz$girej`X1+~77K!jY2`$U!OEyPYvD!4$+%x1QbTknTlw(O*oPYTqqSrJT zBSwB!x&Zviyjmc=e4lu`|7=G-?5ysz9$vD8;yG}Jw8IpO07&Uskl#w$#8PAMT|JEUz>GRKj%1Ul3q?1g z!AV8&ZMyS!e|F4Ul$TPOvj;?;yS}GyLb87~{ZkYc@xAmrm092%Ye?Bm`cKsQsG8@+ z0A@T5c}ofv4y|3~Uy$ofVg~~H7Zk365;l!9?W=P9_SF)XnS9!K^bwWtdLZ8ipC2LA zi%!=y(Q(2n5 zWjy`v4n76Er`*eorvzM4r&yG*><*c`dXx7p!1SI#A>ExaW7?R&Qv8n9#Sqth58C`W182ikzsHv>f|s z4oEd^Q8ShGyyC;bah=A}(#jvsMa@;h*soCkhm9NGa`NXW8`9ChdfKdXxEABL;ze^^ zCI^MzOjZn*0sY5W2k;)FXLYmIn#|J$`XTL@VV)4~P=#hsG)(%a7PY5hJ`n7&;;&1> z*;I!K0!ljlcdPmLf3(dHQl6MjIK-=~DRDlc72u#F7Pf&MyvX{h4RpX-(_--mQ5%EY zi;rIeK~HcG*|6{;a~*$Zv2 zyCgrL2o-3Ub@?v+c>36y88q}(1Z5-KwY<3SYw-L}x`DA?*U7TkFA2qh4fh?odjrCw zKnc3YzOH+g>_h4|J-xZ^;*>dQ$j-YD;-05*L%&<4Z0aqp}JfWW_F(@3wpY@71=Moe^7Kk(V8JQr-CamL7$xzh4_kE?qu z=JNa+-VT%vpj#jvch{vn{(`n8LLtj79uJP5(fk+kRqu5Bg`GM)P)n!0xQQmyw1GSe zJGV3X0QG9F!9%o6I$VJ(|DD=He*V(G-pmgTDO;`}WxV}5^!=P_sqsyzer!l|>};rD zoe!=YaTx=NB7+zGmVEGi+2YNR@<-OI(u!BailW-&5Ct4^lY9H_roW(%+n<3q-xC@y zEwdvXyAHb@0|>11g7$xGR)m^6<$J*KAx7e-ARW)}bM8dq@NS0yiu(UfDg2MG{$KX{ zC^lC3qPRAvvoRQe+W%;a0HCe^t@)4B`u^Rjh;8Zk9@gM?Y0s|!%nE0=1Y+|rA0i{sX zn8N=eCUIO($4U&c2R^G%>Y`!uAfme;OQlT~x+c?kO<4 z-ETKVY|v>Y_(%X&#v_0)^C|WeYYKz@f}kr%M}mto?!mNMLRaILg$@hm+$hdYE1<0s zVUL;zI6!2XvCZV;)UuhR(UxBdas(7YOu+2$o!phZ*SV)Q*s5TtG{D1T(Dl)MFA4J8 z^!0p1+xx-}K_HrP_sJS`NzS2%0T2FsRZeVV3+QFUKby}-1p<5(LhVa(>1!~py&4F+ zl{-vMNdE6j={bg7?oWV>*n}0>@Nv@~N2}~bZMw^)bEbOegy`yaZE1{a26)#1@;(~r zXjlnW6{z9wk!9k82k%Mhg(UFR;!N5BwFry)mK2+J?vJEAZgjTrbHTqeMIS*q$Lk0Zq;*W` zj!M^^Y4&5qd|IbiNQKm5oB2PwdyJ_>-1~J~Tu}epUZudl6Ekd1bgat;0R~(>RfsmE^GNQ&iDdow@$(In>CO`l;HKoW*909E6J!wB@I^{FWtz|lV5be1 zX$>5k^F3`}cQkOHg$o0{^T1o#8v_95@6(j`HNJ~(she5X+S+?u9_&p78rx0mpW{O? z;}m;miG?Ws^xS=o+XT0f>g<^MACGB;8nLl8f0>}3jwm)jxSwLYN7&JASX0YLT#s<4>T?X*pkmnTArf%K@p$>d9el^OaSPNv!@UX#vT;-)F_wX21ra{qnY2QfIzM zN7YT7rI3H*Ysqnm0HMGjqo0ePyX$I$1BJT*wrKuu_vaewMB=axpZq5_-~|Lgv9+ZD zWjNntpdtXYzM*(_Gtm!p)J>T)mScCm^RSgA{h$)_sLyrD5%DQK;OVRp6P)O^%EpfF zz<0@w7r>Ai2k8I*;z?i}i+}e2)_MvMh$1ujgn@oDbwQtaxF6(ZoFG~7Y$zEIb zf?lWYIQ$qeijDK!dF&x)!{>+UsIlD6t(2Wzvt`5=|2g&OLr?$kB)WH1$^jg2^OpGU zW(b+pPCF1Rt)C9{N7Lny=X^?kK`N04DnN8v1X-EuMsgD#xE~mPX9l^MB96H{1w5Mn?7V!W z!?z;}yOEyQq;9oa>apaXZnv8&*8>&MleGN}l#OvB3JY>GnMmOrQBz+AuKs890|v;! z$6sUlmp~{kIO`Mlv;GI*>lL;F3rc4jl=U_6%>G#ofNh1FfXKhaw*Vp-z(M>|3}bu> z77QBV8$w4}X9TU6=@^nty!6z`ulp}(4v67U$G4f3@o%GU9_-vs%c)k36?EewOs)bp z+Wj~4*gJgI&yFFNGo8Jk>*tO(ny}aR);7i%n#D@3z;X)&XvSJ`;pX6w^+RkIu0hzm zMT5)zHu?VLh)41ssnTY2aEPNJamCM51#IUn;{Umus5_yM3X9vlzo6@hQcLNtWyl{{ zw>pP9&@qF5JkK{@0zRAh3py?YoX@ham*8A>=4peW^!e&xo_z7wLHw1K>n6n;hZM|z zb^sIPPB$zF7XSUSHkYEuukdJjnE*NkIPKI)!3Gui&E+e^|GCoiw?e_xqv-+~DyR1$ zLFP>iiWSSmUY;9wvmf$%)SJ!hHUR5;IZTSY`kFosGhLC6Yjj!TsXa6{Uy<@XrjmMnmCNp`@M7s-<`=nl{2X~acy267RwuP^OT%gyXe=@vKlDM$Zk z{KpR@aWPXTZ0y4m1@X&yQzZjunr4ybHep_K;K--=xlg)fS9KdZtox<4A$S|dKE$NI zRy6EI5JB5Nm=*3_i+W}I$RE!Izrvy30<1hlIi$BTDfSb6Px0V_?qhlH=L6rj+awfE ziCV92W;YDlk_D%Q|DmO~Id_UlLjnb2rk0tgHC(k6<9viyUm~xe=Fz^=fk>Y7_E0UE z^K3n3;s?ImXf3*hj}Y2v$MvO<7H8u;=>9))j>Q@aZ8ylXhW!PxOU{U~HcT;aZ?e;- z3<$56uY*bZ1t03m*`-9yUZ5IMoKZ~g?bJeVM6cx+Qjoi6v6+YP6-x7^LfO)2_=n33 za2rHJWgTvi{-}Ck!2Rs=P?KcN`OQVCe64@d)NqI=iv2IBlXW@_Tq*{MB;5 z#;;7%NpmhY`Yv5jG`004DV1l_EzfVBSVlwGm0cvM;VpQXc^e`-Uu>9W;&GdEX){|i zV*E-(ulYTTGq)`up60$$qZmBrQo}UhVN=u^DgN zSed`J8Be(2e2P@_k-NI$Tn_Ymr0~%IzwpS@C|HObK2E&Jv~FRsPY!eIgv>tB!Ko7| zq&<#NE-wPi8Br3~BxG|yyO@;cVOtz$ZatL-dU)HUt^mHS>Clz&rQDoLQu-|>X8fHwYXkO8V)N){R)6)3Y^j#6vbHJ<#0z7-QmQbqErPz%I92zT zAAiQ^2h^UnR15U7qC4=@FYC5OBh70`k_XQH?qu3;ad*>vcKl}u@RCrDiZ+*2apW>q zd%ptYZ1hdvrc=?p%XU6zfA$7*TCxCCZnkR38e195W04>cK#pov%VK=Z~c&*eOH&;hlrD^14vBo9I{8dd{G^{mxD8h8eY_m z-pl+80;$#5GN?-HC5}i!gb`6!D;*HwnB!f!{s#{sui~9FsUID z*n!YJ;e1U-$ySl7VOyWQ1VS)4?173g^Dk&YBe3h_u#znvowF<*bs`@1Vo-K4{~kF} zem7^crfUQze0l4&8O`6dyH$Rck$-R7hnhE#TrQa~CPRAoO8&8=EqXL1I#+;#2mKJi zo>L~+*h$&8Sz&8#5A=dosNgWEhEoHn$+rAyg968|w@*oGaF!0WwS=1bRNe{SCe9Y6 zPSAlQ6SxE(t_nlA)SAd+DwIDgWP#S;x6*doO(wHLdCoO+c0;1Vz2>xa1$d-+aHHEw zQVhLcnwSci)90^+K=bTh!tgkN47>o$SOtW|1E|cBCZ|qnqREqKqNxx9$qSW|s#ofY z!bY6KLTJq;_MUTQt`I-d-qf(eni7&maga?!iqTzy`K)1G?rBS6xlZCV-b6~ZUMBDO z$OM(?0~*zXpv+V6DAflVb<&zYMaeI6TO-ps7~GKl&vuLq&b~Rf5S8H?+0}nYnj*+& zgPisXi@Y-@#Ji(g75<#!aQVFDHALRYf?Aq2{k43l3U z*nS=0r`0EJ)5MjyP3UD*)7n#hwZz;tpX#LX>8;BG?ZZ!Cqkg7dKdM=4xK$?Ac=+yb zQI1Oc7Dy#@WTYAiw-Wq_em+|;8?0C6tVZj?{HTydiz0!GySQify!frci{(Z3EAWF; zy>lZiyv0*|?AgUdnd?@uWrVUNW`@fa$ByHD-$}JekhfPOJ~Y+OYO+F6$nJIh(`S|R z%2(*Mxi8;n@RI#bSOPTa7H%i(D7clK>u?3QRm598ZuK3{BJ%5BvAEqHifVj^#&am7 zAx0M##P+|J^Xq?+`#3?rbI$6Uu5m2tR;;Q<2KQz0A$ymeiRJ3=tSugL*YrZqWs`m{ z)Zjq`fdtLcDbwb?E@!8j_f#zVqqr`>X0vp9M`;)!dAzov7%KwI?B)=KQ^pfL&3CRMcHWsvX~sAaJ>+??HkU6#!H z#IWfPbDSwiwL_`D*C;9UAE&h9*)Vl3Q~eLCgx+qzDtS_2f?y_-53|U9*>y#+H<)+V6~}gB^Iiu|rV2$buL8~1z&6d#n|En9z)^vr zaP<(*YxRub-`whLRWbS7oQ`jO^IN(WJvpwGr5>uePj{PHLCLfa5}|3)SCw4hF^9-L7jA%ocd0jCRI~Q3 zv?T{Np)5e{K*&m_L(;zX>a6xin3*E0C8Twc)8=>}j_E;_B(d1%&LtYD=3On6yuJ(( zQ1Hqf4V4M}3nFtLh8`AM-30zFoM6z?+Fn`4p-Ck8cvgD)sZi&#rtjxTQA_;8p6x5j z9%3qbWG+F;iV79!2!D;n2FLNx)=m*W~u7@g1s4-%-9dZz;$r5~k#&RvS zk7Jr@v6t*;#QT(S?4T0rby3JOQ1kR*z>ezJETQRp%FWypf6whOb`_^q>O9#InJyUU!xWL1Hi;Tj z7?qOaO;Hc%`J_%fD~Oe>skjFu0`nkS{2xmFLn`2dkx^~<-jlP576vCa1}#s?62NDS zPbq7hUt44vXn`Jn6=0>nwK~s(2j!eml@p~?rD?G*J zrj**XU7cs1$zO*;Si?xo5UHhKz-`XP_=W=un0Ou&*@(6Iaz!C?OYY&rr9_qoEDO|l z8ig(YTR=lhL-qot%l>tno6?vvRuUH7nu4s96f%i5k!z3Hc0^g-;Ni86bolWuzdzwr znRpe=_>Q(Sn@i{$G@vzvQ^t|QsYuoq}+PoXVRKPsYg zTpS09YflB>2$iM*fx)9-wKB!E6~fq{|1+;Hg*W5RNtIdh0;)U7oq4MENmX#qY;Kw9 zm*MZ#JboBC`6(~OOlF=kKWt&=I8?9{v%*Nu+(Y(Se>IINZW((wR7qr3?wB-c{UV+$ zHIu7YGASwx%&~+`I23v%7vvY~Cl8o>l)Vy`EarGDT$1nI{BHB*Lt%FK?ZtyrPP(YC zK-I);lEB$Fg+7cwih$f7Q{fTGk=Pgf*ag;Zfv2%8;7=NB+UsT`62xHVMv?$gKKjot z6NN2iw_x+mTodZCNVq=hdh`ooO}?6@#mX>Ax92UQ;cgmrTL$|{^>=>m?VxF`+B-Uc5^-?H>E4}~P& z>gF#XoZ0xkC}+B>*31E}RWu}5JKy7lukfE9od~^#Ov}2McG^woip7JKfxAi+Cb`rj zhMDsJv#WHO{eDIaO!Ep0WcTL3y~fL5NuiV7i~VBQeYJM=jqQJ!HNo8y_1XW^nclGbrbivb8>r!0 zV1ryue$Aeq=X!~VuQ`=;oUx24W`3xNxSQ$3+TET~CfeA6eo8Etf*OCH+Y*l|`O{W~ zKxahlU7{4vYtA*I53ZDQzn8J6oknPu4V1G;PAbZf;*CzT;FDB8`CcWZt+52m`iq#` z!bAvnn-63FrS%rUM>V{s-;kPE9K^=qiP%M7H{rrw zYiF5iVtA+tv%M(E0=bYim7{B7>cSaStSEu*C%fbnA<)4j5YhvsVHrm{Rr&bhfqqS) z5x{4GOhDy!b2Yz!ybnJc6B!zfkFWv?A~I-rnmo7%A%{%kjeE>iw!9Mv((+A0G?EG*+Yhvz7K{0KAWm6F|#h+h5$wLuFWxNI*392XIE zKYu4lG@{>MR?N@AdKkuLp1uKYGA-Yf#4j`_Iu{zweGrn{CUb^q!2!u_Ugz9r}BG#y$3 z@75!p;b@qS}WBO_p)y|_F-z_WHXd(u+@uUwhb7aq2RY@ zl+UXTiSfro`9n^ab(vizBKA$R(HO;~&lq4CDV|^C5WPJv@v|f^&G|cqj<$P_QR23?X`JIxQe3Kw`FxoA;P^*fxn;+4^B$S zSHo1*EXyzfbLJ+rBk{y;ymmhfvE_-1x;;gViwcQ1h$NPmr=5D19=FsZ-8I$^ogbLr z@+@@_2QaOo%(%>#nA>TpN|aBLpfw;`lQOnth`lG4z~_?ecIQxPn-3^`F^spEiW26E z-v$q#0{QKh;CtFbNT&4kbWwQGn5CY$cE9y63zfRZij<~DIc0vJ`vIQLhjTN9G=f0z z`&e5<8Wq(uiN-Qb=;H#E@Y+)pccroVh9rKTMWY>5bU_G{$a^pH{GZ-K;ld zL(%)+N+JyU!8Jb;c4)79?8_ZGi(g$EACM$9y$S~$zlJ^*RN5{BrVNe@SM*7+wdz9l zw?{;`rgv!JcX)@Ndgr+@wQ0YWKRJR$hy~l~c7Zg}`$OeSN9%Z*o&K;{Kc0J5E%s>T zH88@pYM?o***Pw~CRRtx_o5~+*e;Bt<+6-QLsD<#Qz^b@kd~z&f&FBrjdWU-3tEX( z#*q4V+tea1gCfL&rhs)?SZ!mRZn0xYEE*MAW;uV>%LYSi?WuQ@;W7k5i@I_AY6aMn z>qWTgzr(XYv1HaoJ-qB_6`V6oo4TAGa66DF9%xr6Oxm2QMAO$musFx%drg)A-HRO< zD5fRro$U%u_;fkA__excknWpzbjvy8nDlhEF1|;j9?iV;0*Vb~TAdf-Y6_}B`9vzu zT1BU}K z#zzcFLqEg@499&WcQ8QqIa-$7OF-{y$JfS59{h(q<}=RP;gL8}3E1#sS!Y!9`zhZT z8cyjVpF83)ICq8a&y3Dq2CJ($fRTn6Rchhz<*gdOqg<-eEKyayf7}M+$eg z;s;c1>FkA_p znkj8KXaNr4o;4o(u`(cj(NyYFVlT8NLsZB-trIjAh64wAy&0l~3&6Ni4=I>nDuOca z03}bWf7Y^AgHj)h@P|g7V?7OM(tt`#nWSv1!rg zZa-T&RYZGS)7hjJ5cYD(=DMlXGP-UQkI$sHqIi78;zo(GZlI@JJX(lCot;3%HLta5 zn49dtOQBHXX!O(sKbN-nbFS|p2HO^=;A&-3^ZC%bS?$w=THJo5qFcA#P#M+P$YY&7 zaXo?L?}K~BBFvnF090gUMxDbBAQMdZrnDHz;4=Mj>ASm}WkF1CRZczzoV2YDE`eX`qbR?Y8lE}YI06crvdC8!f4LwhNk zH-pbnnP)0zy#h#sAD<%jq%A_ue@v9dR2rveE@k0G47w`Bu(0e{%h5z)h* z&KbVnYP7dD2LFQUImz4}h~icLgNu4IZno{&*`45MsxiBO*LMXI!faX3 zux*G_DVn$#=U2k?s*DOdX42qv3aefAZR?7Z+JR~DiaKMm;rlRdEFc|2y5jUy|4!{Q zwEkzPOy#+t4Q8CDblS(SJ#RgDe*?+*JSWe>y`Tr2o&Sfcw~mYQ`ToB_R8T=g1SA(} z>26p7DG@1Y5EYP;mKGL4Kw3ajx>LHlq&uWLq`Q~(o?Z0)`Tp)de7LaeUgw%QbIx;K zGuN4CC$Fi+^ohOc=A&ZU!4n~CAY2TleeS}xsUpy{(WgK4kqCb8!S(X%cQU>1N9o|4 zGDWMLGuX4*bQ8g#N}I3RPqpbWiu?=+O;fp}_z@&)a1Q6!qm*y0{F*=Y4c{R7bvzXfmsPsb+7413pgBHq_9XAU!C9LFihsI~bGbb}% zXo+r$NHWNUz7o&6>-b%FO_Jjw=fPL8M$Al+R@sT_yOgageAJ^rT9)MFu1v(Veul$G zd9Li~ho&?dVB`)+10(DS+5E>L<5pUmxU$;}so;1;aIRvq-!n9=z@$LLKK8j^822}H z-MpKE%$^rTxa$I$URBMZ`LvZHut3~jWQcHwn||LPO$C1NcNy+1dHV!9s?96CP=lv= zGU1l;F2zZ6Zc_#u+M?zuL0Yzu;&9@Fd5|{kKoUaU1<1kf?9x={nX*7r#6B5k4bHl# z;U6@-^Wj3;qeLz(8G`_uSNIjUCqBsdP(h*)orE>`5x6FeG1Wnf z#EBOn*M7%8ptlyHzGzvs@4p9WVSolY%9s1{Oy9P)bR})a3+X0e6zeSbM-x_XX+RS) zho$c0-Pb6U&vbKwK3{V9`Q)&W2)<--$Zzmj!IQ4_MH~P;dv^HBACyuci#Hru?n=55 zyC~|3M2R~;a0Sv{Q`?3qh_#AU5DE`Bx<8~(Oi?71*#9Mv)A6Op0_+fZ{6k$k5^J1) zanPM#-a;o#C#{d!EOq3|l$2RQ+)YsZf@|DX=^KB}Tal?@fAH)AAqM+T6EEDf_pW|X zqrxAO8w||3-{y;Ck!M#+m$^Tp3L|(FaI^(Htr%8%$ zsL5oK**>|4=VvZk7Fg4N-7)Q2>aCb-{nrw6tn3IhZ)ksVO1v8;qq9);`Qc}EmehFk zO{Q#R;UBe`1@}bML*%69>=-4VFBu#tMWC$?x>NS^@>aW;F?8y55Vw_Nssf_0$fDsB zC5ciHY#N%>nksI0$9;Zy=>)&b-m2bJ5x8xg zVA^P1X+2oNy=oRZkOeXJb-1T6s}w) zIXPPNlk>~Yj8Z|ToHM>tb%l8dm~A#GTI#G@O=wS0m4rU*B8y%0c=D6LSKx4Q$an0J zV7zaqaO2qI;18NE*rtcC5TMmPf4_Hr>`;lF1}r+4PD#$;;?P8YZxgirG{$ZA2dxyx z#yLOI%+*%kC`+q0*FsUGszCF}_KRDV-NE8gI82GfB(DeOh~o@rpv&J>nDCB-te`5- z&BX`wIU3Elv7|^17FmvHZBIXB(}4@bubn}5Q#mr=$9f?CdkNi4jV}Cymf#Y6fvAT| zGK99+l~#ZyM6ihaC7B7Il4Z4}FzCmmJ0wj;w9mpCyAb5CgF(snxXFuWh?iK-&BlAa zuV#!>5C^>i=Qz<&FNW%&d47*k8`x^fvudAy^9F>SXmI+ZnO2GY$@wrL!(5nf!&i1r zOnyi-#$JO+T5waXkjjB*Yck0hsc9%1Q%yVoc^Dr|xkiM>3gX&GV zVt{U2(PBpZGqj*-mhE)BW<#q@ms?=F9==-a?_=yc+NHybVUT!iv!mDb9Ou^CrZp$l zC3JT*^~=kJAE5g~FWSg11zl9}9~dECQ3K^i8_sZTxpkAs#wo1TYAXPD_6OP_h6UO& z0WQima}BQ@RQd z$Nv4C)oXo+q|PpbmobBF(H2xOt3_LHeUBEywq7nza(gXROX&}XTka+rM(5|zDm^TX zrqZh>>E$?rveC~Z9lWn!oq$~+pr?MHC5hnhjLZGmc`-k>v-4o25s9~ICfUx86A)ly zErKee#Czs=P7)`zWzm*PhvBwRsJ+$W2xp^711g~}O_Wpn?5{ILWLp)SY)vEnpuH`q zP%Yn}4mTfys4ZqBCK^N%o!jMdg7e(Dp0=G7-+E%=TDNltelhA40ro+3fvqnmaM&IJ zZa6T59%+W$vLvXujR%^B1@S;boep2q2>R}?DZzr^*kZ7u4&`x~HBt4eYtS8V(c9H# zMwSos-dDzRk%Z!5SDm6$*Wp`mT^3 zYWVkSqeUluV>DR@;(}x+X6Kd8lZQ)S=v2l)?A@Ypt|>DljH0 zU^|h(5VXO;xq_N1IytAonFpNR2uFUU$?YQ%D2exlQb~PX#DbirC&%2apJ>0)&O{iO z50y+}luhc5pT>Wbw{A8fS8{{|FEBl9#sY;3Qc(`{7~3hd8M?Oxy#zZv;qnw<-Qoi5 zM1dj0fzlZ`gspE_@1zUnMe!7Ra72V`z~>Szqm+AQS09kn9ZoCuX3~~0=ivBB?jD6r zbXH%z=I7DWL|Xm(&BaT{cWCgup?cF`CH85(KK82MyGz00RrXtwp313%8U=0R^gy}+ z%l9oWrOfVe9Loj6u^@0sfq5T@k~LtdyH+c1g9~x_GjR37N_+Bo}^ea6vO4d?}2JpenKR zcTBDDUfoh!Sa=Y&U9Mv;QY)5w!d^hsr@N zY<2W1*y!=LAzY3Ajo*)%u+^)^itO}9xTRdR0iIi*N=cczS01g432anqD7ew5tMS3c zq!5#;?1Hybp5ZdBrq7a8FVUd~#ve4vx`xUcU-~wD^Y?rgQ*NcNTpn3I4$}TI9F)LhBO*=a z$I7AXA~UT^S&5xN>Hp~~Y{#$qc$)Lfy{0_oF>JM}UDWc#U2hos(u}JUTt5Y#0B1nO zpiH0#BBSAT-Rjb^Qaetq?)IrvU#r{Y{hOKCWxx$YUEGktmNu_#TujUk`)mEI??`9) zd=PHMN`|0$+J+I>l65Ixy*&k;=0B^8Gp^_qmm@nc7XYiA;4Z)9KrM=mTWltJsL;LW ztSjAojD9<2TVA6!=flEUzg>Q+gbLjpSE1XOMXpZwv!`nfS4YsZv(ATZq_A*xPK{NB z$Ts>Pv>(Xt%Y16>fmQWHx)|oAbzfVdb@+E1!kMw)&Cz1Q>W-A>a6s2v*z(Mk>%`+o zO+4VZj9330uOIrl6Smh2j7|wtkW}DgYESdO=*({$*7wU_0!|E7LIxHP3I?x%=wL9F zg%u|D=nq)#2tRWlFn}Oi}HPyoRh-t*DYeWO#7u< zDbCMW^Id~@k-QU)n~byKH*rMJU=tt4ar?}KjYb80px(2~ek4r16mP}2E6A0tLykzf zRE49!^5r@kke8bx!KRq$pIA%xAi;3^aF3<&!C&<4m0u49qR?P_Qv){zzyNy-UGpHYyma_Eih;B)4JZdlXL=*{+>l6Bs;>?hAol zB0w4ud}Jw{q&&JjcBuLdav4$GUV}dW?PK3!pr9nADUW0o9Lh$rWcN-^?jq-o+=eC# zwT(Y*#p@#US^m`n>i&=pR-bp&5^0mchu^+~301uHi(Ii2K$2Seri7i|{49oExVmB3 z1t&rPB#(11eG`t>0P(7PmT^{qEX~d&=R_ZO8QMRsfO z8wU^$wwYTvG9&?3>R^~)?PHot%A_fmwR?KwtRCq+TIqP{bKJUGcc5n<%9N{ zukFaNY%$An>PYak|Bkw1#j|r&*|MHTPOJm5N3=*>G@c*Y~>4Xv#x=Q~?k5Znr2h0lE{|sTcKNfVO zV^=Lams~xPs=+Vewohl9nzr;v01P&T*_Sze|&8qtxH?}*cYAS zag?F-31SCx=-@D$PMb>MocrwPpbemne4JOy4s)cj=6}dosenxT{#aqIe{-x4AT+rZ zWT*T!fCmx+3;=Zd5enXtM*e_Ix!@rYd`b7g!Mt2H3)#?_59MCZiv?n>QV zJ~oz|{|A;+y8oa4fgr;j%HZJtUd6l1u8gfh{z37Nb>;C!g1n@%sHnxe*6a_B&MMDD zI8-;8A63_Rjmta;Dw|%>8E~8 zxHub9OqwI;K2}^F3cb$cHEM6lLC#wMqf`&hWG3(NXx?1^l1`Y&9lx|dRDVl0RVb>c zE`G15G_Mgez%>cv{ruY|Uz21ux5dN45TO9YVkeuyAPRxa;v#8LvV<7Saw_U~KzA*e z=6XhHz>3urn+8|;+u$Gbkq|p!J{?|{bUl5>3L{|Uwc~G?NAdlcd$z~mGf3i(d*nlX z$%{61+$B zC3QufY8S%Y-5;}#yKnx&@Nj#zn9y4k5Fw4w&G-xPYTo|GZ}-RKKLp}ToEdqa>76Pl z=&foVjI-3XeC@I$=^!O|t$Iq0zz~;Vr3`I>bs;_X6t>4*XCC=~!0`-E9|5I;CxD&( zsrUYG!Ubh+vdnk_H{}d=pZ%!ZmwO?YFxNZt8Bwp5y7MkqHP7OKr-$$!X!e)l3}Wro z0gw~WiBfWoc1-$KtP6Y`xU)EU2l?;Te*HQ~lzhYz1YP_)OGSmCihtl(69rwpg7woF zJ-~n$phaN2+1HNZ(@ZRi#E-*7YHDOjpW`lwzQW4T)6~>v)RDj*oajRQP~wMw8E>Qr zk6V@iJ^-RS7%BwzP3uhJd$QJKWkq|;G|--H{<)x^UkTt{WVU8d#C1UXVcms&aOb|O zX&0Va{)dXUl2zq3(#2olL8<^AwJ|(jevE>li~=#h%b$HlYqG*IZ&hXJ(s?deoY#i2 zL09ldPJ5!W*ho|%766sQ^6DCV1BwLSa z1Ami%*3H4g8hnk{RxfKwbfjAz=@7GE~TMbUHixhNG6EfNN-lc);l;t=IAFxta*tg zj6LQ|PiJkORw(Bk3PGQF_7p9-#<;=OKvyg<%E=;nDn&=`G|jp_#_KF!`!!{&5+^u# z7?z>)18y)`w>7(qAN>7nAdvt&f*)gZXbv`n%%?BG(=I5Cl&AXSHO=37dADyUP1TrM z?a_~Wc*6u1&}U*OBaji|3DL(K;+q?eMqvTr2kvi9%~y9bg}Z3yCKdknh2ocm>v#aW zE7XATB_tF2{yAUzF1aON&wlxddvKCyAo|yHKVcvN_MR!bc)Uh=cyjM^o9Dy|^X0*r zjhRbBi+5HeoE{XyoK#QG1FRLDIB?ILkv;{E#CoJt7nm}&ir01BhmyLR7dETy2!{#! zIp%F?++yA)qNY6C@IJw`G4in`$EL)?z6B}i#e_Ub>-5rso0=&T zvvv({^A0Ir_dnVa{r>oxoaPW@>KldIcUU+M&iBV0jof~iyU%Z7OucW zT&?twQY@H&B5T);k`e*Jp-%PD*F@kc;J*EIp4QYaM4Ll5$hPnqh>tGfkFX@y zR=`%zrYcLUQ~uMmeBIKAxp|udTC&7^cD?*GXzY1m2?`Ar8mkTy_T@+%z(vqS5XkCK zH8K_c&K`$$R{sVRnHqUA!#@-!t*Szj(AUk=Zo15Tbmu!MQSX%04tbSf2FllVu-$sI5%HK@Ha4gPzSV`P#NcQAg| z(C3R`kTl{Vt8I=0zJ^xV{C=%UCf$!p^x`>?AuFL?0u~=mNl$pg2!9IyjKVlGr-TU( z?$&#!?%9`&>MP2WJsqqG$X#NfwBqk$7798lw4IZ`c}F%qxJ}C-nC$&}lwQ=Q*pELH zmTnzlrZEMzQ4Eb26Y>r%#fBZb+x|fdQg$k%N9g_=%b6cjq5I=dBtKPCM1)9%>FF@z zl`}>OO}X4{p4xjZ@mkKs_o>yGPWx&iK9Jw?2nU%T;#-`k1Z4u4gp0%5*4ipFjjE(R zPfp4a)K;#$bFd-y+Mrz%Sx!o@zHXEjgTbPsCuT< zP^>wIJ2TbH(q}NyioelDKY5T{WFFle`iek+_oNsrsrb8yW?%!l zw9Sj&8`37}u4Uqd(^3RdtM+QQ{nup)-tMoAnAbJy+hkeB)&%5L>F=~*^ebNfCp$`T zNx|j#VjgsCojB^P&J@G{uOa&&^rAu^a@H*TpB&*{$@c${rt+=#pdTsz8@$3mc)ZHh zKPEJ_C5a|2=mT0Z@RHOn7tcTZ76O}*f8PmBjnMk|*k*Ll-&epFyLlNhdr|8O6--&x z#1Aw78_8*ZPWsMhT2dQXWSGIcB>$Vcf@ZnVQ8S4LrbR;_V9W#m9$38+laSgY579W_ zpM)#^STMd2)1cp``EB>+3gSk3R%a*E-o@+s{$5Cr#8P?g z&FO1ogD$YL49K$Jc=xY@1{O!ywIvcxkv0GlDIyr#fNdT|I+j%QDV(0_A*f0}Y;-Z1 zi{EnVVMqVD@b3ESU6^NoOi$1Rn)JC2YREn>kcemf8@e@EyBywjPOO{RmjRFr?~AVu zf>x?h3EFfI-jO|_$k@6ATtY3V*z!T-z3Drdd)Bu_?aOI!GRiY~#LPhzA6IGAEJsnb z1Kvgb*NaeTrzJu^4P+;jf{oD zg0u@+8AHx6|0&p+dLEgH;vuE6@ZAuar3(FPmZD6v-4WYjdwFFEC^S)?CxFePRt4hFCtko zxzXlpOgo@iR8V^mZx^bf z-t$#}W8XkM2wN6k;Yo!JL=9~3fl~xOxa7YnDr3)fI5tBhyKZhos8N?|-d9&r6iwEz zZnGiv=+hY18&RxV=1aI_M7Ns}-;paacQSOhjm-@;tInuiqXU*?>Kn{-;s8QC5Ob0E znEVhN7WU{Ada8K+`=;2+=$wlavZ+$K3!(pEq-Ja0?>p8GB=QsHdETIOY4ERu>>lF~$A4sw}jfzD;w*qS}pY)9u zVEmL z$Ut^lelKh9w&_{-Xdrq@>V--!!td*|Se#9RnxI!=7jN#g$zDz}Ld%B0XqgvE^ zIH?5;+M68Dl z+PS0nagf~S?EHPIWl5aKv*!X(`I6upVUHhMa{JGA#TvLub&tGxpey?8?}`XR5W5ZQ z;&lh~`lcvfYJMTkwCa$#*8{P<} z<|o^CvCHQbOaqlm5XdPLjx(hBu|=slTg$ms?H@F`ic(e2o^MO{i&%Gbu62cqNIoxn z3|!(%&Er(#3B8G2xVnC3&&u@+;U^Z9t0AS|GwLwwtnTJ})UeENNjF70&r~xPN}DtA1O zEk6pS2m3?_BI53MS!0x_&(_XxYNLNyd?;j<_`&Lhb(lkA)nvUF92~K{EGycC&A5N# zr<&v$2&g7sU1iAE!3N2F`7B*y=ho2+q0(rJ+^!du!fdk{V5hSV)%A{mGgCYrlw2nS(&(2?+Ljxf-6- zknUu=VxO?~lQ!{8+u_$stN9eA{>(-4k3!Xr?3aqk!nEC}_IPHB7w$}p6R&y`8(dDA zwpzL0&Ppt)Cy_|hlw5*9AHs#725F6XNs=(f(3 zFnl6*pr*CSW|zLHe5Re#UD#ugV<;5Wk& zoo-p>d7dDqcDM+0sx#SH^&Vt3j85gJXm9|_mWsc&GnjC4hZ@ZwSRN9U^%MG2f6y2m z7`!hO)jw-$0OKKtp z>j0l1e^#E!4FcBkwqVpz~BsEx|Y>UW#M#C!Y+$v)?6tI5P6x%4_jW z-GxChJsx>G9I-Km>I#}zG#Z}5 zJX0cG!d(-kY1tLYi!PtLHiH!7hu6HZnyM=!_P4ctWjSS9eKT+6z$SpSaBu-=5{3hr zaQN@_HAa*LOgmQwKudt$wz?0y*c>A7A~D`K-?8KfW~K6jO~4}0EON{8CIh98XC+G& zO8Zt`Y%$?K>K)k6Unc=26_2oCZAYLPxhc6O*OcOGnVzm!ecEtAU66Y{#^JY7i+&22gt2T~nN0gPc6Ke_RvJF=awWex%E0~KHAhYzVfMT3KxfpddI zkWg8_Q!ITPz5~DP0p+D)&>~+9lXOgLaq!fnye}x1hV%#hOdb9(?9E+WqR$gsZ@1SO zzusJ!Jv-shjL@S;wsPK>8Cb7aUUf=xqw$@Z_c;_jM30mf^)BbZa3EuHF?6-%`R0Qj z;Pb)gB5w!2!FBQM0s%vPGOi&nmZaL!QMkT%Dk=2t*hR;7#`%YInDGp72ry_*b_Xsq zTtS;gf&kHvZf!h(PQ@O2^P-4tU({zJC!TSWr1cONI0dI*LQPPMr`ju*tYnkTAKO?; z(T_Oq4_sUX!+O6GUte)=xhF;$^jS53i|OA$1AY#sMvyRMID1JosMqYAEb^4Y&0`s} z7diuJf$BMX?7WB>xn8MhKDjLqVT3hYP?#i4sQ>i}9+tB5%!zhQ)>K2N6WO-fxu-H` zAVKZ1&v2a?Q-}FBY;}B@UmwwIbSQjj#wj=bjNTx0WtsfN?c%SJXzD@Iz9&ChH5_i{ z-lD8%i2j&?IKPWK4D(r*M-0^MIH86N+i@U>ML=Q$onkOrB#vP<5FeC53A*f=_YcV& zQ#@X^eG6xgGt70yzRCC{YbTzXx_JEu&|$X{^l&wn9ivhjsd1@`fr1;_>$n8WzqA6Y zw<6Z(U4my~@wPUUaHI~PdnbIC$Hv!sH}2He;KXKBbV?l5WV zU~POKojD^Q*H62$fw_{>fq-+&%r=)olx@^5`Ud>2^)GL-dscpr%t;#&^t&thwuu_kYrh2F zi`&xl%D9njHQGNEQV`bn?4w+nK84Ba`Phq64kc?^P}=)loV0o`jA4uYWVfGx@_R0J zk#5%GC4u@|2cTH7qa+6~;&7=FwM(Fli4cM_(4jhe?Z!4TPYFrk4 zd0>P(9fnq2W)?SUkW3Q7-$x4jTL6EFz&45`KSuIqDF-gGcVIX2#skot}j} z3n86n5!UcuT#1nCSIzX5)EN1;9_aaMqsiZOPF=E0sw_ZlQL_83W+ntJ7Wp*B199^j z7C-syI?h}jDXh~@!!&ohZ7@gD)WWdMZ;s!hzG(e)YbQv7cuiL~Kj=s(*oUMn^*n%M zy-+vR3N0&K?Qw&$K>LB9XaBi1>oRq(5&IgxFng0hO`xA}7@crB*}ZHR&nbj>F-`bN zcxp)WbdVfJ2TzJazUi+>WgQ(;J~rk6&ETjfeFbFboBRYs$7PAof1MaE_C@3b4mgm~IN`Q*41Nm#+Vp zy3t;?5*V+?1pmc)c{7J>-QI#W7f}V8=oe_)3L*@61mPJIZ-FOKz%loTPS~43~6eZ^{EAJ6X4lb4M>X20zVqtoiEl+EA&>V9*1j39u^tIEqMIovLHz?N+w?L(r8 zx|VBgT{yv1oq>dFmyd8e%ty4z`zFpvcX_1EROh(U!(tLo;gR|+T?qsXiF~Pu;bG`1 z%7nL!18Vi9Z1t=ANQ16A17OLi33h@!g?#PSj6e{JKjHvh-(?MFV#%>tRIK$xVo47Y zOUPG+q&w?>tal5>CknpmLoyH6Z5Abp(qubbX#@t8lVrI2izBip8K~~ub z-3>V%E(&ss$k&-(w=d@uW0`Ju9LvFYw9d%3B?pq^CF;U4G&#zXIuk?t}>k0O+jX0?Bjot`E1pG+{``zvu}GSDJS^k98R@EuPPyq`h&RazpZ#7=1M z4;mZl`@rM_Ky2hVkZtA@CBF?*)hZFDdVNoxO1uP0bM58)`Nc4w*89eq=c>*JVc zyYz;(A8ecPYWKXjg>9p&lk&Jx&HlO~XNgVC3kp8Q<_aF8UXNAZuTMdv401G{=byU0 z?As#UKKW~<7hpxyh(hBv)1)G;aO{(o_zLSwlTce2Da8sxQOP*wZjOYKOZdXJnG^53Q*47SvS$iM?i6x!o!xT93JliQ4TQ2^e;>8Z`;`X1U!%X!kM8{Dv7VWuw z;MkIDsLIr}frMrNCMCywgq<{o(|BuCmcjfO> z<-CtO=a`6DG&XT#W@SZUME^|DRXYogx%kR!ciKBE=`?-Rjt-T4nF4 zf0MIXV7hB|SF4&}z|3pC;+C5Wcb!Nzt6b(>R?*f^nVM$Ehd(ko){aow^< z5{lK$e}rQ7k!#N#l(B8iK->UBujOT(?eAF}xP-n-mKbZ&&BVg+pjGQ${RVQ}r*4Aq zTz*RTsC(o@jR=O_l|1YD3(_9J4SArMIM6`v{?$x48dtyCvcZKi*qW;!C`1vyToF5>ba>F`eSY4T zH4Q|QzG$ON=`W)uq?g8&3@AnsvB~j_RmvpzD3)R}q36!+-&MQ6A?SH4#o*g#nZj7} zpHpZZA&paQ*FX8qd)Xm`_jIbt{eHaaTpk_05>2d9my2#;GHYMAZ?!En)%q5M$Hp4n z(V+AQK*}4D-kkZiFCQ#%W=#2<6T^*+uQjx%m802oeEO;Jxl#CIM#$`|=4ZQX{^^4D zVHu{*<^yWR+j`8O-5n{bu^qNz^{It_?WU6G97mSLQ;kyeDGI&9j5tgTaJWv!Y8&uZ zPFYUy&i}w7&Z6HccobLbmEs*VLkxKz@Zc+_eW)1Prvt)90ydi}3fmkpBJWb6I8lbB zi2Yl)Nqti$KgHk9I(kSMd*M7v6DAAx`P*!_(fW4qlrOM7cx5K~sJ7mF0jSdo(^5aw zvCvf8J66$*Fo}EK!Axeso(&L?H(-HUlsTtLYTh}S_I1ceoBl)0!LiVHduLmjt26QI zcG%i)k>A(6YE#RZ?dO&LN-FAALDSf3hLsOZ+MD?b4k20KII}n##79P*t_N}_N(RuZ zZPy+#Fbxepy$av%jA8M^xM^A-t75|I!CV44^^fs!*@%Vxl6d0RqM8SN5qd5~`&m&6 zkjo{CTOno!FGbExuWN%HXMFRk#Y zjRy|JODCMM=u-)%*Ch>2j=haS%CuYfo?QtllU>EOtg0U?zL^Jc45-6Ta>~zpIwsA{ zouDB^dpnfvE`owH)n3}w9$X8nb;N@5^HAOu9^5(8SriCf@exXF1(WlkmsIhtfyBo=W*0C1Uv}2e27>0y#OV{~5fcD~Et>qnuOG&yP__jp*et zSON|PgmiAQ`0}3!VS-)Cz;)_;OK7rt0B>`a{Zc~BbaW*;b7o3Qui;l1*O};hgUWVB zF(ktLLHnnwY$!_@nkuQmO4+W|C7@-XWDR8Anop-f4{szW&&fabPB70&Jexe>qejHs z_1S}T7E7U=sT?>H5LI%fWIr79U5P3?SE35;&oB~!ZR3^vscBO+B*zS|?-i<1yg_oz zKTYc`)6247_qC>I1^{hbih8FahW_Qu`81%Z0ICN#!$T?OYECLuUY70F_o(qzowkGC z?s4w*7rNiC1PkA*inqbav8mqfE+8P60@je&YU@zg@E{a=w}o?UuO>QG1T)`rgcw<>_fL7m3?ECF{8Lbz8xDUE~j%;7x=6J4^=m zv6k@Epe2^l@VdXD#bH`>90`V4W#zjwnZe4+-8TvUC#d8*WXQkIVVGp8b{$VyRyc*| z%aa5mg)h{n<<0X_cNJl0`HxKqfV+Ygfr#br8*qS7+*d(;5AZDGw(Bp#5zKgq?2eVjeb7JUI z)TX=?o9n+Jv$Y)EM5(6Ve-jg$r$va@*weB{1Vla)%Dx3>+|k6)v$Ci;C2Z-;S9wPw z3j4>|;~B5H>6~a3SV*uyNCAJ>cz)2gs0#O{-)TE-2X#|dB0k|qJ%n}1)bD_FAIMNH z63_Jq%^dS|$b4(LGWxAIZ>ZGoY%VP!=8|5+$4(!h%b^L=8NgQiTcot421*plcu0f5wuOlI(aNo zdXB=S8raD$ERe4YI-_v02@8}AlQQ|u6nbVf0^3P?A*X3zm8lvXgoe!}Yi?no5k8Sw zQxjm7EwV1lmY3JxY%pi=W>uK$0vDW;S@wQ@$el|Ve;Tjl?GrUF#ILO5HF$PFm+(F@ zO*DBhj9pcNTO!x@YzSw%9)7IX8}aGw>etzsU<88gbYO|^Bn2c|e*}-h7FeZKg|E2{ z+yW0IWStGINSbP0aKYTzF3#&0wFK=0=vC|-1SJf7R>G{h61MY2z(W&5i3R4r_)e^u zu{f#JNtZ>zym}zhG}M$ci`qbjxAp$zu%6}K&a;I=(KI{Sd70$>HzodGk~F0-D_28Z z&7kd;JFOu762VOwpV{L|=r^Y3iSqIUTS@Bw5);K-X>(vEaniKnH8cx0Y%H%#^C z5%$oIY-78a{~Qyu_WpJVuNoCD>=Evx3H{l-RE*EKudt})Mp+R==ObJ8adJF>5YqPO zqUVz74i7IW{RMNvtPcW_e>!li39ZMyywuyvH^AelA@ za|bj=nVFop(q%F$nITJfy5%WW`=#}hj?yui;pdNOBv}UD=*_V02DzNC6!lcY+#tyA zQEFeFj`L-1qZu|hko2;#H9fu9gUybBhI~^B+i3=O90@n&dd`jhs3h!S;Od=O?-8F* zKZrgG#T-GGlNYz+&suHm`tJ&((_d)0Lr$0Ju$p*(2-fJG?7@D1)fRPw>z(YXm^>bP z+B98Xi)zgbe$N@KBFdE;HovFX zWUP{B$CQ!sRa(mi1_6y}C|0k2<_ zL%Ia!B?8>kaES(vxuDY~EkEymBjqGF8{?K8I6eK4hc_uXF?cHipC;nDOMB%P;*PH_v5T&g%Wn#>614tXn z(^D_N7`^gQIXfek9QRWL3#H*@4QEf)vvjJ4a%;Htl{XFq?aGr(u4~f;VACW^9#EfC zERG?<10@NGb8J)ONQk#qycdSaoI2;wH^qLN`akU&&YzPcj2s&4TG4J-JfzNi^IKY+ z5i!Z4_>Najs2PrV`O;?$6h1!|Rxa3nxB31^@8Y+L2VXYmYw?JMTU+lq6iBJ_6`PX! zYL#f)XI|=hr8r)s@Kc`+)pd};C!c|KK4@JcyTpb4%v_123-=b4bez@CQX?08FtyjC z;kUbq*Xv>I^JH56w+oE%LqrGX%5X^r!s*cZkQ}HyonOfq_EcwV`kSN+sLw~d_RQ{< zJxMs<_=7h3!_==UI%YqmM31CZl*-K3gecX>3ht8dv+S*5r5C;TQ{z}ejRN9)&O8=s zP(NhZMq{!Vmjg4yMr19^0Y6y3RwFKmPx`cifU?Z?U+V>p&S;P0v4o@<5i6!-=HZhE zedFSg>ni+%#ypHz!>vS6Z}Okyec-x3DHWrNFU!n6X>`-bIykXSMMc)8Ec5Nqwbl^t z3KODkSOyeS$c=kr>bw;BoI?8GAvPMnDuw$8j5Un|-I~}4=rbQ0KiOhar%*!5&J2pr zB$?;2rj8xC@4~D*1TwpZ55hamL<^?8e4Te?GlTN@47GYYQm2ep-gE}yZfWN=hL6Yy zti@>BxvVX5%6;fnFKgqL}B^miBeV2JJFXq7q0DV z^ebG-tQq|4U}n-_CS;vqkrM60$h)$~(p|PIVe9RUCjRB;lu=g0x+B@Zo6Jem>$%Dd z)^OG*(7ZS0y#aOEW_R(}VzIS7v)ZXkm7`)6Wbp2DQZU1QfowqHFh2V)Ts9Pqqz2uP zOXK99D~eSu88IJsH($q930TOFCf+Z8B}8m!^<_7L9?dDIZ$pbuZBe1zjGyik2-2rv zJ$e^&w*3w#*=3Px$M)A&ZiUKKe!5j!yp%7lkU}vNXU1PhAds$1#Hqd6ui3_%Z}oQ4vW2puxzpKA z*Nj3VEygH9R^P~;x!drSEZj`4g$S?Z^^MHo;KSG#|beV1i$$KUo<29;RAjiVl0)w&c*cLUKXaIOBw94Yvy!1@RT)*J-4 zYY6!NUn=cLr)n<&Xe$BI97q&RAeLXfm%R}C7<;V0zcE+4xQ2??JUCjNRO9u@A6`a3J0>f8740RD8 z0F#Ke(Vxr%YdR1-Y5_w9{!{~C(wGW8IfMNy*-Rp`Usb4xpO&8SkYI!d{&oVhpSSPa z$An3kiCDqY*x31Gfw!y3*tuB6;Oo#LQRpbLwEz^X_2#|Pv30oypD9Y**_PhVjkz~q zv}uFN90`lkW8lj1UtzOI1M)yl%+JtK$avQF@xBD*B=c2@LX@%~{Jf#%CI^zV-|f2n zqk>N~RtmY)xwoX`1#Q+beuDhO2l5lnqbZ}YS;)rUE=(|lovon~RnA0E9B$ZUQU*S) zKNB$W>OzzSGF312PpRPYIkYTnx13!K*}qQ;h6=%^{xy6 zIF^Eh4j2kLh}1&03Z}iKmuX(9`V?lLB{wnqtCLfpd{oO?7d-t*5*f*@@Ad6@oq_(? zYRD#xL*s+eo2k*t{*}Pz$3qgFU; zdaV&UBNLUAsVwOI8Y>g+tTHR5`n89^OF5zxJBY+Ycy7%CPRmA*4Y%Bt)cJKtMnoLP2S129RzBrAx%3gpmemq(e#?hB>-nEA%e^{i*@z4lsfcyDuL?0m>OGJiaJQlR_vttU7JR8I5C_2ZN#0}Q>V zPN+Hz;-C3z3BRZ0tg13mO6I6~t5`KmX;5dL^wH+a+at3gp`~tmir%d^X4RbVDW%|N zAKGFRmd@h7XAB~=Enji{jyp=koKofC24FqIpBk_>AhvwMXMmk0!x!0q?Z;Y}i17Ux zkY*EkR?^qR^5l$67KKaaR-h^K?CGGYhby^=+LKe9;cRPzj31jEx1GXzy1rOQGTQ{f zn&mRjMtw$p9aX>Lj<3Qaks<(E3pbbZbg=49xR|6gw%AZ%*elp}u2$b@bheoOf&}Mr6yHO2YZ_`g~!hKL=Zr1I!;*ML=BhAPc=WWpKPhDZpz!<8+>~#yZk6Ar; zeAkW2H1kSHodZnlV$5|tGLckVwds`vzm9ek+k!{J&W_s_jE?X$4cWil)8+tJ-`fcxHc31g zjTy$f8&Z**f+rofA3<^Rd`A-f59D-&!bYu*A`z3pw|x5_h)mKykn3li4aH{P`T|}j zp8o+zU_$*%^}x$@f%DX*?EjpjZxtUwGd+lZ*jh+YEXUwf0CcG(pKprFwy<5DWb|z)AjvpLMP`CDMZ8V z5AI`!p9RC5Q0#+A1MoEJg=WU+q;(Gno_VpB0 zRSoOv$FNg+q_^$ik^V;%t>ceUhEC_Af>4qJYGh^TL~tXE?=mzkNNweSFgaZBOd1|= zG3s~0%Yk`?UF|R_MBNeyO8!^971C^xDFOBYG^leO70%!WO{d||=D`!hO=uj~#!(nU zr_yocmotvIg$rADG&Mqq!{ycE$yD5#gQwLxJ8e4+E9ed3tqF7KCbwn%w+z(Q`r$Xn zIWcG!Y=6X6tDhgkwn5N?7?bXNuB_1ZxM~=B|IfR!k`%XotR0C=mcXE7So2D1U-T71 z7bL|K(k?>bBdOwWn-fUVQ&};O`>;=iUFgt}4%oz~HQ3zJ4teHrPuK4>Zt32g;Sd|F zam9i)u2jcuvBnK3yntxx)dUEa@8?@#XqHZ;cIG>9*$`SDH*C(zcJSM4q0MoU8#%6Bc5y=fa-yCDxHI|bf!4hQ;f zt|^Br9je1t3jTC&Rrk!_dWkK6*VHe3H_*V#o>@-r90oO2&b42_n0>m?_bzvNzwTDh zzm9b5B<9JI>B2Ef+@)*WTXv|chPdkygT9eZCd3WCy=ymU`=EK*MkHoB*}I2D12Pa;W9_OnsMznP`T&5H`A(&{ z@h)eg*6t6QaOR9KySRmkY9CUK1-;bAeZRwg=gbKjR!qfEsSlp6%eXeB;q((plqK-Wv#`tce)7vR)(n+aqRX6a9gOZjf>Z*> zECqX06Bu3<2-kQwW%zBFaeL8MwR-&y%KkOVH8Jz!e6HaVP;fJ@iy-KhvD45J?Dx#r zZWg=)#K%@s#q$oN?`v#LF^1iSoa#={Ya_-eKe@J>J(-Shob+3lDAQjLdM$Z?vZq-= zLhF>$hOhb85x?As4B4`CufC0TZc0RGAIS8Uvnz2hBeiEdhv(A~T7%2h)+bDkDB(yU zVeOfHhnaMQ$lW>h#2+I(2jxBdDGUu|^(2&^sGW2~m60-&D}q_+eN3w@)UgektzpLa z3hd>vzvpD&ubi3j(HS}v#CKF`y4}v)OvHr7dF1+DzT3lxswVajNSl@k1>u%Htk7 z;8)I|_F+FFaa`5g@&_)8DqBjX}Xr zj=@oei#O*h8|U4G+k^cW7)|yu1t7$SuGxDtL*Sg30opm7=Tp8exZIO{d{Gy`;^~L$ zhZgJmD`)%aC@h-47WY{^@S0jVpI9k3Fh#YtzIZ9qPM)?fkiCpCcan~w{+`YYoExHG zXkwk+0?fBm%rk+1AUii;9VG)=CN}{^1v}rezyAD$c-#bEY0bvq7axx>4%&xYhu7FL zxeJ0ct+0*;vrnBN#v+1^TxZXoE=?ZYj$WawG;St7-XU!~_~3C)n5d+pb7(ueH;Sz~ z$j(ccaT9%nZ6(m=^!Z_T@gj4tx7FML)AUcMCnb zgrL&A`1NPG4zFHid4~Ftd2hL7B4eN#G5mVrG;B(wW`!@QYsKei!bYjDAgb-t( zAor})$zj{^)$9dBV)m@&G>iApHEieUi)=Rv9&6V~h(_x%~X)}@MilSFf^O9@bR^Ay^3Ca;Nev2SKQYsByeAh!S>Zw zd_~l%f9U}^S;b3_$K#ub{@?5Fl((`Ky~BRFWcE>eYY!Io-5v1MJOyWY2u|cVy^43!rZ=B8)h+ z$o^Ljp>TV3tW?0UQgQDjA8Jb4Vrt)@@@lCjh3IUz?%RX2*e7!Psq{iiB4!rm>X+zT zzc=#j;e)j!@uiG_>g8^^C)};r1m8$9l^A$4+z~21nR@=h81ZT0T z-8N8BTU!%Bsxd!tu6v92hkbZEd5d##T0uokdOP&AUzC=G!|RV@upnQKKtcxy~D+Ol55Mf+vT>E7lRO zbZ7ge5b|-8D_usn;OnsH*!7??^=)R8@4s&5R4~|25Q(~~w@XL17pLS2X{(T_Lf`At zQmQ!S1z(3IfheHLT#hIRRc(4+Fij*j1%RsAD;m)^T2~}D^zBQnmY5}z;sfX*Ey@NF zx~jCPOL8CToH*4@yl$}vb48lGIO2FP+8T3e(fs*WDcgd;BU0<-$dYfLJ)0&;h4o2oJ%R*4!g20g6z^)&eH-jeLZZ3=W;NU>8dy4s%-b;=F^W0*3IdxJ6^078Rdazy z0Bn=Qp&jY(%IQ)Viyu< z2=Yk0=)ns0-!27-WB<3Wb@PIo@|tbSKAso#!Y2peF&-NM-p=)6r?uW@CoOkOOtXBq znaI3jmAxQ;pmfwB1DXK}_$%?M|5Fjs`-c;nz`frdU!8$klt7wf z=^x0i(hFS$&;$zqPl@rtu&7R0*qYT|y9PD!jbdjEJ4{+QC{I0=ZvtrA<5*QMGfY{; z0k_F~a6sKRf|A>xxU2a#9WN%KLkFPg7O$xvC#L7Gn&gFb#9_<1nCn2NA!6djxr}2P zCN;#BSTQ%i`Re`=0rCI=egw<7KIoRfKjVdcK5!gNK|}Zg=r(N{JU?wsq|`!h?0oy{ zj&XLEB)*NQYlsZpo!{SzjR-!AEld9y4+(Y*usL~YSs!;=p&j*S&-*`JnCmW z_z}XH-cNN1_-W-c^@Ue{(h$CA#PEPfP=aa{YvtS{PxT)GSyvFQRcwAKKX}$>9ks|u zs}4w2E?@m*X`fjA)erADI`XrF!;Q3rAniMYJdeUsWFwp-gp*X|@=L6A(oGAL3T$$y zklh8#iE<+uiGrLFB)lRAg{bS0!fqzsrhN9OcUA1Yt6r6={ln!!kEFEzfn*tXxdbz1*z4sTHVbP;7Ajq-#H(oKuD_yd|bF-$qxr~(j&Xp zO*+jG6B&Bc)$+4J4;2eB#hlqoX3a(iAKv*Yv8(dPbncKKOKw-$ z@`FKH)iWUlU|G;)gD{Fw(&`LdmueT#a2WL{45vAIg{W0)i-RFMm|rv92TQ5C z|ByMrD~&1DX*O1@`mX5VG~PtC6dW>+iF%e$#;14i%LSGer=k!JezN!CL}f;K@65K1 zu{~gq4xu>zG5>wG^ysLfNz`Ug0)(u05zIA>@u8k@%(iK)lX{uJ`}!{X%Xb9X=Q#m5qwlwV zPxW|JG|@4RWEhG$-0E8IEH!R7k(4RfDynI2dR^$B>uZzH;UjtO%<}6*mC)S!0MP8F zC)-;KpUfjZ{?efi7&9iD6uMPh<3m^}e5Wzvi#FI2?P)JwkczbW)eZZXGPy|m{)``I zG1I>*H4<-yK>=bV2)q0OK>O^#{_>zJ*NAP(WS`w_Gkd#^g)d?OkNC5O1nh?2{;Z4I zRtq>KTds6D+MTjQB5UAzW;c_sV^xN;E7U~F^?8E3>&ZWmVyv3b!IrrEm!!R*Rs=(4 z4_NSD+)+QzVEvCVmqDKoJouNMU%;SQ%EZ%@Q|g8E%{!@As@TpHZ5$=tz2h`iR056b zYcc`@8L(<&3SJA=wFLAXDOsidwJZQR9V$|TFa29`4An=VHU3XoasNl+04Kz%4R|$x zIjj!As*U9#7R*)UxJ{aI@yWfF$|<)FkxYk)CZU6YsVh(A>W@CyfM6?#luO?*-2l8? z+jamH7D!o?!58Lx&#|Eu==+Mp)}3Cqo@WV3ASMAry^eNL$pA~`DTn!(NwBRTFxXG9 zG-TU%dIs`3f)dSBIS#Ml-ZXxaj*vVO{XY63u^JO0>ivHF(_16rB| zXqXNX;-X;V?Ix^EJ(4HI7%G&1p*~;}@*iqb2K3s-SR1ueFzJ0t6HPl$$`L_FKUR9) zrsId%4*Uc0hj$Kwpq1JG>c~IJ>HnHLcaw#Hqt}U<)|zpQUlyN)0x_%I7q8i#`KcGzWwkKhDqJ%Ep#%r|5U5tUxI=q=4Qi>e{k1J zy-820gKb!I3*zj{&4gDu0kV_~Cg(VOP9IC8u<8w!iXq@W9=W0y37M=5eRA~+=cw>x z!%R%&Lgz5!PSBde&e<&|Hz8!<^DFi4l()~sCD1NpMGegfgL(owwXx*6%+LL(Oohy( zv_O|!j1_j0VtW5J7idczmnWiZA5b7`G}7Y@!!+y|(PzigZu%hhwtQ3@)_iig(6G)N z_H$kX&nUpGbwx;uDvBY68dU1XW-Qy^&Ec_c=^W|oSDJMC>P_66s1?74VoabQd80z4 z2&4Z%E{b|mt^0eDNAh!>gJ29t(|0{(>eo4X%2W{j`4CNc+)|qmOM>Ly-SG-8o%qMJ z6%w(u#?SR1;2`|^jiFDcerv1ry$R1HzdOCH|Dzpdrr|!vGsA;3Y~ZKYXn-?bh!S~J zI4w_xqAPOG_kqYo+OLc2;_Vq#7CJI<-dFhfLI)AP=JzF6xz_p19neRD93R)u_4Bkv-PJ z>Flvjyu>+5IO85Fv|CA0zM3@4{>4HjJ1*_v(V2Sv?6#jrXQ6js>&E@Pb|sT0VfpyZ zt2j2{YDSSblblAdO-Zommh~2crwZKVN7(O~K;6OlX7Amz77sLG9EgaQe|GmN$V68M zj7dOIj}d;HrOnacoRQ=n2Ad5K2MFA}BYh_DeE1F^=;Eu>6#n4mv&mBP$wNP!)(Gzt zy|StE8pEc{pi%FJRSA|HWY%?k#LT2_o8#uoaHbOFX7a4>M65wBjO*SB>Y6s$r@q*d zOV@>yi3-gzgBckAN%$NTj@D+GFo5?-|E*aO0iQ<8d7(IZ?{DQkXPoE%{bmY+C!|Ft z4_XSzv6yCWTQ;4O+5qbtAcV{&e1`^x;cDjJShLx=o6e)A*)6h2do@;Ml9pP)5r``v zky*13?~lb!7qHS_g^fRwJs|>$wL%kMt5rnc4kFQ?sd${MU~d2z@#5y;b8P#u-2qA= zdB{gHy0af5`b6(Lh3n^86pzJ}qS%apy?3HLSmae2s}>0Rc1B9Fb6a z-Z$d3whs#eBjX}hWfY$5I>&H2x!R-~8=;z+Y4L_5zhMT`;tqVXk1t~%QG76<1GPuO z9f8##v)Q&o4+CbcBB+(y-&*1FlLSbrTq(XnrcerUmKB4gG2gahQtY#L=>aHDg9W=k zWBS0&r9{+{Z_*nE`*xJL+vXMx-9R`Z4GVSgk#_*x6&U?4O40h1A|>8u0&W zc+s&SqU3+`2FFFaF?OD^X!@3E<}xoix*EPCyB>pjU!N+hAe{V~>{6*pp@ih+zYW|K ztz*s?stjNld>EGq;vYOmoQvuk^Y5X zl8eCqE7_Uu;EQ{4z@+;=4H(Z|XvSsAwdSN#x4sPGE)JIq#AQy-Epd8hX_lpO^@#kxjP*m!wtaxLL zh;WrJ&!@ZBjFwyR_^(a{Ik_$bbvSvM?xU2q^js+;6?Lq$J5pPzJ}N%Rht}%j2nX?? z1le-%r&ZP^ik5?!nv>}5xX6!UAU0S${Hej4m&t?sRXeh_+S8D_N?#y6_-4dWKD~S>pwA?;|R_SowY+@kH&&&Ez;buPDDg5($=aCG3jm64foq%Xh6fGKAB?SWSRH)7? zAgRvc=dJQZ9}3#5U%wq?vrbwI@I(E))N|%v{6JDRr8%V(o#{8!GjTp5-e>At(k!;yv4dAs7|H|UAK5pUT2A8;qdb(}jm6K8N z!wV$+7g$~L+dd>eB`#8$dbp&(*I!)5b3>+A%H=N zXx^8_2tDJDVz2>U$8xxdt%l}#KKO=}%O_YECp4l){#>K>d1(`m*?KS_J`fH=8Um<2 zO95BOu@C4gm0KwDH6!2gdBFxQQ2s$=&DZ|kU5PIo)EqPU)cqT$&&x|i3VbKIjFP=Q z=p?M)v;=wIvzjnrnZlNHp)M#14GO{8SI|5E;Wjvv2;VaQ1L(MXLknKfz%`ID4EVnn zW0o5JXd-YrQ2YpVFg-x(G=_ln7;}xfv8&JapDnMFeU}oShZTCmVtknCM!u%%6j{Dh zZk^xkdLeIup$xv|e{fjQau(IXFpji~{Gm=s4O<;J1dupf*$%ZEFa}7t1#9{jBUvWA zk79p-06W$27q_WPs6h;qh5tql93$-fw-UjEP7T*A6dzAET&9Y+4LE<|DcG;e_4E)# ze)%Gt^qP!LTl>5a25!H6(e8;j{nUF^zoUIubQ`Ra(ypfGGc_@(78eSJdq2(u>XQz> zlJ)K%NW;a=u-c-FmKPrzT+`Lh9LX=$BGdpqBn5wAnEllQXOhwQ*YvI%GtruQ3n_of zuR6)v?)R%x1RP|@BMU#mQWr$Wn3TL)~p1Saz zCVRYzQdCfaF<2A{p%2kj^Hb+R>xgEJ8w-doCZOXhaTd6W8(ykhW;Q+G%6oYy>$Wjo z$dmz7H_x`#tY)Jw8}&)q zW!Y9{gD%}%OOv7@mmiEqf@RPbQG#57LznIIrW~i$hz7I)szHKoaII?(L(l^VM`u99 zYE+zBN~Yz>^D+=3@&sQq*n|ju4~shav|8d9{g{&~#qad2^RxQL%bBqD6ZYrhRxh-r zo3ETi6gnzNX{8(Vc~0pDH+c96w%D1+DVdEPRZTIq`G6dwE+nbkqezXHaFv2Q!Mp3E#k(*{2@;I$c3*aAW2gEorn@O zU6wv-i$yO4l_AXs_O#&Y!baH4nG{HzmLsYe7E19W?(_(&Im`5K-cDQVV}aWH2PAC)rMeOh7R^Q@qab)3*E@1 z@JhIo&L5t1K`F2b`(Kb@ODZpFVcGR?mED>GhgUl2u>u0yp}7h8l=Nh`!N&>L5Z0dW zCxrMMrK`6?)MFU!sQu0~{$B(Vh>3zi9?`CjqGCglMNgUUQH{!44_Vumtke}lS# z!V3sAhIh~*0Hhv@Y0-0?-U42+9-F*Xn6iHX(rIVC;hI{tfNyTn;=>8KwjhmVnF!TbU$O>UsqsM|0DDswiLE`sKk@mm+P=sbv%~ zjzw1|)hZpA^v6bRo4jooJq=RPmy@~hxeT%J^gD;lJ+jt^?$d=9xX@mj7ogU6-l7Vmpr1esOYrh} zK`#JZ1~{GidA<;Q1h8`eRS=l=FyM;sSJfmL?u*fx+@FhVD_N^Q5<`}*J;->9ImPwr zXIcLcUekt!yEY77Cx-grkX7@$jPG$>dIJ$4+3>yu6Q6u9O6UpF&BJ^s?@m*#i>(vk z{h?p0D7w>y;-+?M7AlsX4KLz~$NS+LLedl>FX%XN*0oK7RHn%;({P;Si}ua-`IkwPW8{xku=Ar8cj3uW!T%-++YUH)NkP%g$9gr9 z4wOt*&D*1$A2)?7gxunuF3-q|a}>Js_*>IS2!4=D`mSN*k=Pt#JV=1fW6$yxF4a3c zjrghX@KGzKHnTE3|6wwfo~|yIXw~K=B7gFf^&!)=q(SddW+H>aYz4w1nArf7&b40 zOF^nu$jxMaZWw8_m0|tS6J1W-2ZfW;FEbrvNgWL9_n;IWdWrH3P{XU!s^VvYtIh!sGmr$5 zh+p`Y-9z#cQZ?M|PbCCtfP zi(4}5a7zDnr3oRTCb6ln%%IJuQl4TDA=h{A60Ou3ml1Wjbav!bi^8m<^G`>`T&%u& z;gkg-3CoToOKwG| zi+$%g_ZP&Adg1cJv?eVj{W z2P^>Q`IyL_iF^S=-5X{}{$gukZ+WmXO@rC-p5j?;r(0h- zCUx3cjf?on@)Ds2IL@Z_f&K}mY2~@!-u-f>x7bx9jZx$r7KGOc#uI)QdT2H0u}yA+ z-k_V-yL=l$RxqeknI+`=#86F*XLZ&m=}i1V^91qd6UwH0X@qmb_a+K_nM4Pb<8PtX4AWR)Fr%32ANr}2w3Q=Bh92_ESm_txV zl{CkLqb#WaUDO(0Ps_P9Dx&`!H?>eSn+k#(0S zm*MM^NIzB%#zjM)a{Slt6-@B(Ue5&65$w1Myl2@q`lvuh#9pT9`Zn_lrBQy0iwW!R z)=xR47K8SAk@J$_hI>QXYxKD4vpEZw|EDrhoeyOn$Nj@DGCF$ zJ95dz1fMOqOju)cMynEpJ#B~e^^E143i3g7tu0lGAUibiI3$mp)XXDPU(8%X11M@ za~;OW(jWPi)0aJgfyB&>r-;oFlmglJRW&vUCt@Abd7HO>DqGZgmDwKuy1cJvKL+;G z0{QqE)%&PT5hp(_xt^yVz>ccj8GY)MOI4p9n9AMOL9!M36$a!?zfA^$)`OurdJqc#1^;^Q|HtS?(5@H z{8*_(J%g}!s~y3dl#N?XJzgMuWfTf-aqhTBo`*5Sv9&lIdeQ%#FPE*gG;0-4O^cM- z-9<){Y3;K<5AIQ#)0F~}vKuIZ-#oZ=RLr%yI3S@mZlsx;gf9N;O#0gD`O>gR-v#;W zcbW?K_;R>1MdWFoPRM+FezO$@(Zzpb$84wiT3d(!qO+{GY-Do-D#?u-EaV>=2hiTK z2L5P}I^!%nSnwn-PSiOy^=9#gN_P;<4ASUeWfrRbz zvxUl8(R2*i&UREd`5sR#o+o*q|1>G5ppz-Zqb7~*sGV<)b$u{*N)M^Rrv5fi@VU`K z`aX7U7;2zJ`a@_w`-Q9ck+zP-U;>!}Yn;Yl-SE3_HK8WC))Tb`B9Ekc^6KBv)itne z2-%9r$zBgRce#$V81``6E{-1munMA6LTEdPWP+SiE-^+9N>g%jITjQYsny!YBeVd9 z>y_@#X)^}&u$^mr9Spm$aEI%XDRa#{!>(tDmEapCdf`GJ5aRZ z3&ovwo#PQR+bHE5R3FU}hzlCBZoGIfZ-1k;- z?8+fP(Lr%}a`2#Fx0&N%Fx4%t>bH|VL&h&2Bi7x4I6tbwYQ< z$v>68xse>Gi(l1MEu>e?d(O|BmonYJCQ)3U%cey@0#r_pDK8|Rcungy-SIuKIO}^a zw^ul;Ddc50ENto^xAF3RX88RK(=m7xf#9o~Xf8?M2xsz~(t9LcyXm!Ymq4b)e}My{ zL-JuZmvzkUXO`Wz`-g!Wt*Obl&rk^*+!51bv!P*K3Sk&z0%4n`v@e?I$ z@C5Pw4_S^0u7mXwZOlXy*xU6aCxm2w!vic^cXTNu!b8o6qbF70(XqRyPr87>jxTag1g>?U! z^=#jr;kRi1JkK4e=})?18h1)mAANx$AHL0HIYjlL&%kQS93%Xv=6RE6bP(bTsM`YQ zQ&e|Bj!Nnws`I}aR1bU4H!I*f6tJC&Ux>R-A*JWo{+1B{-3L~MG7+1DYL!*@LJJ;5 zsezvBE?iEoaixS$SdLV=soPZu|wbvN!j=MzHJ#{A-A?Ej0n? zz%o%dxD|IQ`1`~`HlwP-GSSddUk*~EYVN%$7zMo( zu9S&4`fd~X)yCVav(=9K;e4fpDl}|4DD0iyV0@d}3ujeD-VL7By}XS6h_Q zCF4^!A?;Ms8%`2B#O$Kil-^;$p;pHnqU&TX+EC%)D$)_VNm(!IY8Vt~dE>S|K z$>Vm&oqz#_4P}U+tke*%LOaA;{OF{z%=chcSrfZjW?*`Zb65fV%&QpI%^K`kSfG z8x6}8pR4gepinaYw8n;OsAL&tPjdwBuli&VUgk%6>|&oy1!e{-=5E+YkcYL~;SF1` zl_9WV@)0}y)sEfBXm=O5M<0L&1RR6YiJ{7#+yl#>mB3^P1{3&&t$n0`G-7u0hzVH> zVs_xhq4|r(e4O%kI%3$rxHKC+{5HC7Xv2g=wBBlty02Zpi&Rp-wKM(^uQ1ok1w1Yu7Z%9e= z;+)N|LvGA8xP!!MvkBCWc@%a`%yMk(K$}l>W&J4(*&|kvlAvT?HN~&uJDK-em5B&x zCx`T5sFrPw=X(V22QoYFoLsOxvCcbI;ZFOE@a=KzHJS!5gDtf?<@?sz8|v=Yn^+E~ zJ9TP)0D5uuycRyG_iwrD;pz|bdav&TfB9wt<2 zIYOWpr{H}>*?;>@4tC8#Wqr-5INTs!IS>BAMo&pTcF$ylv#npyr$lg*u5)WEY%)LD zz4J9#1xH%+9iI20PuIYDHh7~Em;(1Z57TSQ!IF*g2gL~3=kvIe!wStaUg+5gR^~H^ zW@if7s#gvVI?<;9DzQ)LowvgN`(kWFttbj_s3b=>|Glg$+7owjRD~AAcI3CRBZHT0 z_85Vu`NRDL9@m8LuV4GVM$vVhs3)3xRidIFvUb-&s6A~FVQqKcG?+hY%e|iB9==|R z`-mbVibLA_4Ih7L?;yNdio`rHgv_f6#d<@`|Dif0K-Y}+3CnG!GGZayq&L2Ab4p5Z zorElpiSYUjHR#eH!e8e|G};PHQQrOxWmjK*N{_oMS(Mx!NKf;O!TZ%s7O=$p#-$sr z{rEm#{UFhcidpU2(D6a}gdBy&9sikUHv3#j;&l!#LSZ^jeguCF#o3M=>F9dFUlV5? z>crc36eCsz#p-&Rgg-)yP4}c#1fhpZo9f ziMa#buoi9=5c8_&Acy!$(%{!2o*aViLNY_oPX|T%{WytON{am?MrxR8Kr}!pLKDgi zxqX6D0s7r`)5K+w?Y9i$gUWu1=i}I+S8=K=Wni2+@zNuUuQ};d@BkevP_B}*+Oqy@`~^NDj!WugkV55<2s4G1VHXh@eZL(0ccWV(+3Z-Nfc??w%l#&n-xsW<6hobut?{TG zS1N|+9%8}J+{wDeFw0Elf(B%g`M2Bmluvc?^PB$wOQb;wKv$pLo0!?+O$?2teMX%- zFL8%{aS1lk^GY{Pg$`32;b+}8=?&1ZE)IjM3bI;kwg6lb5NO*W!BV1E1w|Y>XU;2_ zC%{Ps%W7CAOOc_H378dp^o(>?4 z>896DGn>Q1T#yQGj=y<-S3XYx**K~eAHlwwh@ZD%WqReJ{Uj|vrGKD$CyWOEfv9}2 z5?HA@gsn_e)iLlwHx&cbRhYRthkZqPA2ZnXZ2}}&>AMS{_70GCSVJ+;0iSIpz?}@~jSf+XZy$*Pxm!DaaYgxUtb-;)irF!@j6^lZ5 zi5FB)tnTJjOJ^HvHI6$l-%HdY2OpQK`(#FZ{B8JR74UaFBQu%#7=%V?qUQ`f_*8^@ z2@DbrrZ!_dw*rP^7vDmwdmp@ne5B0IK{=$Hyn0%7I{Yc?1_h0z>^dQ>4FdmO>`y}o zduOAl)HD~rjD8#v;`FNjsF;{)Uo^b|*1@aT@Q}Pe5;8=_J6SG*ihtyNJT$r#+zzpt zMG=&xH69dFI^^bDX4nvhA8a3#+pWda#cG7fQ>~U0P!47+At85^Z)nID%?0S<@hTJ) z<`7?d=lsz#vWOJsnRD5^gSTM0d<*Ih#kswlrk_9M|7ZcypT6a4)UM=ELD<>}CduohCy-PV{HhD;zBBBEl;*K`Nu>0eu@@__j0 z%i$t>ZgdqnYLe946Sf`Vx&*JpB-qpz>h9Gg_69RAgx#Z){O(`g?0KVrsY;%n>gpxd zeW;#1ov;dpL2O6!G>ttoLqh}6<&|z;<`p0q)uW_eah1E~BBuv_rtgY4Bx~cc zFAS!Na*w-%ie(>l=l^P8+54<>w%C80z|94J+R4mv+h8fpYP~qFKeCf%FYd$|yuc-= zw!ZQGPVzABjP~fBKu@wv*r)a@1>WfeC=E9UqVqf8O$EQPC1V>Es7+(nKsI00ICP>*E zlHtLo6ma+FETT0ea>3z_n)hd(u4@JVd4$7iq zBkv6aL*9f(MYc1k_(b9{KXah1cs5+4v(h4m4t>&B$a>baX{tS)p?vSs_iLA#Lu=?C z9uf2@1_T&vJ6yq-WheQRCDZT>il|hDnmSM$Yo#+971L-VH5S*7xw{ z%%EvSpWM?(#q2_7Q>XfPg=H0EW2^Uz0V68nls2_$GfcN>l)t!h@05CMr;Or#ba1EE z(Rk}qR=`;Rp^Ucmt#C=7nOE_XNgNtPw(ws~p8jU=U}Yk=)FK)YTWuez7iq?Wb6Z)E z3X-I!!UHKp(dIkt1LNEhsbC;~4af7L0jE&5h#{S`|{M=K_b9fj!H)r4;71&=VX<=DLMoNn<%X}WO)g6?`ERrG1m*k?5 z@Ky5rfPIb$2x4&r+b1ABAJaWb_OLv*MDM^+n{c`I+{&Wb&-LkZd^#*-jNZGT~6W7-ZId&{%MOG_zciX!>2{ zwHY<)ODCqDBW|0wtE@p>&Vx8U|81)|LKzQfU)3#9(L<-K^P9q@o~F*BnHC-y zSxDU($K)vKDni?jE;nqM!H8xD)u*Je3Q?V?0a|Pu0`NO;TrG zw$hcStvJ^wRno=<=5-0q_bc($WU^gl>J;M{4!M(`m9(CYF{xUcoy2l}{E5zC4mdT!f~|JbnQQo)ZP9^B>pe2cZAv;sQW z)(weh`U4i49~C>V`n_6Rz6<3}_~C@eQ# z>UW>7-QKk6Otp$}G}{>x`{ZktaJELS3yw?I0+VKl+2akh0gw6kIfy?>e@e&3D^V0S zE<~=z3EQDmbK~wr2Lem*DgEj#HWc;EaUc`f{_yQERqTJ*=|vb!%U`kkpyS2Q9jPcA zbV^fPHL$pVCJVFlh!$MJ^z;vK*iX8BAK_*cggJ3Ev17|DDfC=D7P;DmINiRISAb1`hgElT z1OL|HQ_iK;QaKb1y_1MJh6W+vCqF@O3P+rhc3R?KX33e zn||XfKO*mGB^Ee8+cvXppd^p?!5n$(ncv!@tpdxV%TUIrofGlbZnUWRsllZJH5oZB z)eo zV1MQ0dU;~^*qZX8NxJxX8joCusphmHn(Er*cc*x8ny48V5#IFC2N!F|1XQ(2y10XS zz>Nn#FRMPL7BV5C8F^ctIB`S6^fihL7<+l~^kxtqAWhhh64t<@NxCwq9~SwL@txXw z@9P@Apm{=1z0vw8f2P(i0_ixr;rpV`&Q!t|YvZ$pl=`YfEgBS?Q2K^LlbSAU>hY!L zq)NKF$?hFSv5E{a)9Xk)B*YcETe>v-44Ul{qT0K#vs^P@>m+FtV!~1T0v_Qv8ca2- z_(XT}7l9AhUq`h*_x$87;4JdH;Q5v1rX?dLD)OB2=Ev=}x8Epvn-G->n=uiO96%&K z0H)VglyUyH6yA3}c7E=$TPD9~A3624<$r$4KeGX@rP*iMXQ$4|Hz4;hW5aD1X$%^` zLAomJlYQssqH2RAkPnCt`QSXt5ePfd*3tZyc4qpMOF@N+fr{A=8h$qX{S6EKn;;|F z&SnrFOjB>7a4XVWBpqZ$P(`;*!)Jj%06nbk;3ing!B(pn?VLq@Cj|r>$L31F{({5+ zALZsa^q&aE*xO5$@r2;c>#)6ZU~R$8(N3`cxmi>{65pIY8JLBsAQ{r>?1K4+>mwe8 zZGn?!eC$mmenJ&SgWArMWY&`qN2_abRK7qqjx%vqDo0PYk22p$0MK#211 zjbhV!G#rm)U!6qOxA=x_rOp%tFvF2{w)78$;Mj2go1has!1?IAAXe_#pV~NQQQ>%C zLpsCV;n)z~+!rx^flJXvQ_CE4E-UH12R++!Q9FIE;-|&@fu65H*bZ&ouKXvE#UZ@+ zqm^5tI%E?YDJB%0FJ&?cVqPvjmS9;y?4fM*n;MywrZm<*v1PutBut*i$y+;(_QD;o zP&8zvJJ}6(dFf#9h01)RZO!dQ%Ko;L@?*^Re)5v}lAh&`OM46+g^n^A3T1~Weu$Yu z(wOI@qF*=bCC1vu`u(_SpdxVcjs_?>@rE30mfV*jOAGnCS6)89dA|ST+-2fD(@wTV zf4${;4|6U&`j=0y9?OG(Z0}=}yw5!>-*N~T377~VPj|g{BHGEtjvw#GihQ4yB$LY= ziL!cu*i7$n67FNgu&y=ibid6@{N1 z7ecH91_j0$hlQCs3aefr%oH@$a3d}Bz|Ojkq0kT90-8#oAxRRT)BT2@du?vS{WK78 z4kO{gy~a#%GgW^+{6s|?qS!@n=a;meKocifGBpHxkcYf)o@U2Mo;31D*3E#JQ;`G& zJ2mB8lc(^1YT%1Vki_{Y%Emm5V@@?uQ;*Q4hlC~++@436P(dbq#Hn=gO8#O5DUXc4 zzAoO8;b=|m_1oXt{Aq9fKUBSSKvZ4VK0HW@Ac}Md3eun;gY*zGlyo;rGtv#>5Q22) z(49kf2uQbdcQ?{G_jkCT=Y7BT_aA3C=j^lhIV<*B*Sc2WIh#1b!h626c-{cO;&qP~ z|2(4O0|$C$WH+WRty?!Lh^y`&zFhEqbp!0^aIEQ4KG1ned__cYS>)Q;cN|L@Maq=z z;^YrH$2*rTbl0e2goW@2bw#&Vki#9gu8q&XXJ)kK&=E$cFI)u0O=4-zAU;AMxvWG_ zEh);S=VP_aXjz4Yt3R_nCI`MiH2G@QGBowJ)rg*`KFsbu=}RzNzA;{|fl!pSv(cYP zins8L!eSR&;~tqG2Cw2ExUc4h!z>}E|A7AU?ZY^RjJVMuZm!@D?mOC9Sk)Z=fMEZR zpjJP$VEd0)gH?!PZ~&E)4_MRl2W2vO)uPnk(+_<%-%k!R)PY4td+WX{>F(B4%FfHl zN5#H%RGvxRy7-T_0UEqLlj+>mTDF3wp0PsV;0z_jI9I#Y^4RDhE@P zY2oL2d0TpnzBWcWy^f8gh|zOruIN_lt~z|ElSeNxjXfQ)`uWT1Bxi{nXASmlFkTcU zHsWi=0U1_-G>3Gt9JKe9GkDq+z18LAyK$HP25J_pm*3ibmiFHkpwvjc1fN5K&y`0x zgXL>KZ}st~U1%&_YmAccs3YWl@Tl9-^Bk9qOOT=e11c3E=1#+QwGj_D@sG73r^B4K zF*-NxMfRlEgrHF=l?V~x=9-}+)asON@j>Q()LyHI5juuRiO*wr?-ko2rh@JhVO6>W zLVs<3BWbjJq|d741Qfee(>vrn$vr$J_Y5GGBvT0e3~=ZjKIXtDwUI`ewskRBY(PM#?h44<3!!s?<^D!c3lqYR@~P|1c&2(hu!HJ ztbrBznZ-+5)iH}Iz>Z)Y7b&hz@mZ!&a~W?uQe>1W(p!V@O^6{uR|JtWd6*CrdUn;s5n_~!V@n_OyT^5HPX$mIme@dxMflMU zAWBDHuA_@z8Dj^4I6TPz+Y3NQ0R^D@U-OzJ!xH%58vwlz z9yF4|)s)s60oLPCH$2)3a?-dneG;~&MFn4EHDT_QgbP_~c ztsmX4BW4wTyreyq?ftU(enkBv_CFx8+=vplQ91!X3AXNZVx(1i-?FshDv?kF;^=34 z=`*cYI(p>g;Z5ZBaP6&g8~m$ac>|t*Kr)T~FMvuW9uk9&pd$LGn?HY)Iv#Mi{Xrv? zBZnsOI-a!^UVdkcV@{z>wTP8Rk7L0(FEMh_w+LBr7^GU=U}$cxYl&$dK+?VZaZwy7 zd`&D^OSJ;wFCE{^X^a6PxqxTEY>vj1lQSy^;t3h6q2K{1yJX(W&jne}f?&!I8+7H! zAQ=#|1#p@KJCC;rfr{_2OuRW5TRU|r*~eWGtr8&@%clhG0~Pn~C`AtHu*#iWr{hk) zjw-HlBYyEwQU+v2Wc1%8lC&t0s1_Iz*%Nv3n{Uv1=W_Z9QFoYkvv9Q^xu9B(@VWG~ zobC>T59^N^mY)V<{OUTc-x;D=nN`o|7*Df(m7?fzRE2rTxr++qHvPW<>*J_)Dv>xV zp7-Zqt<2CXF@|I*wR-r~?8HoQ5et?|?CW|tF@nk^nS|CMjcp4#_7NqU0!xN@ukqFV zIq5$Xb-9&nt~q#WzE8(};(lPw@;a(ht*aCwW0DRoUKYY-D)l(ssZQnrXDMF{NThkW zCr7+rY$OQyW=VoRI;}zT=qQEA#gMh+>Sq_y^jBQ_H6p%&`K#TyvhrrWs02}6x|ouD zb~;85ITnC5#+F!p%~9;wEaI>!x&a80g*1Ndg*BJdHAI8L`tidehkmcr9?|ePPv>_!YYbFn&uB4n#P&OSjIxP zOCD->#a*`UFyE1#cXt*c0pxk2w<0cD53VLm@QDVZ?vgYMs88_0^1GX576O%%`%P9w zx^t56n!dhUCsG;SP^KZ>ZBMKI2eb|b5-zKbi9KVaE)dS{(FRr;0)xfp^!qhsG^=)T zKtv4|CZjv}a=`P4ML{pSe2eJc>hr@Kt1rj&zl^NdlBtYJbKG%xB(*mMKV;49kfiGr zk<%*<)13niIMDRy4VUi`?rtu~fbQowL|CymiZ!AF!;K#uV;GkcI5QDyke zqtqfa^U7CoOq1r!Vv#d7M|2rQhn3$+j!+H#ep;rKrlMEdSts*NYCHknFA<1JYgD>x zE0I*FMr@vd1MSs(Irp(Fi}7}lXL}y52(mx#te?Ci2M_4ZDB!o}#avc`?tN zBi&wbs+c`i?tUDd>eC>kpxCwNsxUY*H#S@01v0eLlGdCM2nhp=dMk9Y6Vnk!6YX+} z;CHGvEE?qXVQbeXJLR^~%vs0HJ6dO75TT`(H~qv3=^lXsp&8?PY^+5^gKU8OK8;{kkJW2a;G!q$N|9s;t<_& ztLIqAgKSm=C>zRDu*i0nFGaij=g~v8K;Of1G*EoRc6xPS9AF&`G=MY41R-qox9G}3WHE}wCwu1FB6MKDo@u~uC9*m)TK ziff&E^=zO}NY1I{Sr}Lr02kz$&>&^CGmv5Y-qNzFQWV-U+E{Oh>?DC&fb>yC=74QM zaa62Pt|dA^s<=^m+h?aqJR%W1jM0~(KV%Ca5^PY-4zWxHm_#uu&vs?B<(Z!CGBf33 zXuKEXiE4toGIz1Y!hE2x5)(W>oeVN?e{ar$Co;o-*1~>TFF*$zGm=d%x6YnCK5L!i zP_(P4ISbWyn}6*+H-C#eDool^8}sJGGqEA&a~$y=4X&U7W?92{Q%1~drulRFkm!2| z|IkoZe4~I3fw^-7RxG9;0*y-6r@N@uS$MOW%uWS!wO~ogC>Ru>Ku+W@!9KuQuO5M? z>Ks2g<()d~nv3gP9@=hrL*-b)*nKmAc>D7Wg7NjL^Rup*^%vtPk*T;l$VBdFlZj!^ zV8yB^Mj^qX`q~*U#E(`u*{>FDPveU<&ROBJZ+TcqvF{EdFF1?uwcEf}3`g=2kKz@p z80T#1AV~9f`QbUBZ(l?)eBMba!g4Cdt>`L$a0ekntU!O&zRBiM5|CNe*fWP3HAbM- zl3@nw3;$44VAm)s2~s^OVAmb_<;io4F<2wQ8H=4ZT1i)}#>Z&8ZxM0oI z6^J4;r!BD$Gzm{FN8I~5lacqox{T?N4u_3Y1-tkz8W+J_B|_`bA^v2FQ1nLBRz&0xp{XEP z+5+5Ft;mT$eZYh6qlrXxdX*YU;lPQ#o{G zINue6)`)Xpj+G_+yi~W7HEFqRg@Tip_QmRpD%??=U5mVT4nai>Ka%RVzLd_@Xb?+B z_eVxVI7e{_tmgWE0vlSIBl)wSJq2j#nCdKTG0Q=-p&gN|VdsI`{NIu?&3o4YgfZR_ zOl*TFrn)@hd{6IZ$MfJpAy4+xyP^m$Q`feghK8j8D*#mi18-xNwcc3>jlhh;GkqnL z9#oB&?g--3$R}*m7%CMD36SH<*9KLZJK6z2DN_v!2rD$@5f866@Om{Je<}xvY-DA< z*6t_QuBSdAq;h?LeT1l_yM9az2sbZ(uo{E*#0?@-Ux$}`R?IgrHgr^8ra&VT*!ViV znvR#4XcT9Rems{v{McyMPECKvZ3!d2yGR|YlbN1v9&v8)ljezz5_8d&|H9-jWqOTK zRgcGeg2P*v5{I@MXfz3ux~qtFc;jy5cjR48-9})S$X3`@sbg^GtZq5_mQ=zT;VUd( zH8Cqax@VE2AdEh~M_PVovW)7Q=qyC0I@eVk@@58Ik_ws)BQ zHE0dnGzdZvny2zL-0~mPHY(YsKSld`NRz+_aHOqTNSIqR7#Z|jTjl?-rYl_mvRQ(x zFq@1wi}5sx^aOUaKW-{1rc}2~N|oy~MoS zM}ne>tkQAHq0G1Db0T=1+&Qu}p}AhH+*&(|T*Q0oIgv)xZn+^n^{>5HMi2-osdZHV zq3$0SlGou7(cxvecY-pr8^|Tv4e51? zXssHLV4QQZH6z>)aieIh!y=x0W9!Fof1BJW&6W9p_3s;fzUL)29T7Sf&Zj$*BMAq1 zuwU;we52sHUU1xBKju`1zI+ujhh7)&(3zVU3x#U>d@=$jN*r5EP}I1qdi}w?XJEE| zD;QwpMjgMQM$UMQtjxAFG~T(?1PJljQN-SP3;jlL;?5={QK75T?)y&1qSa7~7~g_< z-&BzpU^{7rWkMeyA6-CjZQB5Zp4kC>~CzaKfj(NI~t=fBv}s5NIdiTsEr{gDxyp?(kYY!B=34S#H} z^71odaLZb#{RO)=cU4mqZ&NI!A;L>u0g@xz^6rKzapW9wef+S+geKj`KLnTjhVO5< z^E$NC_X>2wZ_O?8IvNso3LZAf?b@23?^C|>Pe1JUa)Ei_`)vc^a@Mrlv!xZq+CV3N z$O&P6_q`+d1*{>nmZO=%!J=Jk72WyoliN4}02&3NU+S$y=xipMKyrsmRUQ3 z_caXdU=Op^-=wTVu0u?c{Dx$n2aQQrb2%{N**)C<$*2ArokU~o65Uf3MoM#1Ns1{# ziqEES?S*(T^@x}lmedZ_3xrT}qs_OTcE;Jdd9v}5`8(lbr~L*&7rDm)^MnIKeCV|= z6WZ=zmY2)BOS@bPzlt{4LhG_^&xH0et~~R5^IbhD+z`^rP-TM>ECCdF#=G;W73=FU zUJuBV9c^4UXXm1NcWK6frNk1C?uKlHfq$;Kf$?dbAEnUy-g~rCv1aeua$G5fdQVu} zR!8lPYkfqwiPhUAZez2-3joubTTwQjG{61rEm6c3OiDVYxXA38p}TLHoz7n>Gq5rb zMj6d-yU5WTf*`inlPjMX5g|ev^^IYZ@(IswjAn;Ez}Ec;eaj$zKc z|6tz@_{2Jnb8{P125sytz=O?w`%%1O^hUgNe{=UxY>ksn{kLb4YhkMjv7&VA`lM$l z(~4KW>Isiz3slC@^~QIY-`KrRPn8H$3D|nR1Y=bz z`gZ9PUyq^q{E19hTmlz4;qbT*_q!qj&97+j5YPu_h*$>Z%ZTomj;-L(xFL`2u&0;S zK8!29O6J5GLobKx=S9@xFn&56LNHWk9GYX8|Cq6?WUbxBJBpA#Kjv zT718x>D#IIPDOh)E(DmJ=N&t`qnEq0Yv>kD!rAo&3l@rq!wzac_nQzrWAtC1B;W$SiU zSVPivc*0wL5`F3^FfnNKDM@l%Fi$LFT$)^H{0#N+JJG>7I#FHzY7Bpv+gX7G?F)eR zAU_?;D!1mjy%aI!r%_HRNqMA5^}LJJMkomSW{Ck?#^EF7o(daNGZwR!Ef<#gBi{^h zU%7%U+i8%4;sb<00>r?Vmq*-;x87Ts>Y!5{e}MxLuP#RN zAiABf5Xpkvi61G$q@#jDNSG$SbG(yn_A)=z8NQ?k(LMmO@r#r07gnv8bkR~KMG)Uv{2(?& z4N`Dga3zjNczzvKjeMDMyeENaR9P7(+A|+&>##2`Qt~`E3d(l!o^w}v@SSaU>Nr|y z{uNyGFHhc^!6y6J<mj30R%b*^&6ZyL+M%msq|G93McSknyKPKlUy$1C=yr?@lDD%y!nxZSk@nSj z$p{PH>*dIe%!zs%nHVnM@m=l5PvU6u+%PgbfEpKi)v2wHgA=WUi{3AYTO=HH_H$-sbqt)Z}X z&vUq@Rui>2>Gn(nOX&#!11n<_6fYLKZ{W#u>>CA%Mw|{h>hn!jvkF=AB5mII2}a0d z86_j+FU57JEJnd^Z?J(p@PmDYRQ#UHtBC|pT{ z!*6f_JKrvOM~~>f#{d>)B`@Dx@;)3erhkP0W7y%wmY!ArU8OWa%cZjy559nZA~4WP zWZLz=*GnXr+qjzkzBB>2L1X?(+F7@fhIrT6vtpikN^6Gi-=?;l4on;fbW&uKmNj=} z*&ZKKP9#JI=_%+<(2a9oP*iPFZ<)>z$Vkhql_%ZD{%gvo?r&@W1}sM4)ucNu-Cx@r zXWKltZ2epCZ^RZbe2+Owfq4Q>#+Bu@rWOIJZ@h8mQXDl6I3sXVAhNykuu@5P%zzUB z09+DMhJp60W2@|nAt_KG#ZAGdxi5X6_}`&`yJy`#crfXnQx8Ms!&ew48Z9+|75(!~ zuITwcpjQtAS=hg;VC2^aLfyio2A4Z6zf+#36pFv@r49uU=VX2@zkx66w`9>)sLaC% z@H_h1F39?uhp4=qFtk0E`ZD0G{(J$eUp;J6)IEqUl`H$b$J*U_5gh;Zuj+WkntC7e zOsfjoNZivuYr+$q+us?-^|!U>Ek6kBCOff$F<Yjzza~tDTHv?-C+Pkb> zg%j|CEK+w6z1{xr{KqxCs4kq(+c2ZHn~gX`%?&q&qiuGWm}iQDfqF0fy@OVlCA6}C zx7$iVB;;GiYOdt$Ouou1Y3sb&9JC_wA7x`NT>+R{`E2`}j=>tHn8xybZ0`3V8Yy?O z6FF8Ct6h^DuckkIQus@72v4(Yuyu&_I%#?SWI;!}VcghXY>Laxm*#g~`W>c-Af&K5 zOCMYuXhrju-WT*emTdB{LtkUoMEJHK%3x7GRkxNM4pov?N<|)1@~b*vicBE%_-u_Ofe}vddUVyWpM=8uo7)pXL}@%UuKq>1|rsd z_=-cJe+W_}v5^*m#N%AazEZ9Hu|oK-lHYVNkmKyTtAa;%M-W+t@UAZ>v^kMb6& zR;$y?8xZeyp0l_+4{9GD`J68iLGEPs6Em@4LqI4Q29SLoosokNQi0+g{OTr}*-L$o z%+QgxlhRE$NDjz#F=b^zTq)&?54IU2rPw+ucANjhZ_4_b=DR>^0yW5clz8}LvwgQz z+306h7=|JgdqAY?dtS3r<6q~WUvNknTxi;H5AWT-SD~dC9bbx6K0*Dw@K;G5m>FK? zEkrE&aj)b{*v5@?H}k}X+Cn&D;^Bm^^nMSuO7H+eRLhBufBM_~^831M z`1q+Dk5A9v1rKQ}9@LIlj}n9Ne0wQ4CXaZ`b##6AC4JNFd%?&Z?%^vbu%f+_EbtLciRMG(`LqZY|@5^F^yB~)Dcl1s+a0_2m zA*UzN=MlhOR-@9Wf}L9U%BiA`MiWr|p=Pc`kuV4#ctEk78vkNGeB%awdj;=G1W;dF z!86_WRgg7>nV_DXZ@iZ{Z;__8k;y@Twi0=Sg}J@jPdyS0ya>)mcFk6uJOanBwMa(@e1kvl25)gA<_&+wHR{Ge!U z619GB%sp1TXoi9S0I8L{{Z$f)sQ9$gJz#$YS^323F}7a`U#dhAqfM6D{R5(jhg{A8 zY0A%&rIL5e^Jzs0p=7Zh9lul@3hCF8L{4nk>NuRyS3}F=?RZ33Izm^2##EX(Y*~7p znXh$E2}h!_|8s7MGR2#T;%7_U0+mJK3uTw*B`Nw^$=!sF{dX)u(%`A>G`y_ z)GFt2H14w5JYtt&l#RRSW9`_%BnIC?nDow&0yx(7w{jDY08kSlgYU#k#ywLNkfb$k zLjoY(Lo8*u6D&TKqQXw3opDAQL(pt;Ynn zMWZ|4Ixc?eOW{~6%$9n_d}4(R+d8NZ0Daej_=)lDsmEG4NL^l$#egn~$geFc@bFZZ zkC_v^OP^o;ee@)Sa2>5V&X{rfE8R8X;y09kD)`Q+ogqL7Zwqk!a=lj0AOx1HScz48 zQPCji7e2bFyk^I8OBHj@gld=@;p6de_BQ3Kvm3MXk}otQSN@d7VM6*lMiRJ%G+vm- zdIow+i?ZzdqroCSdIY8lV!K9-_hl8DUK^f^Q_&;^M_%F9K97n#_M)+}7|@%F@ssR8 zFV8`6$XmIkP-mXml>3wl9UZ+vJm%lo)~W=3Rf_e5DK&iXE3qbVU`oA!Q21(2#l@45 zDp)zZkl=Qm4|yj^UMi*Mp=NL$0Qj6hjDTXfdauC7sj)F|Ar%TwOju9GgUh^mf-jH= zMB_}A7AuO&V?QTP;-e5+T3*-jIo3?C?4){1Fa0gA$pw2>5@n*u48w4;OY)RQNp|1U z8?g29o>^|vhpyU(Q?oj3ST&Uw?HMUM3B17_{&PjK%~o+GOafoiq)j#m4a3+m zGvayw>yCQMfXBI@=#9MeJt@gVS8+%ESQrtS?rf>DwD8$-0@`su#I@4xBeLo=< ztMnhWwA3_XmF?=BkpWHbJ)B%HOHwEo=0Dj+W}c3n0jv$d;yygX2?L&; z9;NLhk1dMn0R0l+ko&Af*GMosm8@5u8B!B_a%86OX`sSfk*Fj~9o3H)D>uwjO;Y zvARlRD&NjOpuJ*Wk0k%~GaA2kV? z1`8VZPxqJ#{7=8MAnNv{O!X%`ztSq5G8-LQ8rS+gRU@Lwkhp9Mw-bJ9O256&vOB4n8i}WOnE`T?pSBh_NQ0*q%q1|z z8No$m9<2m>TOrnw>?@~?=9W0075Z*Mw?w}4Zkc!i0iw*Ab;s(AqMi2^`~x?3_j}Oq z>Pna1CXHoCc#9lYkt1L6 zAT|@uqx@x+T2&ptSKl17G5m&Dhnn1q`itbhv3}^7I9sA>}SSA1S zX||^Xtl!%I+pc(4_J9ut*86zPSjko z%v@;Z3Q&}PzJ_aGagOFAoHne=CGj$6Mxzo>ib}^@lDzr#ZQ?18;Jkw2D1~w(?VAsN zj(b~?n>8P+{9NQ%ImuqmpK~`S(eSglGD>RFB^ivrAc-{PeUX>MSUWaZ4;_XY)3zi}-m_vgZ(?Wi_Pac! zTEmYv2YTJRVv%7xB_CCvr#QukN**Xug6}m}w|3Z*lr`9~r>CVeIaxM_^ESyd&{nft z5a8)^S$*9Xq8u$Yekt0+4NAx&s#3&sL$*h>m%5Kz;r1kV(&ymx#dW_fm`IYXM4N4A z0>X@Q1swO-p;*&E-_4knjM?zj=u;%EsA3;b#ez_c&Qi*DfVx`~5UKIE9vW@ua%^TpCDBSdKlip7--mw^5sfYTe zsKIgIH)qz^Ant82$@Af~7{WTCJuZO+tH>-j4SPcVHNh#p!X5T>Sc?gl+X$I>AkVUo z^cszyTVC)XTh6$hbxFx%LMlU=9IO6AP^H1_^{HD)qw(Hi{frn}F`ZR!Dn6}LKYmUi zV~*6H7SYGpdrA~mMSdOX1*5uZ`f6qE7%G+B+CQD@NIzy#!zAUB)@`Ns<|m&Sg|R|A z4g$)BD9KKZ{-}FAZsRHKrPOs-fYe z_L(p|o)_iRZ&86Yj*Lek2)49;vDt!c(SWooOl^OnL|dlIqJFq^OUgRIr7)?JvXd%b zot-jHs36s2GyRm5Xz881QlFo(&aLbk5PJC~!I)}Un!qeLL2bSvYOKxG==23n@!4KM zMbT|FV)y{+onbb>HzY4%u}5YHb8LPSV0;_K`ebmk20PJZWw|Hh6QNVLkvj5o5zz-4 z?N4di$W4I#iuZB2RN6^F!{KXti}y!LIEU|11qE`=fJYr?{GGc#qC`pxogvzNiyZkD z|H^vLV0^7C%CQ#j@v!oD-)5JJZ}fr79U8b5Yd`0^({eamGo$J^1tue;@L`szWDTR| z7LGGig5{}Ns*yfiEZoPPi}q##1Ydy-2AIAlX0_JTy&vc!jzO_~ly_^IVpG%#_k7-w zT2H+v^zDNkPyv5`nYN=x^V5p`tlSR&?y*pFpVu^H5MW#OGUOhs|8)2fw~>>w?$FN( z)X+X{v$L}{s`ZgJj;tVgGcR&ZH=6v5CXBU|hc`WzxPnm8Rx+cDwP5r+qj{WLmAQ6* z|5xkU5N?IDZb*v#ssXoh`Iuh^lXNdh6@ZM|{UGji{(Bbhz7@T8+wN|!bmZ=Bu6gkr ze}=eqc)x|b&hb73O-p@IaHQn;^CVk6iqtUggcqp^-V;d1Z18TL6xEINflhF$v6#=4 z>D1>Q5zEW=(1{HT8lpwH;I0a)tR>P`MN#9CM))@DbP;myz8^=$W*aVczmJkQqP*H% zYA>fW$BDb{dIUtt)P)q9U9Brib$3V0V~0lVpS{GsLgaY5u}}2(j0qNRvD2k$-cC4a zPYg=fciVo9i2QS26x>=^=yfV%VnRvm{j#~!kjrB8q>IR;B~~1NMD!=+&ppM;V_Rv) zf?VhHC!y|1-_^d}PC%U<;<#rKi<2JpKh*zLMZNTfnpbWUh`pTn-Y$bU_J`0LEI~#a zo)F*+lJs)$G@efrpikdSwp^I>c|GC)bz{|rKDHj9cHIw|(;@r1Hb>}X*Y5%r(&8Z% zG3y^*Wxy<(+I+e?t+M{xhK@0Uq5XN~C=%0d&D&yOr?R@V0g!&=eplv5Bn(x-^@teCNVW`zI zT&`qd+S{PP&a97PloB%RdDam<--9e&9p~zepR7xzUz*V3O22FP;3&nj<5d9!55Bma z?P$#|_{{ZGer!}4!l4dzG!Ld=q5YlTTG){M+EZ9{jnFze z6!@&!5Z~;%ts-DAROAsIEK%-g2&o*x5=s5l_n-E1z&8+unT%RJR)l$;!f{Zyp zoR`GxAO>vrFwOo~v$mGnOz7-c(Qah)x3~rjpWsC{eKqV`JSR4|PoX%-02Apk`?aOn z63$O?`}Rt0ZxLDjU)Sw|cCA-V4;J5#_-T`q=awOfl%et(W+VJUel@YVb2Hjv5$(8` zY6e^9m&kXP$npV8Pmv;V;^6t2ul6+0->&;g*H(oFkP=c~38_Af-Tc%sm3t>Pwzwr3 zbofrX2A)80nEDT>uc_TP+*15eH+jy2Pt_<_hlipIaTgyEnlG8=H&N$zAPaP(T|Tgx zR`BpxUT~2W{(yd>@x07!BIQAd3?+WLsjql-GHyki2()Z_T7ifr%xI(6Vv`cPxZLmzx5!hdLs?hhjJEAo%eYu&JOVe>)Oa$QRa z3NvG%EIT&uY_sYPl7kP^@*m7T8L80vsf(r`{kY-^@sxkDAafQnG@<`RgO<*b%wpaR?l##mOC2S3 zLh@E#Z8bVQqh&~{1zzg;<8KI<6eu0LpNA-U8Ta~j^=%+_!1)o!!sYa=DR06{>hMLI zZ6QB*(qKWcc*?VBlP6!ZgXco0$$(;9!Whw3mBU4Kn~lsPI{jBXNZ_aKfz7faQHpKr-je4V*u}t#|ulZe~fpyB2<~ z&hptOwN}0&&K<4}Z_<8{GZD}PaOPg)v?LZQ#02cw=jWg~g+Oa)bo+7p!CqANRF7cV zTI3&)#!ZlSY|M%`_F{CnU6)?sz`U!q>zJc*(b|<1?PT5$!PnqW(a{@;T9(8hKHgIr zL4rK(Kf}#TU-D>|$4@?%xZwdXx=e|}c=vCl0pB{?!@_vMmO<(mL#|i$Uz6n%ZYXSz z*Nl?92yUxeltuC4U(hSPaxwDCYUWVY5a2p%!RjqAc++HGX}v3UKeFptls~~?g=8m% zjtT29QEplLYaA-n=IA%2LI^AdbLS##whYb+V(!~!u+K{@e|R@0@^4hiex;Y_4Sy3} z?cfTY=P$}oSL}25)!od=t|E^EX}|t{q+ItwBB0jqby0DcH z7koF*B)uA@hE2=w>#G&xs;hp|*JcED79xg9-xbL$wewGmbhw)g3oY;v46HUs62F!U z2rAmf!o(60_~Z3g$mRFcg{?UC88c0SEc4=HvJ2v&#TiKp<5#MZ5wH3qFGJmzIxJ$j zJz%jl2$wL=x&Sj=(O%)1M@=qj6PvCxcqGS0S<)N|>#T)oZ`r4Z*y^Qq4?xjlan|72dcm8(KF2$j^X86=zb!FZY60`&hEJQ}`~h!<^Mh(9 z6+S!usVoi>-Vd-Z7AnM_SDQ-=ZM{EO|B5a0fo4aQEM%D~TsyIoF&&pI4t=rVL*;0s zu%0EC$o4DCP0_Yt>^)_+p)}ir8{9%L(OX-g7xKp@Dd!bKvuB*F_D?$JP&dSOg4nsw zhl8wI&z~8?x7Bpo-Fc86>9b4P3kRX&A&<$PiP9cp%d#vj+iuK)hPpiOk*zFW4JM{`g(;uat zR0q`qdE|ly_zx#d8$*vQst8u}*ZGilXSda6y2m*Siv zOOWM2Y8fZjhu`&gJL;O|PVepAYj@K7rzA9&eE<`e%0`w9Qe2;_wSj9{bC(@-p_zX(Q?@&cCuYAGP~+o_7b z>}mTK6&`*GaGZ~K9zQMP>nvSey0_H$Y<|J<)~D*X>tAro{S`1~5lrs5Gp8oa&D1F& zFK9!guLC;zRCI69VP{#-{22)F;vvTrf5rsg6lpDH$1BbCgI3n$*G_1LVyCs9(%@%C z$4tGTIX{G76^bAKF$=XKxNiiWC(&UA-{XL*ISU#Qcm07XLcp1u(f>}n{?RTcFz5yM z;jLdJ)0IiubtvP%Pf@V8@*Td(1$hET^%X(6K`?t}`vUBLaieF54GkIN*(o7~fEhKeNC^pqESmMSIKqRKnIk`>Z2E*13L zF<dZ=CEIljWojTK6G??4wvcioJ_%`_H(0DIC+@~dgnnmTZq-(0t z*dbb94$jiC|`Soe)lAq*aprR=2$I@m}Oq$ys5f=C}(Omz{#xjVziczS`dn%9s;%tyrUhji^*gW;% z#N0SyGE~@zzuN72Fnel2{$jtI`%A4&fy8y-n>jCB=cg+)g(`Y@>sW$l9SivvktE?p zn<>cm03xma{08?-O#^3oO(kZ-h*T4?1od;5wq09SP;fZV^=Oq;(_tOzB9^s@oTd_|0n=!L~bNp=;(+!zwiv6Pa8H@^sa7h^j#fIIMQ($lnw$>f%wsMR5C9kLuGascc`12 zNXm-eLFq!FkAmX4$0VHSBYWmN{ODN9+L=CYTbQRyFrU?B_kVQ$kZ0M8AgA>#sRNIq zEA`{K;3!M#1+@OMiBV)RjrFbQ_34k#4uq|s zf7vt0O?N%ec43m*~?bSsci%<3i7#>bH8Ww7$Y^%S5jg#NqB6pOS zaxKWI{4K{xg@^&Y`Kh5gZq$e>I9z;s!o9PI0%4sg(MF|;JF4>xc`7-5qiW%}UAHS> z`m=!}M+*y|_H6-PhIda+@iZeRAs_3GHq-7dxjewc`iiJ(%0!}{3KvukbDkWG`oL(X zUzB?%Tr*MCs3$h3#X$MvY1;M`uW*ZyYgKepGA&EmPy^&C(920*KEa8PJ=1iKvg!xR z`Wf$m2KjTQ`3r-mt}lfMw8PGJznH4hLSN4%-yVV&euB^ur!)jRzh0G19F)9$yN;MK zxD4Esvd8I$YM-eY+6}qpFy^lo2MfCg8B`I7E859F%Fa}%@}Lkr7R~=FB>{44>G0^N zn6z4dH-vJeIq4IcZlk^D5Bh8KY@n9EDHk(8vvUg{db`VhHgo_EDH(pmRk19HCl|ln@OUwYh`}AKsEUfc`O$GCtFp; z!pX{%N&b7>KT#Mk{_0mBJn+zlA2pQXUwx-GaE-dR;(4lVOa_s6E0ImD-)w+m=;$x) zR?KSY1{j;ynxw=~J>NMm$Ww{jW^fE$_8{i7A=ElJ{OE?NBEZ}+IOCp$FO{PDYJlQe zlD~|eKrZez1i&HvW?ZGYz7;<=h1{}R9puahSNO&Iawl-CC0u2W_`Lgy`6R8|Nq3^@ zLx!bBm&0m5S)d|MC9C7*Jj+GmN{arHqK{7f>!|s6TujRL*fx#o)kpZd8V%9Cxz~zw z&p={1b`LFOIc4y7fWzWN)5?7w- z&xZr8hDRZ&zSPAhQ%OhCkAdb>AAp(;rCRUvj9zmHDFD1e=ym3Ok+|~6NW~5SSO^-U zfd=vqfV^LS#!pwt;K$DZv#&;YMX4=B0XRO870EkV_aS?^yww?0Oex1o-j~@c#!qaI zT;tFW)&YZ?p+1zf0)y%CoQyaHY=-TCuzTq&uzklj>jBpR9Ko3c0nGnQQG>ycb15gX z>?Tb{FPcQrgKO1=OMC%BVBEUU@P1^*8NeV3xlh+N#Tcg4? z%$25SV-BTs2Nj3jZ_pA$0$#_;OSnI;t`eMCya^{tU*m4Iu!u5)WuoLDePd&6cT(b@ zRu7HTp{Q1rZeh>bm8RiT;mg?2;wxureaECBb3G00CyjKc#Vlj?)4N$};!wBUA^|_8 zC_={4W8k z!T%pse;pQOxP1Y`gD6M~f;2-nNJ=vx(jeU>U4nE84Bar4s7Ogjr*wCBOLv1q4=~Jm zAJ6%H-}SzKz~wN*!#(43@3q&y_g;$}J4S>N&JlW!8O1o8|7QM9Sr!ueknJ#iZd#;> z8V|3^`yM5sW^PxcJ? z7Dodj5EVUZ%RoFb z z>|@BJgIAD0Y2$b&c|vZLaM&3De?J5oXqNtYv-A>M(uPi+%M#=6R9@YEw7P4zk|5I& zJuQf4j!%}w&3D6d7ftwf<7~h;nH4#+IL{wnFBn(ZB&%Qil!{Pq^P3V+;H}@pp%kMV z2j3W04w3m+x`DTBbQvi%QX~V%DlsRP1Ott^-XZVCH?w-xpOvtew@n~_CqCjC^2V_5Z$aKZTn$h5u@Ekg9tFzxxfnpEIa&sWSN;k`>Xszi=e>U>kLIxynxW*4+r`Zcj zVRV0Yt`M9wTgrAIU*O8`FI?yQZFyah*a{vY(Hkg2vOrk{37f`g1^7okCI>;!4+3CMJVvW;fSI;%Wq-upq|W4=%IARy*lO?^o6;qSijH>Z3;=tvsi}A0+~Pw zM~v}BW9Cb5T!zQi{i}+FZDK%J0jp+M@6kE~8vU$v>>Jg&q1<~~kB&dOZbhqQJ;@@J zkbA)0z0k<;!}3~r*WWM(lD8OiC4+}LqA|)JIK1`}@y256YQe3~K&*$s`Z;3dEIkx> zH$OfJv@=Dpcsxt&l-4>ND%VFo+dOgIa{Pp#umnER3fmq()%iMm0d;Zn@(H@sWVFLL z^g|O0A5vXmdIbnG5bz!IG9t`o#9201Uu#Aj`l}T}Qa6W5(1lMk=RTWGw@Q>dKpoYH z4sX_JHDl|VKcCUmDXYLu^PGH%zv6si#NHUpV{y6Kbr^5k)e};%H!5 zAS-fOcd228c5~zaQsuyM{9glvP990Wg!zd726Ef|j~GrMq&+L|y^s?Cyu3Gi>KJ`% zx*8Y;drZq*v;)Iq?HJFuDT$yfW+-kzf&6(yY+N>}0opR}KWeB5{J<>A71b;bZC~G1 zk;Gf@6I`)f1W;^KcCjoPy7^)XKw1Xt!pD1nkb>b+2SET>t3BKRK>606u&nAoAS0*i zOCzA!xU=~XCH(yQ5^_Il5}rf{uZZxW;rIWIDDL# zbP8aY^;>_wc$nxG!2{4v@kje5g5Ovp8$ygFw|nmre39!6?6jvTuMhR5@{HSJOp5c9JrXBB>DOK>2>=s%PEC_ z4_nSCytw}OykG7~&ox#Mo@8DPYodg{S{pDcS zEs3eJVj1!^SLvvAYir7|EsHSuUDFkMOv_`+v-OZAJEyMnQUCMMlyBo?(9W;-+AM!f zQWsi&M%)su4&UnGHTy={ezX*Ky|?(TbWqih25T3`h=-lik!#%%s$!;JG5nVxUJG6Y zxS7z%1)37^jbzX2$>$;-l;=7hBz7FxgfE!IsGzXT^ovTObz|u#%YBs3cfjI}+lR)+ z6ICR5W3CI1KV*Ir1e&OoepO%L8I*oxGkohi=3i-EadaOzS3T>T1AhmlrI!Its()6~t%8e15Bch|47I4^hWM!C)@lwd4ntl>@|Iy8zbTB|nSG!sfCpAey zaB5a_dBCm3iv0GBLqto>(oSc0W#69T6N-?_5#F&B{Qyj$*woo1O+ZA?@28tTmhz{2+q#Vc0+5P-RmYs5 z-Av{CC~?^1)&F-fB?mwFUkbc<-c??SkQJ=FyZG-KzM=?KfwdW-?#<3~4>-peG^e^l z1#7Zz5(#E?$t!_`H%twfTh0b{S^HO{BZnr!yWALE;1!eg*^jS#kACx-F{>1EYBny# z9CB`WsyBz2@WNdURop}s_-H&;kx~s$m!=q@M*85SyMoC`cH5~QZ6iTAv~BTz4m*j; z((&pf01sq8HEEThqm!BP{J0T-5$eM=qrpF^8&D5*bkl=+U8ac#9Z6X6>VaP^MfmT) z8|HB=Ve?hBYU0%#Tr?G{r!$RU8H8ouy;`)#wkz&0tUQqF(`2{E1&M(+Pu*$emHvk> zO@ktpsb!VU0;LCkxft2l!CjFq0kWU>gRhUdY*melj5#}<((w9;$Of|^&&{|;J`PS$5!8l<&fY%odJ!#m4KAv5G>LB%TJx*+5kC5`@56eGd0=1rdh>7yIq z!uSSgu07P)i_9V3d)WJ~XYeAU?%fE1`Tgt)HlpyEL{uS<>1>AIOchNRyatb7556c=))RF0Anpr<_3TGK0ARv|Fd1~z9xfpL zS>oWN@uH5~UEqEV1}d1(e+8{NrGT%ebD0coqP>F;` z<61swibEHGngfO2lXJLQ#31-!0DKMKzMm8)-OPb(uT*v{86h2DNO~M#UPj>@P>#|= z+WouTsG#-$ECtFVW*RAqH_Zs-Iyhx$F0;=Iq1~@@l2FC+k3hxoc>V(%NEUO_!4FoD z{#1k_0kWea!2c&oAO&3pMF=5yna##0!3ex?3RrVR5M(z7#YZttL!_~wZuW4+rWUqP zpC5|)gZ;q{hJApE(r0-@{>sMo3HT8;9w2^+63p;tnm~r-0gdA_|6P_;7PNL7c*KCT zH^w7CysM>kuSSJzcJ!Aq2N%$Gx90c-0B{#?0WdX2J(NW>;vMF70S&PxbcZhc!G>)G zKiFgBDH-WYV3a}{_)rq{mlD2eLI3;jP8z~Usv}HzoEBx*P5x!E0>PABW0^<9{7PKF zFJtI}B}(v1$sdC*hw0emve0hEygi9X`kH*WYSYvDVtSZ*sX=`^X-JPr{dYku?mYGB z7p_5ayfZ7))X|?_j#cbqw$knkMzjQZ9U^BFWxt+dM ze(h7~Z&SZ!+WSp7L~BiD2mDJK9PcF*6#H31j-)qHa*rHvz3#chxl8}xCVE}7X!`h- zQuX&Y(l!3ezPl&KKqE)lhGQ8b_ycpqx^@H0Z4B+Fx9-h+&<&YSNc=_wl_Iu+C|{^a zDwC&WBq1dLgLuMPqy@qhEBoYJ@tHFbS@UcJZi9F(M2Jrsq|?$Q`EfD5n5Qt~gOtx``3^|!ATpq&zXK4a3mPxJEpZ>S1&|{D1XyY z(o3X&n4$TAfoT}J=LND#F`gHd-mw*|%=PgLPz|eW7IX1+lf0d-t%YEV_i=kZvx=pS zYUU3Jc;*#LAs0;eHaG5>Mi9rZOv8YnUh+$;8*M zF4m@Mr~ukZ>Q4Y0QVP!}Xwz}(1jM<)8GR%`R`Way_$FzKdN4cB17HP+&EFo$q5VzH z3CH~SF~Esen400ZWG|3``9k}HHzhu~fGwP%%Vy^V9n~6sxt)G63pKo<|;o*R%gA&^2awwiU94v;4=IrJnoD?fo^fdAjY7u1GO; zzS~*fw~XY^Gpw6AOwU;XxhD0W2yrPT^4`4OgHV;L2OR+1D}l_ltdHj#WIq3(M% zKXXISRdxhQl1E(hRh?TG!HA>VX?ND(+FB&M(m3K!nS_Or;!aclf=_gz04aKI^_7o1 z7U~^cjf&@tzn!?ny1qgdp)bu#eVz^ObHBMQ%agPiY)gNG3*ptvYnKOqhUef(TsfD# z-J!YK6u!>ESKIp1*aX-9+x6y>G4vAnkN>R~)}0m5i`B`w;r`c5!6#zjK~Ji^`mN9y z4tvTZO%BSU^$nE3#6Ep4gZuoq8iUg!RzHWr34atrx{6Nemlvz5FJH6nc-$5#YWi9H zjIv?teshED19P#0uAWYVE}~IP$m1G>Ep^j*n7VPzw_g#m)+a7PP^IlOA;s^Mo<$pf>60NqPoBbq?= zy*v+t#*6qf!S15}#dS=?B!e=F5R6X zmtugwQs^Q;5Y{RV%*fDG!*0#MgVPOR{vwmh#rMO|{@(!YA~A*zY5>K;3K^t*VYi*U zXueq-2(b3##`p&R8tFRLc=HI*4vJ4mdK&N%?Z9K5`JW;R zn^gc@qu%2G@HF&~aR9eI)bP7FB!3`2SqZpcVFd8fzE7CdwDpDmJ_&TB{dU&|z9&G} z{|7*Q)3tMl;@OB71NXDVmR6Z8(0;>xV1dN4z)UGHbJXDgye$$K!cz-DKjk9I{JWMm z*p(IY;dj!bBZqcvRm5t((1KAaJY=VSd-22GZ!35RWNqFGeUg6On1&{1rdRjjb^NF+ zjJJ`BaHg;w@Jc)0cSu}(MMv^BIr3@K)9peT07~lpB?HF-BwAprCWToge$L`N$euv5 ziZ|5yW7~NaBlRNaCm##zCD&*aKJu~vlWj6E0XB#HH=P zegEkdb?FB!`_2Uwi@fR)wkC(ZfvLLzwYS!G~XT;wC0U6>j%_%9WuKe-| z#JlT?8`b{?ylJ3HUk;s!{TF%#hdlgV*{~4nuK&Nt1q|`74#?smw~N5N!W}Z&i_Y8} z>!F5cf9y>U=%~CtQwKIB6YBi7T$P~9JI#0Yb&jrGzeT9a-H(;4K5GY2j1H(TQ}4~_ z**@c6@K-}Und&iRh9L&AY8w_Nn7e9u^(L3yRrP;a!oR=O3LW?#4xB~*=4CC<+mrw( z&yRmN^>5rw*$~)RK)D5o@^*XDHkKOypu^GZa%cT^2}p~;|Gx+S7Auly@Xfc_>2$Zb zG3L2?YYmT%#!5PHT>ig{y!!7&94p}R5oW4sPHGxzT-(p+@diyrJ{{gor&Mdm<7`(( z;{CM0X%0`#GG~h|`aRrn`*qf<&v)Q`-Cx7qUjY^Sa{7@Y3aWo|S^Z+*chr}|KQOG3kr!Jhpi zy@9y=#gXCb_gf`eNyFJ1QWRX`AMnZ>vw}Q}3}{TPgiVLpSqt>nX-EPS-^m;EBMH0!^g>4-2fvR(Hz}O;(-qnYd9#Fz zFeT6mnfOc%d&nA_DOsS$rpxmqh$yHjNl8`fa-gWtcY8iaq>{`BsxY_8H2Xm>$-+81 zuB;IveO;NsGbP5rO-A+NGsV4LpQ!I#`RP1coV%Pp8)n63XtwE>UD9=2!Q}};6Gj@T z;B24o%MKZrlUCPbcBjLbXya~dDEI9;KhMIh*uBBFIj)~q7hV3S54th_q}B2A*`=cc zk6}2-OM~bv>AfZhzw4Gz9haGT%Y3n>F92sT;%12WB%#Dn*^I4!^wmyr(N;NSZ3i^3k>Li!UC3eZVS z$OF7%TLC8<9*)qDBO};!>$#t7$A-81m$ySscL8l@Xg90(2Zt%>dN^>qy23*%xr&(~ z$5Fro|L$sl6FmPKahXjo4otLK{x>i3`IzyT3BiIP=6&F~mf$5`Aj3&Q2~2GgV?vey zeiNt%um+oKB)usW&=kjj0`|&z!9N7*0Ti=^0X*49Izmu{?*=G>AU9+7(VM*4chCQU zB`MObk%FaLlG?d?2X^oC>HL>a2vT6x91=bPjn|SS+J`LJNmji^OoOq(_t?GA(-2^@ zi3R@zhlxvmTVyu&SoQ))i%qG0uDxq^vi$-z3gCO&`tseO?FFQd0Ov0-!=gJbE<|Do z7Pts?)CipJ#$CRW7#jlKYNCCb<=Kh~_ZIi6!=;6qgFBew ze{id=Y`petWB`A$a^U$R|I%2t#F)QuRl5n-{Se54Cqg#}Gt}O9{^VJg5=LV-$WGN`|nVPiA+JL*R4`C=AEM z7!6KES}Gn)l0R~K@d>!^oH$_CL~6u;zX?^65ySV{AJbbgfPlZYf~9~4(Bt>dcjn)hDiuY5P~0S@#Lf4P{ZinD zkb~8#KzB<~Ha~NlJ|;|Sh<990b%?IQALG8dN$k#6QpY#0GNddlexA2UDi|wS=V~=3 zXg%|zzh$mGZqDb7E;#HhkM9V)Xz&tzU9CK7)38NZu6yz&X}dwXUO0FIdq{{MI-!Rg zlUID-yOMJH5;`G|Ja~AwehCnK(O6=O%m~$+XaJ{C9uZq+cL)CgWy;3jp}CpWD*p#0 z0lpN-w)=|m>v+6!5M{*)GbL#}mso75lHz`69V@ijc`eb#k=S0ycGY#c^n1=ou+oi`k&XHk!MwZT4E%Q4jH+&uih80}B_`<%47qnCiQDn*ai4%91D6AW=t4S>BFaD<%; zi50#2yW5r-im{Cb22K`!HK4ow?Kafx?j{p2WY_cBa!rc4bj@|RFd1^hi@Q{cuZo(? za$IfYvV3gYTy~PXymeb~4yXwvaq^!llRal*5`$XYjvk6 z3cIvL9Q&6r15!_~E3Fpv?`Bv={VfdcMEFzjxmo_~-?q-o9*&wth4V250dT1L>rDrY z)WBoWrq84i>4z??ojLeG$0N|Ym30c#hXINpvD7RM2-xm*Y?7WexV_%iEQ}-zIBsxQ z@601c3qnz80gBlGU1*a>GUT0={RsTh5iC!PHUY+c;@jw;18+vZG;Y{6A=t3X!R6gN zm~-K#LJ{|D&au#YleG28GxZYU4hh&nmRwlTU-*2q{Sk>|{e*YkH=B1ZShQ4;(fZ>- z1E>}1AszD9Sf;qT_#D*FAE%A()SvNhc6LxReV<0W6?+Y4R3n-*dB z!W3a22tvExsxLzt<*l*5bfM##eE$a31~L4qHNC8L5zMhu7CeZ$!30;}fqWYN{!na~ z17R46l}9dG5dy89qSwnJ=CdEkzuZc@gs4OQxJDoo)HaQsOY>q?)ih>El*&&eKgv8- z@jtQyLvRl>?uC^0z7L!&3KRM(ZjiraGg2ODHv@X`zWE=#tKw3bnCnz z&+udoaVKtxywvAFOa^$RW}T&Nd6V~T$fXkYB{Hdu@t$_WOdYqv3c13l!lW~j~?l{EgE_X z2{e_*J*pGK)5fzWCPrfz&T@p zw#T;$nbuTefOtqyUJ5pCKCp2Yd>$#@Nf=&q{xWoYA~9xjNMXEGcd^|6wo)(gO7=|E z&apY4nPj?lOEwJiFLXlptUu*MKpwEz_^aI{X5~{p>6F0a3@S@;2U4Ll*xjslM7r)v zZ>EQL|3wAKsn^J>Pvbww$bUU;_sCxVG@fcan)gHx{c&4;FXpN8{>ZzepcQHVGnx;d z^579M?KG2;b1sdojp`Tp8&GU$)?V#XukLe|sj}Oj%GC^y`j)}4w`%AI0UTHos=2iy zfKKVbu7H8<+~nwjgUZyOGkx5&$QUE)-p!W=z?jc* zuK6`3p87_d@^67Q8i%b`E#Egy6|x1(!o2&#)SZyt^`NbSnhDx!xK~3UdchBQG|ISX zmzZ{-w1u7Z(48z_(EihE+E|8kgzgUv@#5yD(t6>AyuDMdq05`_kAB#HW@`0MP8jO3 zNwLw0gYMkPis`@PeheLOHBC83-)z12zc^|Zz+*}pQO3sord9-AMVYuK6vF;D4pxz*(TuB(S?xoh*>LXlb$8{>*xOmB zALdK?Ugn`$pC1-%AA`_XPPGyx&&(JDJuf>V>V}ZKTO3YuG#Zp2iysjaYa~~v<+G&o zNhZq*j3L$plnHUbE-s7}_pI>o?z_DYD4UX~HR&UteDzTxXC zRUu*y9P8!iwB5Ag*%%=LRqc4-atTt$ESEV?=0|lXdQO-mN1#GV>=&T$bj0xLNnV;j z$Q#->qBQuvx0QV8g2&)zWnt+FKfPhsJY~?^sR`7Gsu)@;5Q7DxfANjDiisRyfJ)im z*)r;Ax}R=K+xxg^g~Je*KjnmjY{~~VK0haBWTU9ekv6d=?%ey@os@fOutFf^!Uo+W z9Z)W;NRE+mH-pE*?(R}9f#U}r-mwvigM&jUsttHI!QIEJ4tTsR_z<5XH#bOR0wGt! zdlPv-lhQ-$+30S9&q@YV@m!Idam%f@NZ;a@Jq{(9OOzMo_m0hSd?zJhX~H?UZ{T<6 zU^^FylGg~i-_x5x<>a1^G_N?AORdU8Lq&H2$xE~l3q5J;P_6hD)TzOLKvys9!w1zO zu!QZ0XfkF9!a?F{7yAYBLcLIY7Qz)(-YW%t=z)GdjpU5=Tl4xRmdC0R$Xk0fVR*af z`<}yeGlcByb>{IKHSh_hb2>p2&~s2-=GYN!m@aZrb_zOeGqk9QQlvo^<;X9e2w^9l1ZvOF&>-w{>ZG9$F zgJqL}9|h3Xe@yDSbh2jeyp2adk_M5i=x+0W>ddf>50jH_qUL@M z?K>9Vscp!El`a*6W8}kAe`305Ez+z94JlZRzV64;($fNNq z_H$pmIiOlf-cAh^9NrmG2J)}T{R_#0D?lF2QEs@so0MBG4d|I|prHhl_D2cs0e0D5 z3yP9T2Vlmo!se=3njtKLf(IM=ILuY#?SsN2mUmWP6ej zqg8J{;IujF$4oIM(uw7Ne4L|(_MBI$oJ$ts!}0>so^@dps=H@P-&;KdIK0NR3zeE| zpK-}CSpl69m?Jq*0S;%&)~%yczPB+gmvMKW6F@X!S&;kgYPXg*8r89z5|XMA)quAM zu@&P$c!YRxMhQwnZPVy0Df+vqz1CElt+$GR1qDp{io{tscC=_EpMmRaAIXt&F1YN_ zoIznyIQmd;J9!HUDstYc8 zfD`U`K&_KZ=5$33`TiWc%a1_Q(NT43etv~n7+jo>Inho7*R9;5jITCoeRTx&6)%yZ z>7*%K$~hMbuSC8s4oExo?nm~B!qTKq{~mE1UPZCT+58p<(s&5b!Hm91(X$APudSc{ zL|*3*d^xhS<*mZ}^4E~!KcGlK2)+ZCebKUj(~utMB+;+<4D!Wl5+l8NxaI3bzV+7c zZLjzmJkuD@FVLkk)+a1+^FU_S`fiElSE9-L<6onTsRSD=h{)@kGWSU1;;o+^n0254 z-d8CvjVwgsss_<80V7JGQYrurW}w{AB2 zXvvG!JB6M|;eqO#O7`=Qd`5^K{RG*i^^aewPxO=S38k>WF@gu}XVrm{zpGI;6|&o~ zm&_!dKjNTuz^N>+@zJH)a)N#ESqH&x`?-81%U7M&^tUOg^0?aDpzIcy>Gcdy#}_1j zXy6ZIF7oH8dw3mm5^XHdw*!fN0g>XU==!eWTmWIhk7@&iPY&6{CNY7|-RF%HNdGogcqjM*em$+JjtQ7ul zFavi~TfE2jJb})=fr$F{r{xXDKo7J)AzKyk7vvHuV~vuLub0xlRKH|vp9 z1pJzJ_Vo#elF28fa2&~>P6!1&Yh&PWz5WlL|G2z$^u$#TCKx~a?rZ@53wTQcKt9*G-6eXE-&bqpGi8ke#|W6{W>JT&!wOY}ojYdepin-oCq&9#<-A{=kb(lB;I zs?FIzlgG!1ub%QUoR2B23C!C(jSYuMBnu84;ek9Ydl(?+mvlD*h23yKOJW+juCu?; zPCw6t`@XS;_hBEDhlugVdwk8zg^CR?=-;I78))tz~szo~-+r%+hjvwuV%Q*_x zdQ3XKwoQ;r+tLUcLzX7NZ()^J#mSU+G-o5UF9u$dU1N4kqP`q1cv)&EFo)0m^jDx1 z=es6*WJT{&OyYDp>-S$4tDvNcyF~VV#>+@_c*Vze>E!()C7~-~9@)G=S!_3g@w4Rc zN#;<$?syXv&rnDudKzv zqk&)c*3ACw`NW)(;fGGrPdP~VAU*`6CxC2z_WzRj5Uj$OIITW!8ejVDHW$?EdOJaqMzV`N4VZ-}Y}cf* z$oa&n@^p#v+g$1uqg(sNP1%vmcm3(qJL(B`PBksfWkX|A1%`(39Shfsn6pjzudgr9 ztdmXM&>O%7AG)BkA#V?;#)WG;@%fUHCI5jD)+yL^3U=RcRDmh5s;prjVySQ9E5Gi$12cE zUCf#<5aIszS6zMD*`6?+=CnxXlU#L0keiyci3PilmdYg=ddW)RFl0XlNLsaw<1z*&D}lSClCou~)wZWA9e$JgT>Vf%3(Cij zVQnOL^>HR3mhoE3+Bb>|6RWbkGXHC;xCO&F$|7mR@g{V%wcIr>x});@40gCzR{O22 z{4N^fO`JxN{k-9qxO#86ELUx8UDEyMK*`5qvDcLCEnU56(l$ZJ4gHG_;N;Dr<7IY zR^x4(m8S+GT`E9m^PA+*W;`F2<*Px3TLzZ9`3{Um-E+JPP&DiF4t8YD20o^Pqfe{` z2hgzuNq&t`$Mj*X6b^8JXZ#q7oQl``s?(TgerDr(Fs=&nbEWkJX8Bo~Lg>D;L_^kG zI7Zs%QZh281B(16F@I6N?}Uz=c04|Ux7Ag*@R-*ht&gCc(w}xX#_=Wx3`-@(x=5K?2 zREu6xSwAZ09s-mZSyAt1rx52%VD2pW`A?|+)&`ksqZUPOm5N-Et*G#*#-5CqNdq*Q z$3-DS^r`tNjaY8;rzsR!m@U_j5=S=4i!M%Qp5@zE-=W?PG0-IoX!lP^?)Fn+@GVe) zH}9@@dTKSOd`C3c`94#d$}$9su98WoY+$1E!@5M_{r;T+OzQ$98HQrc`K`O%2Ph|0 zZ>!x}f)@l+yth_e`RlKWZ{i`{W#X?+#Y&cH(7kc7pQprC=v&9!UU#89$sVXQmtQpm zMPylY%f5YE#9+V5@*V*R7C;+WM--Z+tNqYv)>xE#z(k3~6bZJO>d>p|-UV-CY!0G4 zfAbr~YSc!G8=PazfsUz=!lFP4&nO?Jnc8sWoy&?b-`lDxp(MkBUaK0p?_PHrjfaERI~3Lx z1+GLmDa3=IbYul(nt45cuN2yZ@pk3=)Cjlq%od}5>Vn`{G3Lb`d^xcU56p&gjo&5< z95d&F2XfmPgm(`y6+MNUi=57p?jLI+vEwq z-W|^@PN00>!SJ!;q*(mrNe@J6S8(}p@h?}HGu1f+I_I@! zwv9D&3}A60yq?GOuBif;;(2~z0+%4;9l^s&<#7^X!MH|dD;rzh>-iHqZ<<>z4Hr?wTR)`HGvzij~y zLu}FofMF18erL|pLM^)-d0wqQOC!FX)UD4=<%L1oN@XX+PxLcB=;;TGv;88arPkb) z1X3q)?c4hW23ud6V)s|!h4nD2qXm4(^q!g7SbXS?>PEE5&TB$KJW1;Cl$`ZKXqX zHGpAGSI3r@r(LeI*;|&V0CwgR;}^{dKdEq-W;^TJs>U((pwdU5bpk{wqqvqFGbryC zzn-Bd#pnIOq}i9O%l@=?OtFv}ghMUSk0G4wZ}swsn0no$ZptX!mI&lu)IZ14QCwzF ztft>)0#;Zir*V%jy*_h9m#Q~163euKwhrrZUN0Xb(rt?QkMEZZy9b8HSMF(#pfB|V zZ8+ifx}oTFZepJ`$%P_MRabk{!&cf|_?Mc4_;oxU1ZwIOv~sAjwT^W=bDkZV8f^a! zKZfodE#WGCW#JMmA|vuky^>r#o;}DRNGym^VD>4HQ+$y)-1AJ~M3#q$faJeuiX=X)Z!~49E>|Jiko) zE4whQeaKo2A#FiVx_8dO1IMRHnwI}s5AK~5kWTB}bXJ}2Kp60aN*GG}({^WGiJp`VYN@(mIa(Wx+jh*Vff& zK^G~%BdX5k_m+r(L~E|Z^%Tm}_&KLGT#78f@~Yh{jjyE$`ex{TNK#l z@8zeJ;K33euncjX)IE~_SUpNauKYAQF)gXOrBY#l>fy7^@ATQm6G!mNqXhT;AOdrM zZHDW8HJ$~d%$UiqK0?{!HJ=x9o6E+3ic?}T_W$XIIlc|EfY8k0wVe+oz+xVT=&oL!LAkn|plyWcRY|uzGyZAaxqOivA+Y3E^Nx!r27<$6j$EWiR=AX4b5m(NJ?7;Om}!Fg*sC(=zR@KB3jJPLXpB_TOmyqh|yGrQBf-ED5kLS;#jX)t}yPm z!uQ|{x7GwH+Ju}Kkco_3!>rSO>*QJ1uBFMv(r9Bk?{RPsfh*AYk5wme3jH-AH2h?Y z%J#wna=tV)f0o63S;u6A=kqrb*=Ed*Lkwol>|P=clcS+Jx!Zq;P+mqNDZU{ z(B}oza}oXEn#XKSZLS@~l!P2Tk^E5)7)2}Xe?Ylrp`k!G1UnRcVA}*$Qg!4fcE_lY zkY9@LZfadrI#gg}%JNcQg@I+cBzrtaf>aaVDS4+F51*=Pn=(+31@%P6@-ZFOJHNH9 z7;>HB61MdL!~G?E`*1S**1-tp+ch4ySY}ID5fi(7JyoDVu}6lgwfnD?-5clduAQ2z ziLK`lIJ<@T$na-hQ!IQ_=EZ^kAzh(oX>(oPpW)yO6Rd`$X6ux*Y9I=@1cnranualr z5l_6y_qCcl(oiiRvBH`ETE}cR2I3+HkS(<~RsG47RPHw%B{o*#Aa7!e7*S*cw!2F`ywM2PY!&j`Q{{uQ{Wgc~4WW4 zD_d#Yt%jShrLp&^o@18zjQH7UX?Zl5WL6fY#VdyQZ}K&9gVm68#V6$o1;6 z4ryRz={LP6^F#eB35-9;pWcUqg&r@B=FjDf74mL1@RD}+kDwHti^U}-@f<32YJbgw z0v=L~fwEWmJge=z4OJCA=Z(fJiaA9i-2`g^A=S2IC^#Oaa9R!scouma{OGx7-21Jm86s; zMI_@M$AQ8q{6N4^V5^-ps=h5klZsZC2q48x8Zz0E!V_~mWU}f{d|i&Kp!V@arn?g z>o@D*0}Rb_qj?t_cFp*gU|sEf11lq(XBQE+Ds>Ea)Me(8?Niwcg2l$f?aZ^WMBF-h zle8ttjt$d9syo1GZOx7*`ZPP1^XaB=@)o0H+=gDd;7&621OxB2g{s_wxSJjNl+A+2 zNFZY?427PC()r@Ook=s(3M9NuV8m9Vy|WyFU}Ui|zHcFQ?~T}x_1IT0&~F0XY-vLF z^Gcwc^X~ozSsSOJ$}#k6dZ~?%ph~``Oyw+hP5T(z6-_Zps62{%5GS)wQKYTJ(K89HD`en5!HS zs!bqsZLsmq%M~87`;|uL#a=PZaqm2{0-)-+ zX{e;5^&2{s^TRh*T3g1O``MHgRg$>zCUz&MAuC4Mx6sgf9x=-lMAnS4DWT68LpG-a zRkSb}PWHCz@+?86w1SQCyq?>}^Y22R`u_t;^zZnblJF(cv#_O)F~ZUFVvFdMFGQaR zgigMn717MPr(2Vt|NK%mv!@YePy1>KYbnl;X8)XoWP?vu;N5U=;E*#w%HGSpm#G0s zL=7|^YctS;f%&PVr^&pQUTN#i4T*7IR^IEsmQE0z(Nn6Wqp&ybpB$sZP}m+{2^$zy zW3?yJzZ$jEUL}l^$;njm4JwYm z#dY)B@z@LEpHT~83`iWDCd<*bxZojD3`O!<3ZsYuzn6!-(QSC{C71MAB8Nwxpb6RR z8OFytk%NBG%2MEV_8OiNqx{a47$I*_E$4#2mwJsE@*FTDu@_etz^>`-9~YLwJ`ftC zWqer;8a#O~`XOtY|DB3#XwXp)}ndBNW%R!NUFU(7=?wiOZb(X$f-^PmoGR zz7k;k+_iJXk?20*@a69YztY7BZj7z(Y-`DK8tb6Cw<6tc^ApLigp9|PSa+`Sw&c6T za7Dt3J?s5&CsX z^jX40$I&{0jDs8R!Nta!l##&`QP|)lW}X9Wd4`?=-3Gm!`LZ(!PzedjT!&NGMmr_n zDukSGuh0Qq>k^jcbpsbHhq|2H0E>Gcvja=hHi)^V26o*~fm1I35#>z2{XOkbdDroC z*bxtOLq|d7l8x@Oeb$;xQ?5mLM_WSVIT<8g$kWd8&BP~ma(q)hrvl-fn#XyFP8X6x zK+m6Pj55np;bJIP-Cp`vLTa6jWwGp=w4hgj)#;OeUul4=IGR+BI$Kby=CnmxB8WH@ zTVp!tg=c=DMM|LqNJ&O{EjgHAnlopbbG)vIm9yzpRl|8l@eRp@si|s!CsSX~*EE?l zOI=SVT_@e+(UjeIxy5a2!T=7jHaGpN*OP!lGFvh+fQe6%(_%pUa%}uD3-I}P=9V&9 zr@=7)OCA&nHB>V72Zf#(B+?HQvRd~ewP)~6CxO-3I_&P)$Z$T7p4P~7)zhV$!$Y#L z31zzoR+?+}Dc>-%yXhl#-Hkek5yifQyh22ucoH`>SbPoV=eP}47?eI(>|$A`Y1(%_ zS><3TZ=Cn|i?{g0+NP<=IO1Y($ii(@O_npTaXWz{c21JbVVHu_2uGN%ALKH=9z6&y zuqxPW#*V?^cPSAWDiV~y`w+g{(ULHClbmSj9~Us|ai5`$8|E){{?v^$V(+>8z}cw< zm0!S;CE{hS``B#0LgXbj$M+A8@(Ss*0`m=t{g#br@A`zqRro`iJV91*JKMya zt>PM6n8Hqu>I0Ad9f;}n;v(bt2GRw7wo}Hk_0jp3SfSMKxxb?Zb#V&fo#xCFEiDH| zsI%7?)(R6g9@D*E%H_%vuJG~Y_6a|v;3c_4E?4+XVhG@lcH$=cP}#C9m6#$lKf~7S zZ)U#QEHMyf@Oz`LFSW4dXW4hZ=iahX~3*M^wnR^2*xdI z;r?v+_SrA;6)YwgG1_j53|DJ8?o_KAT@OR?Q?QGDj8aAn;IhUgX8ivEfkA%0o=3S@ z;*xBjF}!hzryW7${D&QTn&U4#HF*>;%WMtO%EdxNhkCI75~Ga!13($k&$wZ@G=;MK zdew5JeQQTY)8A0MF@Sa=nH=XBQOTeWV2nv|Y|{sL4`^LyP9fwbHD<@LXZ?vn4qPn-4 zOii@D#tY9Qs03tSjDgm=UkO6C_Vdjv#EW+u+o5()RfZTGmryw!Xals=BoJ9f{#&a> zD?>9BahB>ckTJ(@yjDwUBm4BXH&m&80jdx}zBXnw3XwC@W5;qKxI4n(aEp|^r zeR-e`mGv>}Q5{eKMt@r8u0_qfs~qsj6o&*WsZ)c{^HQ~rpqjdAa$89q^GLCXU*$WS z7##7=MF4F70BIZ(x{vK1`KY}$pDP=ky)N3fo!!kL`{m( zhS~-@k^L*C@ZOUmY0+v(%#+JJmgGo2U5cvRI_D?Xw@SzHt-OO!wl9Wr3Cj)!Hy+2m zcW;HindkF0jJ5Q!(4;DKI3@DNHbmzGuOObs`5&RJ8(D55)gz3g%oA3VJ9mH%-f^}O z&OHeK0CWy&o||ZA@WdtVU6Jkf?85QJFb*nhbHes8`0maK+%1*E!tWEv?9aKrW1dew zxuY1b%P%2i@8geVOBAv;lWOIp8?5e_ZZ0}G&NCqE{{ZU;wOg%4TE^i_(PY|M#uv;_ z?*qnVJ-xo6YD*svY0!LAeL6_dtRs=OTd`&zb8rNoL+em@XHC-^TGnH@Fv$?JpUE=D z3LyuE9eMyxYl!qo=hQUyxRt)sY^pUmSx@fp5m)6uEKR{ZI*)GkRWz2kjB72$MHj3IcA!I7bfNtQ(1~Z;8eYW+haq2ev;<&hI8E!5v zZitk}y8$s6A&cWDpd&t+>riU4SzUNzLDQln&uS)TT;l8!dAda=Usj;=zZMC#W&B{!sS23;?-)Bg{@;U z8wb<6I{n(a_xo9q-m{ON2uw}cH3)q z)CRl@%OAzg%*(rOkOgU98=sr{Y4(S^cZ z!UxPs^b#-L3_9YtaJW!=V>C1eeembR{{Um1bQ$ntxRjXPjy4iHek2dhwe<}%ZlS2y z5HWQVG7t8E$UmR+t`ou<1^%_FES7_6!z^tq+ki0wcpzsa{HLd-dS1H8be1~JlN05+ zT#!cW5(p!=PV@l>!~H})l-7;Jma=Cas>h$#Kb3T0jgGK~_+2(WWis>m*x5j;*rCsV0dAXUW&$DM$AUiM($4gau3{*MndHE+^5r~ zYlGCSzR9Xein}9|_sGB94b*-OxK~CVeHqP&h1W3tly?v{#~IxUA=yS zx$Eo6@9yNeoy*AQB-Pz>SCdw}^9~jy8)HGhRjjJyOGCMfMHE#CD58@z0JM~pQUPfx zYg@xQ8|&K4cB3K{`Q~xiNA*1@V@GN5>p&1f+Rf5ooE3vV!oAz^>Hh%ht({)_NBLkG zo_6x$Q{VhOPoM<$t!tu|@JDG1gpE`TFYu`71#x$J>~>m|&ZQ)~j1*MPRv%pYwmA05 z^*HBl?A?A(FvB>UHV1we zCqIRGpNKCmbv7?^Jd)#(8Mt4d=qrqsa7d)s&t1{{RpFf_W_Q(+N!(x*f>X4546Q+J zR<9)-W1f|?niS-+t<9{Gc|v4JWHK2Ca5jVU4&dV-Nw%G1AxI~aZN0DyKkqI0mGV@4 z(B}#X_Z>0Tm>R=g)Fr`t$-m$&xAYZ9Q}VT|a~1w4L(sX&UvPUGc$EdbMi}E!F*CyD zPy$9nA>97}bbHjX-)^`mWb2mA)w-!t!M}+xs&abZamFYE&2_H_-B~+JVy|;*IT#sr z`j6{e$rw1VbB^{|BL4tJ5~(21W(S%{$NI>@!h(9|A57OjuW0&3`aAhZlS+c>-gFBY zWIb1z4^G3AKptAGRQ0akz&3J8E$!iDRgNGAdXi3f9r{&o_(0_|v5QfLXqMbu0*G0d zcTl4^Bfd`+*J<%4kz^vbNjBRsxK~A#d6w_Pe|LUwk@ro6AkIuG^^u<^!S?BxPmd0BC}5BPMiLz?JXUB?~JjfIrnRv1Qi!zU_!cR9v* z7{KmoFk&$5kz=`qCTlB{0az4%QGr;`e*Bz{DIh$$!Y{Pm#}7X-#d>33Dkjl@0KguV zi+!Y8Y4$eP_V&I^%OsZ97*`u)QV7oOnFpW)r##kM-ZAe?4w3aCpS@8XNN25c(Y?jY zo>VbOE8w=&QceKLJbO~w!FhZqHqkty2+XqW=V}h5`%nh?)Q7D!>O%@`7+U@6i5LG+I5}{u{X05?GD269`>0cY<-xOk?I9=mON5lJm`H-Cu80 z%~-h5-Y*GTYvScyCY_*YwqT(d!Owi-`BH0MA6qR4M%3-*l5e+0=2a zVY`5EcCz{&xgN%%d+6FLpE5{yyjHB9W5!N1{?oY}9@*e>0IkgvMzC#O+B>+7%tek8 zb}qTvalzo%JK-%d(XO?)rzrbuCJORK2t&urJ;ywXjB0+?{mnAzCqX69u@0|iXQ&wx zc!Y53CHJl|umS=3V(5L3;5yY7*P|A3x0wF`@#icj3nKv|F~a1y1LfzYJ&jz_p|u_Z z*W*zjk<2@{5zZfsU{!eKvHt*tdlsI-P0#j;lgel1zCt%+u0O)Kj`BP0S{Q=dwT#|O z{zs83LW{X$P#*<@_XD9m{*;ZX>NXdav9*lJH193MNMym2&Kp#XfqnXQ^c8PZxq|mZ z(5)hce9K7W46L~emL9&iqgd39{;_3y6iTma1S%XR31t~L`V)`Bm=vR3V&hu>0EBeg ztaoh^+BRo)+N0+uJILe?ojB+!?VHJ|YIm0q+7uS^NqD=`G~9teL{sIlEPCT4emu~1 zOPBFnn(9O&kjz-$P7 zqU>3}(Qh={G@dKi1V$4bz*}Vp=Wmz{46x`jNI!*U_=95VH!#|2*EhC=sb+F;%n%Nq z+=0gx*R9+)x@O50vhm>Y#&OoUNp#(tn{QLN)#9ken_Rmy91bRRqSW_9)_0yAF-DSj za!D8{4Jp5HN%i1k^sbiP<~!SDvx@2NqCfKv);6~P0BGg|Dtip#v0&M5s)NDxfwE~7wd5ejG{^p0pd)5|z{t<0D}q{OPx9|Cbn-UGcN-Mv_`t~iwL?kQG~GYIkzH7Yw!TSXj^Pw!%Ie(-^dl$n zBDyV7`o?y&)S3yI8a0wKye~a6eSJn~0;hnl@<3H|-=Ofoz4R#GSOL%Q9t{7#Z<96NOcJWXE4kA=t%CZpX72s3hALMXma9Vr!c^2)fhDV z*ICFqib@3n9ZD&*v;eeFD4+t2(M2E%T1qoi0?|bjfKX{i(vVX7=71KDr4&#CbfT7! z^riyo7EtLHKigW01KQRj{B7&>u739NYwMXVCvws`$tJC9dc>N&>5%-eAlnpUqOE1u z8b^C#(MD*^Q6d^jD5L>J6i@+06|>=u5w-1VD{q)UzdX!4DDCwJlt|Tq+vk<-C{^KD=}Kljs5Ttt-i4v$gVL#BoO$&NvFb zmCB7q&dTatQ&HTdl%=h*jK0Iwi0nwK5z#|pR-uyw=?52R<+wCg+zo9k!^?Ifzd%+)#kTcKOy zcBcz}*F3-ef(>{Tv{TKI6i*>lF56U`DC$qOYTN1e(iZ~SKx2T;cMZQF{vn>D=|CR6 zCyq2>%yLaOf4Lq%^ej|Q<9k8}lWQw~zQKQ%Ys}!aol6In-AckH3+E{;Jpcsr?OOJB zZpsLgcKE!=c1Gk%M^y(MM|uG48^$s}`kQFe{r1oJR8n}R`NkB+p5cGSx$zuJ8tr%e zA5`@0=fNi z%G<;ds%izD*E=QM^Dp`Itp*X#AXp((TZsI~G8kdk??y{79ga^m7`%>VX0~v$x_zSD z28v()dc~o6Q=VBf>btJiLdJd$Hl+Ye?plOe) z>Tz3)1Q}@=n*me|oSOA}%{*#We`k@FSngsZENbn@{vH?a57MY<_VDSE6wsy-K@eM}iB{94V#gr>6j2=MBoPJf5vPTZ@B^5K*9q0q9 zeMD3ZsSjG_n(5COr@%}j?@9Y{ipubHMK#HylW=oPrtU( zt#v74BGTxviamUPS;|lT$qN`qow5 z=a>&Qr>^J&Mb&I=B)wUnxrRBs3T z0W034mXODgg$j~#tZ)b&RFB50L9RrabTGZi2#{RI@-zMBPM*_xanIr7FuL} z5Y}L|j@?|Oat1;-e6BOk&>TGh9^$cvwxws#yJJ8|tz((Lt%`|IE&j?wL-Yvp9LR1VSbyG8~FKi3AY z&#caTSap~q=|1I5<0?4(GAlYSx4|{c@JwU4xs8$J1N+@b^yiuYewk&cPoV1ew-;O5 z-VqFGEQUa$R>QEvaC-LVHD)ay=I2d<;?C|E?|#s-GbAdps6mA*h25U#pgF2W%73$% zmf_-3!JBEoY;@1(TUssHhTY*|#&WgQg`*m>YDWe?5jrqVp5|t*Ez)ZkEp;oWSnamm zpq2BznD60^2651F#TNG31?P)Qwh@-HLIiQY+}^4Q}6=6-5Pt9I97Nu=_lg3nNt6&qA7z32N9r$A3QBe|*q zHUu_CF`N#ym8rC{BQY!+c1JwdA>3fxBPGnJ(HLD=gAvYCo}BaB9Mdf=<-XLSwuc+! zb%{3|0?cqfoi=-!B)ghv$$4FiJ07f0B+(a{1-jfLG;*O6BaSe@lwCQ?>oppC4(a0GjP&TS#pOkj_PVWBzbk`+eIMIA>wSVK*_W*if#zFiK zAB}f9ly4=FAwx|UAa^dD4vzm{p1+IEUU;LTo68vJ!^}+j76wS5CIIhnk;m~azOeVkHA+>9$#eT z#K-Ln2An!mDM7B2kaajy0jFk|htW;VC^P`HQf8Ml08-IK03|PaN>M-#rqZ8kN?<6( zEi`qfb)*8)QqoWY8beN`BQyca(M2V4oujEKD4+$RiYb6mNkt$4rJESedkXen3g~I! z%?ugG`b^k)eL?KMhxpeS@cTg*`ia!;6E^mzC=W)Hx8>LCitMEE1-cfIZu{;lgl2o02LLbdk8Jh&3h_S?>Z4fk1@54T z5oM5+P%-k30Y3NxKK0&sgIYRwg>E5fhxV?d%JW7K%^YkF0sjDij-TzcwOgV^W0VDd3bMN_1WYhE)Wx2E(zP%yKMJ8S-N$kV;+thaU zBDm`-+nqk-Tw2IulmY{QGBPp8q4%z~!sZ)$OHDV!if(ng#RlT_fgVmrD4FSw?fyUp zcZhWR*;MK}t<{_tZ-ACcaUfpbB8(^l)bsVOa3~)2=-PIlV{Wqx8*6P=?MeGytEiv! zNJ;7!KYaW0d-SZiZ9FYyE6F*%)#fZ%`3kns9QGU&$F>CkSJQPFbsI%ZvdwjE7ndYT z@_(e;4yp2B0HdByIjfR8p_9y+uA?xlj%6%G#j)t*G~*>Y1p`0Roz=dlPA|CeK@IY#+dpmTMGt#Nhd7#49&Dhv|&aMCpkSR15M_$QeNQOKb8B5wwMb` z6MfeNZ_I=Eh{+s#(i_`IT){QPvt<36e<&ypy;4*w4+=Y;Se$WHq?*qE07qpD zF=FA2a`MZA9O}7D=b#<2noFy@i#xZ{uSC}OQf!dqF%evU3x+a~Lj&_Sl68;V3$G-5dA0r^fxuk))qCYOI>;&^mnKlXg-G>R?~5W{%{b-*MZgC~G#mv?&2 z<>1t0xCc@NS!M$OFvbo5#~(^;>8Z_fZ&vlv_^@+uyf%B0j+6nRqG-CE_OC9Dd8kcp z(ZMt^2(DCxZly}+J5CO9?N#&*Dt&eJD@)s(g_;W{cpJ|JenK#<*X8H%s2bYu?F(@g z)X_{N-qHehA5om=oY2~HODt|()T3?~?tSP2#*w00Y8no-W|9}bw?&>A!??x?+@u_5 zIP|A!x^|m+;N3Rt=c9p!m$?EK4SRUt?N1Ot$I zF5G=;vgyhhm@W$p6YEjQr>c{L89b5)S^%5GcUpFqCG85jDcTF144h}_O}MmM zbTdkJpui-G0K4J+Wpv$3PXNn@QHxR3$l8iDA2;zVy(642aP8v*Z(M&E)!pXES17T7yeuAp_ zvdUyzXPR?6ki$Dd;Bo#nYe#}bxVV-(d4of_Kp-h@oiciJS2YNxzP4XB-dM`y4={u2 z(*)ObJ#f;$fAT!)iT!pRt^Q(YI%uCpw=Z{gtA++NkOk^{VwX_7p7#FU?aHk1s-iNC z0k@|WX2J{Gdv%5zc-}G2=ai`&4%LYNtNJe;FrmB(e?(%;a5MiK~1M1 zk&J*d^{x}rId!r5a8MQW#XsyrpO(5<9-h`f@O7~du`ez>KBMULGVBC*`Xj^-z? z)_^(0vEBSMmk^s~h;)Cv1$1!fR`%BuOp)!DY;QY{IN)(uI_Y6_cBvazYUk;n>s#T! zh>m<$@R>BSJ<54RmfS}kwN~=nS=mWDpts6#y4=&_MDV1^vBx5-GQ@lz5 z(?Wu9UV*1yCFYZFaS0oziDgC4S5cC`mPK+Jg_8NV`g~2g z-s%rF-}2nQ)Kwo1>NB4U-@ySQ=T32V2pzyVVff&Wr2usHtZckObkvhPKQ*~oqHK1?^!zro ziS;$nMYC4Zm1O|IsN4Cgj*8`eU_CMjZ?5XNyE~I5%$hvoG~j5G87-!g-fa1iF-G^t zf5)u@73e2*bIfYa!@;N2VAH{-0@9AO+|z{u3QNo4k*nf0CQB7QC!Dplu<<>3Mit07Lt~dfB}-gC?u1CiuP{`XoJI= z2KkVEu53v+u6rlp{K>8_;r{@KzTc>wPT@0cY~LnF4=4WsTd(C_fq$sRP`c&OPSgYb zT0U?9{CNE9Dw61H1=PjyUa57b_-6X@)c*jaF3?{%^7ou%d-{50dRLC=)6XU3aYC&u zvbGfzWU)2d{7%(&EtZIm7^3~6;EsjQ3;zJKAE6b%Y5Jwsk$#t!QV8xN3>Auo#z6;z z$3t0O=7)2tL8a&sq*wX9)mcGnRBT5cdIlqseTV-5Ua>XJ68>uus_If$>Fcu=_M~ig zUfWSYJ^Hskrjt*e-rCX|l+L5CUdT*JesK;?H#hg3o`C&NY}>uEwbO4>O=3wkopNFc zvqvnb-Gq!XN&f(3ew<_jg(^Y%*G1vm`CeGG=DB#z?Aku}J0w5C0CiEjp+5BQ5a>6y zL2oaX%F=t68!RC>krx~tgP`NN%~y-Uejt_yopgJ_9Ba6jh^9xja8Kbt8tNftktK@K z7M4w_yCGk*+%NF_?#<;M=YW4hW;Z`(jHX~FZNp*5*{(+bksK!q*!ff*Ya%UT{_5fw z8roK#Wfs%!m7_^{#AK>%!C%KUabwk=Uu_>yjsZ2!+dGL~R+OT`;YDQ)JF<7Ksh?hnd^p-~OO_2HS0!;X0Qjw+ls z2s}V^{Z9VDE%*JFXNDv~0+KiGWWYJ(oaEH{bkMhmE*DnT=90!nB1u)6AjLruwm}(T zg~tY%7Gk@adq{*2Br7!g;sHtWE|;p1kq%gNQP6WqeW|UYeXt4PibnHcQe>L8;u0dUu}6b#P3|U5tcqM_fN0eza&hhMS{LeFfYX6TyFO&?G|* z^Kd~YjAI9pKn`tU)vYdG8(CQrWS%D$$g3N--bT*vlY@bpl{Jf~?3Ylq)9yu`wc%ux zNB~X1Z$q(H8@)y_I29h9tiz^3eW$LPBuzphn?n;C5y)el@(wZ5ooB4gZKq!82F50e z^;L_A!i6e99R>+L{*(YE=A{mo2D25M4`7!PLV@OzK^S4oWlLjj52rZf)NNy{E`z7) zR>^HOyZMlQ>fK&MB%FuJ^~XcldUt#m`kHBz=<6Ip#!@6Lj5gp$93Gqw)ad2Zzq21q zk=N{AXq6R5JF$b4KoaWucB^ZoX_t`SNg`faeVNA54#iW1sshBEC>R6q z0)RRj2h;RViPB1vzmp})rsZG}cjx8CIRTD3_Ncrk_8l|F7q*34?6(Uopx)USCmoC88CeoeA zxEE_GC|(Nf!RM!1t$(d0--GncB~irIlE}{O(1LO?`I<>|;}m<@TW?R5OC0_bucSIg z&Qm2uc8;ciHMHs5Sy&s)nga!tP%(|MyJ27td5 z20M`&$ftQYIL|_HSrA&vvrQto4B)F^;~@11*w(F`z2ii=k_Ctofi@l31dhA0+tRJ3 zmd4|L_SgYZfDC6nbBxl)Ys)U^d48PmzR&vnj8w5;rEqY21I0+T1r!~l>0JrY#LW}4 zIP%UwS0Ep+txs{ITiifnx``ex7=}CyR|7pGnrm+@3%Ce?WRh?IsiU)5BUu+|Mi~qa zK^4;-H6A_{T?puT1XNZj1>`LDu98NKV>>zmJ5vLiw1F-Y&5RO>d- zG8Qv~j(w}FDy=-x2&D!h0WBF-Y>eo`9fZzHd`_dgSgKp@fohnBec#eY!0wfj}bG$a};3VIX{md(2vf$8&a)j9tH;9Ko!b(p##oYK>2z6 zM+f<@p{ygSzZsPQ#4j zvG%TCLA(1s+-)I62jw{FgZ@Q#I(5VsHxF$biy@H-`AOp*BH&GN)#|*Tjn?AYLlM;f*lkDZGj%$(K^pAzJs={#Qk(0@Ag?+w4&^b5@@LN`DR(1Xt(#6JVi;%m>) zeUDw1Jp7j<%u+gT=-B*o_+q^R#^9x;ma7_OTV@bWG544FN&1YBz)%K8xxRfa&rnV# zwwKCsJ9kt0*LP#93#)56P=YTL%!udyS|Hq0@f(NXT+XL!9Ai?jUSgghJPqnT@c#fl z)t#bVPd|jOW49;mdSt78Z}@V<@xuxL=puI0JW|$?kQQ_eZh8X9GJ`&i8 z73s*3MSpFP4(;Fp(O7`Mj@UbXoYcN4K6Z~|uGuc*Y*u7GtB)}U(`k`Drn(;@-%++` zcX^gq@flzs{{Ry&%)f{`zNL?9xXYE?nJ#40Jls?BOn79rneFEP09g|hV~l49ujAM8 zr3SqOd5vpgKxx$-NIFvx3R+5909smYD4=0WNk(W8xT1dr^S-YQ)YBZe)qY8L~{`IjpibO#;Jr~d$}JSo&#@rS zhY_%dk<)UhQ;)sn^YV$KKt-1MyxCa~Ddis8y@rpDf)I2vlR;zWW z&kc-B3o6Wic;7`F*BJQ(*K;n|oi$$*w3jo^H^*nY_mU39kMJj;{Do21bldCrn^wBC zvC^&8F$@7jMaFt6ftEb-Pv|Lu&*^tDTU~>33d;kjNdq8as(O{r0f%EtZ|jr-0rNjV>_aba;=`X;1&uk87*C5(f*(m^AB?f(F~_tjK4LQhHn z-nEWbjaD7=O|+XcA(@iqAL4|T*fyx=fz3s3A_x}U?UF!E#hbFgr1SG5#(*!2xh4@cjEsqJ-fh0c<|)_jAqgHyBcR9_=A^lqrI7?m(528bz_K%e4Z{8S z^CPGo^2B%Iv+p6ke+o&dM$wNt?NV4-nT&F%&zg)}{LR2TdwbPgPe+FDLATa~@yB;0 z?F{fn6;R-C$e;`ib?eW6Rd6&PQnV5^#8(hoyo2pfljV;pWc$cMt2Wcl&`8ZkFNiHO za_Mx)TW#D3uPb?Slk>;MzzP2F7z2UUsA^VPBWN0AwwDUJfZVrHDJ7T#!x6acBzEtb zcC{{xsA-yC*nnH>c)Y8niam>wj1$HSVDd#UA2zdX40BtEBog__Gze`_0LSkk3|#H> z>(5bBwxM}#s==gvihEn7y$ukW;HJSK0HG)sgTctg2TF@w)onaV){{kVAfDO}} zRR=1rxaS=A6&>8Sx4NO#44z%-VBTT_gIgs1fHk}`1*D!B@gA8i%M&CkaEizjgC0pElivcJru~ur9_u=L zWVBPqaDj-=B~;_`{c8y$nkHsK%2*X`ta($^eJSf|?URZC)Ry`Qz8yzm%D#1_@MJ^I zLo0Lt0HIV`o}+Dh;GGuSlxw?LWkz1=r;+#`KPsRsnU6|vvR^mK+EdqAhU@gM9x^g=f*kh$2A4sm|oyBs4U>A!0V7l^{+xs^kFW? zl}r8Vq#smT)UBY7!bG-?IQJD2Y*050=by(FksX6K0B}uiS=vi;1anJuB#R;k^2ks* z8OCv%(6-Sdjh;o`OP$0sWDlV2S>vN>iK9%mPuaM)dou<*5ZF#PWA5gZ+N@K@5#i;| z(d&-2(S3plE~757tkQg|k^?t<4_cn(V6wOKr#oW=0@x?7u&y)FIk|1#0~r?b$-Tn- zi=Dpb+NZj-xrW)Kh7USH(maLF<6S(K%?uABK+=^`!BZJ;VVYR&%+|5WVtC7_ZH_Qk z*!$22FLP?}TQs}|+uzs!0M}S6adMJH9il79{fWjpe~orma9qBa!s0lR=c!a;R1kQ< zBhtADSNaz6^?H5+S#B*It%C}I$+?%ck;IQmzZdglXmYFXcC=nG@l9G~k~?ybD-CPj%< zh}0Dz0$Um5BOP%gaylrhH*mC5Z$W|xB9_gWW%ApA7v*AewQ-#K{HmDzJ?H{Y55Wxa zT0~^o8<4F1ah|5V4#8x&(C;)$pasp2Sp##G2l^k-it{}^md8_;$c?c{``Cx~LFaGb z)9|lEhVjgHTI6GNkdXz_kK!1>C+fU@Q~}Rx`=-+D^%&G7meP4m?Sqvy+*xaBa~_>C zsoQ@Z>phv8h#t!9uNO3Qv=o&h{8dN3SK`wIl0p0T|(df z0@-2z0HIX~>7p&Bc&%;ihT%Hzgbo9RT!s8mw*6zzYOUgpIy-wLySK@O8_kc7kv;=2 z`~|k3U}=0uFq28sb^8EM*Y`qxbHTi?Rg;|*(n8%YW6xtHc&_z*jX z{0q=ii?dA%O6td&f=CqbYCk4hXM1VJC54JV7|9*~03NjPYtT;mo@-Wi96Hm*Fm z5VW+EPy?xHD4+mR(o*Ju1r$+01r$+0g{9}xfN6VBFrze?qZyzDqL34sLTCe+rLNEZ z6|SlO06$ir_tF0V3J1e|Q$O+ZY5xFyAMmbDWOwqji!_znABMV_{{WY(LH_^(KjBUP z0EKC({{YY3r~UMQ!j5={DaLlBuF(88)d2qhkE=uf00KYZS2X_s1g4JC-s=8c(nJT9 z0vw4XCki`fCj%a)lad7ndHJh4b%gq+qYa(7EhNkodI8-29M`LVV0o|zr_eNpe0 zPt5J3v zSmX9wfu5hvvwTZ?zr?)-XmJ1Y%4OVVtkj#B=6%3@`cZZHO1WP(XOdshnU-jEH) zJ?nGA@ZDYCO=%6+*==Nnn(}ZtNLQBUuRIJ6xdO0DLXg7D{FOIeJ%sG+SnW_5AVOLcPHMPcGiUXR_Yy8;a)?_p7<4or(`G~^XZ&s zx2q)3v)Z5qz|Tt5mrQH4R1!Qu5J`ybBo5iFCDS~} z$`HXw#|H-=T1X5fu`CB1dQ+0XGmxMXy>M%yv(ciqfgra{k)Yrcl0OqyEwoE`cf3(5 zJclwekGyGt$`~L?#18A{5x5~gF&?<5&m1-v_ z!Yi4ixcg0)*}_UvFWv_85OjVzXVa|!b5iNI4LlxFMdfqm?#}L9E=m| zKp00$+=OzZi~^u!esvTYHca4d0A8`k@2~`&N!eBO5Z|Db0Jod{KqVJv21$}K~g4zZf@Ff9wsOdwsLWt;<{@+ zB`nd^Wtv^`GnSRh5tGn*0niFm(ygPumhmGWXq6QmvUvlb$3fPBIjMA;Rl2uX79%+) z$={9LIosc-r9SG?-ooAPE}bHUa2eR}GH@%Udka^&f>~jWr;m4(%m(Gi=V|&;cGk95 z%{|<)!wTasD+N$<$0y!^FdIx*;%Q2fs0$n}Pac4BXtlJ4?$$e)P?+6vrI4w|(DPj> zjZ!k~Fsd?7wL@h+wxwki<)itKN-~dvGuxr&fH{j|9dBg&CB$AqbRtObUue$d^#`%2 zEv}aSR)kvJM}#f9SoVX+>0Jlf(&aS>#l6ITXWWIQh@!vC)k*uqwtc>pm1`JEHO;Gpx3f0{fX5OA$5G$uTB&b!b72gS`EXn?Qo=#J4teNB zRGv{Bigx6(aXMs%9?JjMt zyt})@cHxN<7{VN9fI#DpnXVJmDA?(LV@V@3O)zO0!I^<8lh9xe2WoO@utRY)>K}aA z-I*AUI$=q`{3_%Y9!>St&)RMz6Yc%ezEV64e1o=npL!+Jt>nLk^_EXMC1hMk!Ek!z zbA$NM236jhX!l8bBnkG2)T&5&fO}UTuG*u^^W>|JR3A_O0AJ}{?xCmK-y~~1LBw(i z5M+!n=y_~ zpqzlbk%L(C$XrZ=Yg9#%JviXkb~1kIiRa*{B~i@bV)-T6#|MHd zuF!6;FSUznZ#U!&8NN}_bLswbT%@V8?2k?l)N%e5+4v|MQE{m~t;E2(TQ88C%I-O4 zBRRnNbBy(;?OLPECq+uKOzbZbbhx(=+bpp=5i4&1#xcRc>*-ngwY2{LWpiqg8FDZs zBmy(fPio$~GDmGI+r{R}s!B#%Zu5=?duFL0GJ8ZbL*&fJ3r1Kr!;VHr2NmWXspp!l zw=8zx`d2q3C7wuuBOtKHasmEhaQthvxwpLAC)*Mb`_9t|Bo*v==xdh0h{Y&%$Ymgk z0MEII&8E991F!F6#sJ6}KHqoK9jmMGo$OPpB!n1mBl4d;iRga@#bH`7g+izdR~SVc zGLw~4>Prw0v}UX5%xte`u*m=)G9pGeGy&f@XslwEKz`AtP7+a$e6qxTgrCm2%?jvg z9x`a0W*KB?Sxb@C}=1WN$2#a+olO!acOzt0ut9}KYuRJ#{m>U;5bmd_#c?XSeHkN=LMk%!H&;dzB6aZ$EG*S4_2Qp0++aHGdpZxc>{{X&^_)>quwbei8 z;@kfEKjB<_$nWK66`C_$r~E5@SN?n3f8R&^DE|P3Z>oRKdvE*b{{V$PWEN)^nk%;d z0EKU<@-A%%{{Vdd0EKV(e?f!6_IKL0rzCA8YkNimu+&}1d`WiN4xOfW zQ$u~1*QaNgI>wz|L+*L}kF`gr>Tqdj?-1Q>q{0G|$a#;-gWnvV_zA3CGU9m-q2mk0 zXT832ZKuPG;d%@Y$bKI5zA3R-bUR%VHj;f+=SgLXFPWY~rzHOXvY>zuzvEbLYK{k2 z)aBK+TZ{Sll4sq4*mMK%7!^usRnjF`l{PLIkK;KfC-fhMTGaI0tupoPF5>d8Bf(_c z2^j#4;QA3%Prq85jL^|_i=7Vb?(EhtJ)&sRNfU98Kg6Tg{A;Q3?YqGfHk&*ve$ff9 zbvXv)vW>rmf4w30`g)PWovMmM62y>K9S0aW{Qm$d>7mr1hr?DHZLUF(wD*UhcicjQ z>=X_?=wNhFT#IISd_Nl-nGf$Z8-?F-IqpF@+CH50tPNJjRi0)ymoiN#>%MKx{Oey& zzjU^EqB~jmc3uuWGuos3JdF8t3JLi@Z2mu5U~-FRbdEMVLo%P0!NF7ND)gFr-XjU6 zk)A`BkhWQm)cV%a+nMzSg<_QLP{sEAzfAhoqhl;>8bxl>mT(*904nwWX5U_?Y(&Oa~(?0cL9VLWI=Yi%C^KI#$ zY5?YjnG}Ib#H6Xpk~&oX0AcyFwzutciJ~(3vWa&&WWsIOy_b%^T9GtRFAc|;DJDIh zUVcu!aqB=F^4N^yV5gfjiZdhaR8f*izyi8Cv{)`$KQ=A?TZd3d7-8O~p3d4UcKc73 zB0nMXFcjyE9MA_j4YErTx?z!kA%{XJv{>$gv{@>SP?Dq!j=1%%tL$*Y0cKE$i_Ulo z1v5_;+J&NA+Bca5nJT~#4>+I>YB&s+Zx`9+0YE-u3@c}_^{L**3g*lxBJNfw1;ny-t5B0OzOE zW%5XeV3gwp!6UD=52P6pmywawcCLp|u)Szg>?ReH%w5K1By7(($A3z+`gv#>5zKDN zKyU#neR-e`M%P0y!igi9Sao&)6Zi_A*FugB_%7w#xh~}6J%^yKqSsD%ZKIA^jMA!r z(z1YD_aq7}bf~R7;*B$zWHKKzLf9v==b-i!0nQB$0di*Y*Un@LTe$*~drLbvi|rD} z8%omgFWk|8dadb`)`oHX)*amPWyA5Q?8Arses(c6lO^Tae0ge=RE+=QfLF8 zy0(hW)$Sxo3Mk3gg^%C>$*E4B3_*etF`Q!=t=p%H%F;`j^07pv-GY|D9q>7&hs(IO zN#oAR6f)&XoF1GWMF4WDW`jz5rm&eLIQ_xFVa_{bd)0L_-oYoIXwYrO&|Eg|zMU(7 z&o`QE@-?*f`%4Y802u8(a0%e!ip{i`O(Uk>Hs|#p<6YF1@X|+@TG7VA+jahCYn%T7 zHdMAtaT>QCVQlgP9-ij9RnyG!THGwsN3?Ee*Bf6WzD9p4=dW*IvApu$Sfk#G_;$ul zNIieu71P+GYFah3!*wJC` zB5tZYKzM0l%gbAQp6#Ak<%H&o`95@Qt|m+4$n4|Fv9$Nq&K1jS-F!QPwe1k z>?XNtiE4{q`-}IuLuZV5Pm`paNqKAk0Un6%(agN6tKZhrw8Z;>I1Z3#QWu0j2Etu= z1~Fm7UZ)U~h}?SUVU`v5{uF#{MIGHIZ`JXg@5t5O+`{cPbJF2wLGXQlhB5Bm8A0Ls z_A51s_Z;}gvwqw2pa+{;TG_NS`gG<#1qUVV2L2QKGJF=bbJv~I;+*)eOVPinN_@zJ znVq-8kt9o&LpzpXCuPq_I#bC9#$mCN+5dj7!E78A_UF?<2df z(o{-KS1X^ltJxO+WBWL_sq7lvZ~GHL0E|G&#u@xqOSs0~sc0tC+^`5*y0`ZwYqMwJ z;_8QyPs6PR_ORx7;y~f3@NsmFuPyE%2FVHBxA*cdYlJt}F<@9{fU$4{nrO{2vM)e_pdUsSwgMInmWN2zp{@#zvfKZWZ zqH{kwf6~!g8WWZ)^IPzH+Q+BAL`Rgc!HCCB8lCP`u?-^>j;n3_BrUuWN!4|h^;WNK z$y9meF4A`e=$Br(&2ybh?j@sIVw;6@Nq?~eVg6--v5GXlX&=ak!cNZe_;57r{0I0l z-7(W#JmFZ;#zNXpz`E$k*Y`FeqH3TWRedo3pfhUT=9m30w{IUHY4^juhfLa@RC(YN z){&lI;y0Z@jO`!!PQP;vt_>jjq=A}}h&A8R2@uPB1Ph_?kgWPSVs&vh)u5hI1154u zcU|JnJw8&n!UqM$aBbO}te=~;FaCsiHG?PJ7Cy{sZ7PST zO==@V;WsQu?=|;Ks8Mja7)e&kbSfv5bEWh#nEiuL`wHqmKz!@*9|N4(F=v4R#)~9^ zDhzR^#@H)j4?g?;`QJdOGSmghe+}3;L`L_S|A^)DISA5r%5bN+Q1M5;;SV1+DZjIV2jy>j2G z_iSnxK5#)L5Ru2@KLA9=K^EE7xAU*9N!SbQ&li+PedOz4g3QTbj*!7;==V`zf5Km_ z^|H4&eMlBL{c)sg&j_xT1GDvF-EI@eaDE)D5vYF7R7H-~q7M0G@V5UQar^os7$LO! z$~{iaYeFjGh!hvWz$ZCyhMU#CU{TlO@=*j`vgEI?yvj<-P5vdt;Q`f3tXN$r zTnm~QLEx`JHIBe&iG)dbdI+p1A=?1~4zKVGtGF+J4Wke=jF&WNe&av4>B_KI|0b#MjmGJz%9)l_cFGA*-x4U6 z8{{~}C}V`h`Go(xSKW3lGh#}aE6oC{hg}rvI>|c(u}za)mysgDKGja|?J*Hp%rjeV z9OPf1^i6DxDl>J~&iZJ-(m~D;mh9G>zUt+^Lp@~AGgk1GQelXzof|yU?x6)F9 zS41n2CX6iZ#0w74;OLp%ASfKg8m~&Ht?NB%&TH zPnL}BT_O-89~4KHtRH~2Zuo^J?8)Ih#|Su}B^F3;5YCqa9GlH2 z5$2i$dN@;7V4%xlWV<-vqbXqe8?*baFL|@i_$XTXg zCL;*zn+J&efH<$Q*Puc)Ogt;JMqFUgh3pH`W#Vn9qcz6AURVl3qscm#NTM>3*x+J` zs(ghKC0S~eaJ9hv+7>s?Z#4NeI++it%RZ3Ovfud*IWZ!~T)1UkXT;tYDQ#ZnD3)Dq zE^&aWjNk0l}HHxH-7@@A4`9*Mk zPzyWqxX^v{t;taEdQ;ldnS{s4fdlW(>JESf;Nv@U_1Y_KZ)mfZ#ct~c#7I#CI>Km&CtQ0}eBmy1j3`Fo+!E0D&_WhMP7*7SwH*xEmgO1QG z>uE~ukvs<1n$K9lKw#3DP^v7q*_}s>V%3%*V-AZd{Yl1E2>}`DN^J^D#xND79yW|% z3?l2v9T@4K0u^!NU&BpM$;{%~2?g)@hIl>;=tXo!QMs(GNAQsZv{VT;3CBCJvKXy9 zK+krcVXPMBd+UWSMwa<1`hHydj8c9aaDKD9<@`D|{mA4Gh}JZusEvRmymoqh9IVo^ zP-~^lAr4cBjSDI5q#z3jk5%rL!zRPX;yx35i`bN~h)(B?fsRzt(skkaGy;1+BiBT2 zi{toNy+w=;&@eLVYUf>J(jGJfM0NWHY^PQk2hK>SiBW4~Ro9OuOARodtRb98y5wc5 zP0Kj5sO_-~^TTU2rivs1qAgfx`louY=pL*vgev8>uKXI}$3^=I>$FDIEs zvd}2g@`P6^q=KxObv{Vu?LlCYM9w^6$YuQj5>E%NnR@7TeCr)2U=I-X+ zYt;$%KxXfr-rG8OS#FDtR?|AMj3}Ex2qUJ9tv4)((!@N_2>{Zi0Fg4mX zIG;aKkMxW(Sq^W(QU!R<9V4wi53kv;_P9ZYQzW$3ShPwo{3i&9>PD46)g)Dl_vvWW z^UNRb>>SHR(vOfrjyR`zj#sX$Nv(*(y!^7=(`e0T%wFYC-G}*W^HuZD)6_NyX!9os zZ+8@@x5c)~4L=^iliw`IkI~rzvDVv_il!d~T;rwIM^h((X%qohgm7-{9Oxof1tQQ( z3merdcvaMo+t%5CQ#{Vy&X{uBVkXjQJika8t8S>kIg0b@bG0cB@2%bXrfez1cai>n zn$R}fHIySvNM#EAwMCZ(VF>bfMS^RcRsb21+Qy0kAF4CE)ur^>ue}3nGsb$KzG0cB-Y9;O;nQ+$%S9mbq<$p21Ek#h>1+zc0 zSPyVwPuX*dp-W2&6i4-BqCH2?UJFfZpYRe1^nh!4By|kp#ote&USOINL?x|Ja=a4c zmWn=8EwjLN=3J*Eia`dTFUMN=AJlnYn-(bzK}7w}3P{5%&bdfrovj$tiMVfyR*SW1wQNqCM#6RTspE@8__oWGcW!w{9kTwIim#eF@ z3|_Tq;`h}*uu087LOhM19?Bu!(+G$QupoEk{oQV2im(6;OloZSyE}ZIRQ$9!v!DKs zxT0p8$ZlR&s5I3c_}N~ROje$B>NBa^J@tq162_061nK!Ng7V)BG8RYdBK~IF$1VtjPFzG&qF z%TBTM%cnc*_^c5=bO&9%?+M1<-kAsm8s}%X=k`NYmWbXp&FAkSMbhhEt}j(5{BgyE zk4gXhxFKDz|JpsZkqsJmiB|qbif|Zx#odISvJ3WQGVY`#FcX@TNDr)P72a#_Hdbg| zcw@I0ge(KgHb)K7Wx$w^)BHOh+%zP3zgo$Bm6;pm&Rs2%VtD+g3}+W+y0r$C851@o zxGd+rIRLTm-fxv?V!h(s;9%{G-P`X2h`NN)5m}HUosWN0Bp~NBVK)auB+{kt4LE@g zO(+bm6zx>@H$lgj`)PYQM@FUw#H12c;s|ISrepzf)r$*tTP?Rfn;3V# zJip|5*mZPe0QxG4W=8XqqMUw{Cuh;GU%jiV8JBFFDOaM1k8H|L*Yad12jbQ35Mu;o zaZ6KcQ%gLeIo1GnnC3lnzFVn;*DPUd(O9C~FMecbX;I*!=a5cYOZerwzW0KkTA{Q- zQYsZJP!!kkoTUJL`C2N^K9i&X#+R(xU%4AosAgikULL3BlS3j^IQ>=xDMmw;$K#wH zc*q&njPDmj!@H_V{5MLcf1U()m+`x8ZDrRJj|VlKePLDo4tH1bt~?9WRJ2 z7heXxDOq$%S8n2kU*FqD#gTR-Oqy2u>Z3V&+?us#W0u808$sq^x6^2y)aEhMEeR~w z)7xIxRixL??(Rptmh~^9yCrJ|yl1F+9G|MJ%Cb!5s4LsjRL63dCWcJR_+c~Jzcw#a z({_4UXPOy2yGU7hJR*P1YQVz&meBH(BYXfAD_?bW7LM4><7q{fyHVO9`x`bAhs8d# z%*aIONH;!~G4ZRqljBgq_G1!-*>OU;72lr~Ztl3jR(U2xYwp@HT^u=$bQLe)zq{o; zLig8(i1WGk9}=B29Dc(J@0&dt$HMne=w-H^Zl=^)_#xAW4Inqn6lcM=vQWr8r8THS zFte{>Ctvxs%O`QWX8FvG>p>M=b1C8ZyIT*DViy} z$c=*@gIzRxrWOJESIfds&F1FF`lZ#Yd<6UWPO%O_KdK8oAZ>WvzMRz}jL3`ETMcX6 ziGc4VT7LCBYboq+5ctyI`R`iJP0q~^4n9GR%#N^i->PeSek@P$K^?FG13E_-@(gk>4(PNwuegDFWuLqp#xw*cyS zsj$M*Ym0i%0Wt()cs%=H5*2v2ZM`j__bg6A$8?8+A^71BPW0hhX zOwRb=ccCcCjs;&^uDkUS;HQmm2-(>6%t7%S0@|dd66GVFpEkCrq|lL>O{|3R;hV{epfPYul0G%p+u@lLbX{U z0C8-ZWHDxP=W<9)ZuE=@gD=u{QSTH`U^4ZAB#;8)lk1*X?Zc6)4)B5V>9#!&+k2Nd zYs2ddMRMlj3>T=uh%u3K7a z^fX^$K278TtCG(h^f7%KEQPw|oSEm!9@q93SO#^5{>t?qV4d>7ur27D3fRH0r0J_kTOz$V*`Gv(_hD@pVEfUF!_a^vQXADxpSSby4r5TuaDP z64~gYNCx#l{!f!*1d_eZDZ^d02EnB2#$&T&C_ne!E7emU+-^`A%dG^+8{fX34%VMZ z?MXT0k417H@ff-sCp}F-UaD(K+IeI@`x=>bxo-6rmZgD8@vbIJuW1D5f;!pjo}BO9 z6ratu%n1=;V)y?8)M%P6B#xztUFk2YO9&DdBvDJ6{V0TmMn~LlD?Yd|Ev^HCc<1c2 zur|LX|LO_QRVji-g2nW4Wo*s6-7t`Hw2B$0U`~i@v~V{d0=0si18JgX2s`3nhXZtAHe$UW5{$jnid+ zcgqh5BW63#a@c;!J~r|pq~Gy})UzM&B{kb2nMeLd-}L4&)r~I9m-;E!E&R@pksFVLdfv;8fO@p#}qp~xV@d;4+lFR zf|7%T0=tqD+e`SSUD=HMCONBSkCTF1gjUsm@Q_@k+hOWx6}rvp(GUwQyByQ3;O=5G zWPsb9Ps>6qp$)=IOHRiLVxYg07Y&J~FNKb#{}<>3dCS-?{)B=&eITJj8mYyI^I!kk z{2SY}A!A$I%=;U6wyXh2pms`Pj|CzYPD&krd=M!^#y$u<$^P%d_8iHHhPilg<@P?c zHO`iJC7!RteZscS(r(XIAVJxEluZ#`ds0T1M13e?cBq)PGuOZ`E=sHL2Y~f$aIeRxpQUFFEf7lX*!eumf|I&RYvlws3CH>*|bTZK+kdOg&{eL&O6} zk+_{+jiVL4yBI-i#`H1YC(%cD0j`8DKBxg+m99o~16K&3(QjF?#e@X+*jWAf2I$)f zJ|pwYtmn<{k;&^HU0W8h@8+?|QvL!de_yl|t4{Q~TfWw?UMXcQTnvxW^klcIsXpP* zAJEg~g+d;chfl~DTboxNgtS!=Y0~g4Sm=#Bp*6+Md^}HDTKA%g=HJ*Ii`Vlv$Ayi( z77rSpJdRJ8rY|YsWGttpDWa33c|ARe(u&-@J(Tmg!le*|FsR5@A+Pe1rW{@3KCD~b zXWv(+Vc@f-?LN<4P|ZrIPlDYE1Xl3c?~MpdZ|QJoQxhD65pb!-sl1t1M1z{V9IHVQ zd59KbNCxZIOxD0~(rZ4;B^`FU8~N-f<=a8h-@8au5G1XcfegvAg3Y8lAf}QQka~zl z8tK^BkcsVbl|W?&6V#n)xR16L4X7bV-i=a%fWpZYFm@`6ZQIWT4*ZI_Wh4WaSPMMC zuxocl;l3Mq)Wzdg@!OMH77lW+At)sFCS_CohLNcqJ!30AB2hBxko53Ku*y! zfWcTRj0;Zm4g(Xbx098<*?CuQ?zl&#Qd5Lk8TOJ5#&h0R%w5KpJ5Hsb7&EzaY_aK! zcsd*99F=rM-$zO&29b07EwBqpzv%;)y1ya=${fv^wdSO`e%We@dh=Xt_~v+&fEN71 zGqb#{?u-Mk5T6AcRS=+?*D1|SVsRt+%s4|;b=GI#eySQ8WLNz3TW~;XJDzo+hmM-N zAbS3S%$^ISDKHHX@|qTrOWs#*X_t&XBPcQKOSMpuk_P5I2=!#u8*gsDmmWy~Tc4Dk zWk9k2V2>>K;dEP1PkVPkO4%BnW@g!EBmz2846T~| zp$VT&BYwZ6^cUSpZhc@bz`sV;~88 zg(u`1>P}k(Y74oY7O3*XmSBvKCSANm(=`LoM8fpg5jatFfMhR9WKDrTy+#=a7O_ML zAmxUJO7qW>HIroOvhdak)|tUi=}XGyIvwtDH8pF=^hui<2|+ zZi?SyG4pA2TuHdJQJ0T4Q;Cj&{?Wv;99edA(k6L%je*ntO zu{fuF)i>1!{zt0+05LVWT;0nF%sj2a3c;Cb8c-lIL_R^!Q-j9}Ye$dkA=i=xVE-jm zZu`Z@g~MO7<*j~5JDNFtSZJaSNQpf!ASAD`{{_2-B;d7f;R9+;pK8RBNS+}}QiVvo z0AIL`1lchzu`#UZ_1oQLQoi3jzG+HsLEbvGc-&1910(up>NLG|Fro}?CRp%90F zx~QuW&H`21i!F7yrmt0hx*BfwqEGbN;$D05-+@Q+d*d%IZFdM;Gn?R*GM~ASz4_@6 z6oz83n=3(oh6vAG$~61);(F>N=EQ*m>n7O>Il^9#bB&}ts1}r19wTb6CX;rh+ z3g6;0qN2YGy}9)q>Gr`LDsHl!f~#3r8`pr%;zm_p2w}4eizd8)P?ZrG?NGYcoZy^5 zxutshOlDL2Q8lLIqRDUm;}{JU$-vZ1mE;_aq9(GW#@-m}aA{;1et?s38*aX%8A!|C zp>c|_)a8!flb`<}uf=Ja_~f9IHyvv-j-3rQ!D(;=*_&VZ0ky-!UAeVpssH16oXz=t z?pOe_LG}en+l5S9t1VE(dmqQ+>RJsy!VpJ3)bgtSh!E5+vU@S?zJ}n1-eH505?JA+ ze``fFTLwP0LI?4;#oD|cyoMf{Ag~0kO$P{EqNJ=TI%yKNtqJ7pcgNC+UwNPoh`Os4B#A?Hm z%?*Q=q=n&>Bb-NitZ{m^%jFM4a&*R2aICG$14%g?#%>c|(*SP2xU z`RR1+)o7j?zSh}N(c?@y`#-5G3*3U+WqL`l-ok9LL|Bssg56gmJ=*=#DaC((87h5g-Q1A2BIfvN0Kb7?f^(eJx$ny&J*bzKU8py} zrDxF|J1|1bxJN&_(@J=PLjFgW*TXI?Y;SIa=BV6^UB~7oqk4}i$YK~jL2P7C8mL2* z7J*k+XeZ3N=+sqgldx70=}O=i(;j)ujBvbM<8}6;^L>=-peuQ|mSl!HF8C)o;|@Ac zG78i^=Z{v#=gtQ-^aa2K=3R6>+i`6WQ}i zY;Eu4RZ_P-3-FC7(Zse1KcCY1`TbN-1bGV)$(Y=$?J^*R=>*L2(Re~mOQIs6 zO>z4HO+P{A4}=ivvfL74L?nxCJhY>7AZVr(-ke{KJE7Ifv~4*2k>Z%96Lv~FjJm2k?=Z4})J z;CAIgBcPE><`6p*VKgxZuWr^X_2usI9MmP27qji>j{N32Z3bmsuA2gx?UBspJ`-Dx z_HGV)oe7;i=6zYC<-HM&J8J#;*=)P>gXF-y4OO zbFj(u?a$Zht@qhNi#ejY^oOF5*x_oQz;UcUPCx4If!d>OS+*_4;|Ypvca-IAs}Sb>#^cF}5&ytd=e_=kLx3e+J@Q8+{ZM&UBZ0YM{{+H-Ot|{!T1vU8uo;_Jv3c-XN3-i|H&ia*9hQT}bX!bfK#}q?l z-0oL-!3u(8imJAK0o~t!3k~5@9{rugyv*8C&2{AnDO_U_Keq|_u5kOKsu_acE3m(9 z-ITkJ9!dnBN8HsW3{+qwx!FTuF#r;nV4PKxhB@c6yXx~ow890J0*#aAFHlQ#pfOZz zK_Jkh)+t;y0}fOF2vL~ku@IbO*?LQAEYI+sZz%S~ot5MC*1;1O$j7ndM>>bTpYC)s$)G$S?7!ry|nGghnx_%)?N%hDZX`GesoKe4qzI*bHt4W4tbn>tTO_TXL7S`8f==#NsQsu_}XCJ8r)5Bek2JU8{p8iN=ffrL!b`n{4kJEqD~ zRzg&~=bn+6iXZl&hL6Rh`G=Sztjl0=Vp6#ZhpQLagR*K@a|32}McQYs5c-Ml%&wv{ zyDE0BK9!T)P#9}E;6@7t0>7I44r!y@KbgOSVspONi7us2G^Z&u9IlptC?~M-6HQC2ajCG3l(FJOX*hBg@@2RT{R%m}HhOTB#D}j?;vO zb&km|7O#jh<=7eP`b^&-m$cx%H-_ayvQMP_A6E!7nj-GnjF@DDNiP)z=rR2-;rZ^~ z!rA3R9SjA!JBijF+5+{`{C)3e8jC~%{{hfvtf)CAO2@Y}hUBhd$;1#6rOWINu-u6i zT~RE47C$Duwvytw&$NluxWC}Oy>!$pmmyr?NyV$cⓈm2eggOv;cVJlOCKA?C{u= zSsfy~TP)8I4}z}-v?VL4duXmpT85IKcW~R|G~3m-d5ypps6D+4rY*B?UwqPL1?M*n zgAb92DT+u~y#UZ&S6j{B-@k4C!C&WUD5+X!`-ZiH!7_{+L7MFh19ODa+f*}PTXD*B zb7nHY(*CMy1OCYfe~nQ_mvnkzP}^N0R(^(jeF*wi&`z+0L6P8qWrz@Z>GXNg-H}+$ zoO(};?+#sFlA@3B9=@&fk9o=23Xy%hV=;ThgSe;k3pSG;>jHaqcF_6!0#w;iXFQZ` ze+C+T0mA%(E59ms5$K3;CbT6x`LF^#bGBU+q^$%CixBh8`os`L)j9x3M2{WPJ zngkr~ACN^q7}yuz5y;i-R)V-hnm0i;E}7vQ7h(EEvVZQ$k4xN${KKYOD@W|{jJ)%Y zJdQ~x$d8Re_b%i_(7Zgr-{u#y!3~f08pho-sQ&@f6u;#&HrN_wXt!ehofx`Rq)MA@ zR&C4iYm&YAlPvQ2N?#ARW#~NpYfUeco1Y#ZN8pkuBJ8Vm@JKsuwtaC;EKeRmh$Irh zt5%sySt)=n-wEPQ40>IjF7yLE;S5Kj4{`{LT#NL}7 z*RczAALo-llJa*MA?AU-{0}D%)mX%nD%33feQom6aLjJZruyZ^W?&IG=N7?L#CW{x z=*1**Fwa*FI!BfGLe&hbD>A6Fk`2M`ZEEbam%Ebsj#8E~cQrhAn}0b6+K_8@U5 zRp;mZLnV=Av#~kHmKEP6NkNA}L#WgIh{+lHA<4^9)u|=T+dhd;Y+JNA&uCMou-V#c zMT;D|kPUQx7M(5KZBgX(E9hIBq-rm~-%SrM30sV^;v0-?7&(1^-7G5dN((g2*0Ejr z7=Hm;_h)Keg&HR<8W@MLh)I7yZ7%jbLE6-3e&A7a@ms|5YRDiKT;8(zcrW+xaBSvU*{V2j#e%XLK?oU}?E;oaOo}1Dk z!AC+t^!zaGwyZ}a7OnY_3nuD9D|31=Y)_|vr&+BZc_vYlj5YM?&HTM|AZ0s1jkC3& zPwLWSYok0)p_YJa0kaNCqEE7-thY&Por9kDz77rcd9-+lI8?8Lt9H&lI0uphIpM=> zMidpaW&V_JjbP>9G$Z%9wNp{b`>+ec;p`U^5R**zQr_Jx5C8{|b+bo1EM8uyJt>tS zu9X>23gHl{U_RfeZw_BxXD7idi02~x`MuOwhxn?=?DA+sf@9Jz0(=DZhW0Ub$vBx5 zMP*?oUQcmBP3DhyDvBjx?dZ%r-{*|ussJweE{Ynl6nSR5Wx?WNx)pAzGQ`0Pa0^Y4 z2z}PjbINxv(UG*YsjZhnpS?7=b#+yeJ(wRVTNeuyI`_D#S?X0~E)1{+m_XY=v0hy; z3nsJ}P}6#A5rmTWT+B&VR5;PaFR$xIMPYpl+X#{cpynZP9Y^yM63*!igA?l!Z2Jhw zB487Sv)$dCt({iz)umyXo{CfZ%U@E40Mh2Zc!ic|2T*UBKfgMQ{|H?O9WB3bj+=Tv zY+b!H(>E)cPGw6zus#sFnSEXA6;qL>c*0d1&}dp*_Grve0Nrt6<02fopFzeBfaB)S zxi%phgvkwdMG0{l>ZU2h1ZHoC`WqR9ne!dCjJI2MyDweI5EcM1` zVNN3S8~Ty42osBUf^?kV3`|}6Lf5cx&<1Kqd$jD;p`_rn2wuD=ISQg})g7ufwxzdT z6&xV*NP{SFd{bhkj-F0V0ZYD*h1BOa0Vi~+geN)fBNbKAvZ{&Fq(Y40nLI@-T@k9F z@GVu&A2KDZ$S}9bE^NwWw!iC!MG)?rD;JM@phuhnfF7?HkU3_X;9FtP~q@ls4 z1G67Eleg0%W$X=mK zEb;1i${Y4BEwH-6Ru84v*mFE;-S>1Zslmg`LPBnaf0@>S(y5uvC5k-<9ih)!U%v2* zV*pZCND-Dxu4`^LHVg{xILe8!rN*{NN4h!Aoj~qSYJu>$JkfpJFtbkLA}WC;I1tx> zVMwRyuo&2_pkYz#_UIDI8A#abQgRSkDVwx}^x9vNcji^+Xc9kl5UsLhu@fs94DoCn zm*L{zKQV}uqRGdUN4Lx5B!SI@UEw9Ed{`gW)(5Zi9S!jV@@K8<}{a<1P%Q?ifxl6#RWs_)DqDs}1U z&VOI!@r3WXZ8*f86pk4E%t;92y#^6~wGrZd7MvjgqU#sJCU?*by51{@Au?C#9z_vMl1zNhM ztq>#0<_Ya$)H2NkEYG+fwZk1)(cRQ`VLx4ZKgTzFD@}-7rV&yKskR0LepD{CG_^EJ z>+5?JXuDA%&eB^6$&UCOb#Z?WY>u^t@w0$BlfwAB@{Q~7?-r?FM#chTw{qSQri9aw zTI%23%ohB1zd0ID-Aq@~!hVeg;W4)J!RA=JXz*f?s0ucHrM4-_%-EqP9V>-YYi5P? zx2iDzBGj^Z!sz%j7tyUqZBOkGUkLd&OcNztNr#Pd;T|eyoGIl|Lm5w85o_gckLGXX ze*{kmVl;|s)MD)MzcGPsDO-an!l|RFiB+*&Dun=~ObD9s)a$jQb)P>&@iF`C_{<{Y zoniS6?iEO6=T5uS5xNF;h$N65gs^{X+S_^T>fGp5_hF_PPJHsth6IN8ij=GWRe?7u z`bYrMO$56HU-J!E{|8tMBswG4i5SGgiy@tY6v;JQdRZj?bcdv`k-dLp-dDd?>0H&^ zFgdbg$|7^j^D-CBLXEt^*RHOD-$BIP`GUY_I|NaBXhY=zz2dCgnv2|~QC1W5+gj)% zn0TFQL<(&a=8Us6pUD;W^$D7!)(#c1jqQGodp-)1gL@JUj+o_Z$8*ppxUALZie6?M zllnfgprlJQw?}N=$ga;->*GiIqaIrlOs*T~nQz1pyF!!NBG-k0T7p{E=6+|cUuu$P z`S6FQ2Mq9-VljX{Uwgrkr7T;Mw}MO)#zN?Glr@ehTjR%;v;80 zFV0ViJHD=3ckjE22+AAQB6rr2OH`(`nNfeB2(T)b#zp;QqoyRaJNtl3QR$-C9coTy zcLg(hZ~FWn;46q}HuNZNh6i|<8ZpbjU>Aj#gZ9t+nDxIbEc#!;NLi4;tAG9P|HQav z6=;Y*Qj}!wk0e43?zl&o;XKzVq#k!`{4*rMfcHte{jD;oc6$J;Hh8ycD!>G8uy??Y zAmDe#%$y?ad9>Vl*?x^2U1z9lb8kz7F*DSH3(1E8M!B3UQfv zpx!^T=NHyAn?Lg8xVqfA35O@(-}}3sGgAERk~jHZ0D(mFO&~%-TuqEjcE>i@ zYXs9%eGfKH6LZ2VQKAmRSQM95S~g2?GrJI+d)ll7gJvr3wM5W>U_8XrVS2JGVhNIo zO_r0A^(Ll1>L6C+*}jOq{FlZk_faH}^dy;bAzoGR~m z{Ha#rZQ^*US^`WzGTpK4*H$)qL?P@(mPCQ546FJ8FQw&T^# zJlbXOS8w4itK>y{Ds{+T;C}f?@XL zZ9f2MSClm9VXTD6C(w@gj=L|AZVU^un}gvWHOfvPc|pzsU%=0Q`c8#UjF3f1XLat@ zD!4DiNGxx^TFYA8(ewJvRW`#63l_7k)K#9`?HL)MKP9}NBD3Gs8vi|RFuIXd)O2?6(A$4+Y}LW-;Ky=rks?4xaSA&fN+(DMCWlH)3r-l}vP)ah_6X3-eM{qXQa@(4 zI|kgcc^w5YkH%1P$W)H+gliGPlC_|9mvsL`akhtb>CIsVmTMXp;PMmd6_uPOo#G)` zqc+Jz%5HOoZ6wR`)BO=eVi|-#+`%r)1Xv}wY(SmJ-0ys74uJ|lF9ngA=xd<226h6p zGkB)@6y>JqNBM`=FsEXbIySNPpcAA&rv?{`qK5LluY(_cD**`F^m$q~iyG8R=cDew z=K79?V<&41H87FJz}xR<`Te&W?;T>y@Z2^{cWrbO@xA%#@|ET6G6$9_2qM8~?~FoJ z>P=q zMftfC81Wb4i4jl54$C(ILx=?fjNk2M?MxqRxpwVck-yR0OEtOr4`Z zH8tYvA8Pz0{AR@^WSrM_Unlq=xmcaA+I)+ByEl8Kb;mM_);GF8|X7zfv60!fdUb^gECEVbANI4k%@=94q6;n zP%o(UZxKgXMI$cj)>|a0!27vy_|Aj%l%2gj1-2%*+!}v|^@7pi5e?jCx<8#huHZkm zHZnawc6OC&Q=kpNV$FVV0aE0hEl~^%-+!enj6Uu`&Z;`XoiU!s>=yS?3+vN>&mME&Lcp2nMFoq`Mx1du35G~@7<&nn5k z*escEIKEH?kCNUP<`q`z+S;OQD}9zN!J=ZL#utL3Dw7zi7%sVR>PTR5UcK!J_NFaJ zPlKdepr%b97<7)cB$|g5k=%VioYJOkZS~0l@MN#;K1`ZH2Q#_9aFVSFtC|p?Q24G{2x(rDC}Z ztDi^(;ekEzgT41${5SPaL4QvWMMjt7bCUjiH9U&phq8=qw)hW#f-Zd^DiY@A!8Q@N z%VI2%&g5+ouz>xfrG5u>mAIV?aIkNUEAsj+y^Ly)+f{LB0Qd3dQy2M@&hbr|*T=wQ zTf?F`10Fjh{6U|o5P?qDGBP^+0M5XX-ezaPpIRM6OvY*v<3;aD8T_-+u8=*$C=zwMWt#C8B28!z`T3(?D+OKI{brv=K4IMCBHFa&15J;7$ckGs|u z>jrBfe|zBGZ>)`M!$KuFd_IjRF9h&^fI5TkCp?MLxZ7az^8|!#hZ82jZn@LV@h-|dnJcamH9YK2zVUVU+J!Epf%|J3>S)XI#n}N zxO*?1)UV{%Nys1={k_$DdS8IT%VTWc;sx6{&}BXuRlk4YtGW6MF}jEjh9n0P8t0UE zxwe-})ha%0!H|{`4-jgHJbB>r3?D7)z&1)AeOBh69VnGn@g)MpFDQZP?|P;Hu`>*5 z;$NHcikE)aWNF2I&BTEo$Dkm~BoE^mU({WbaH2_5#fH11b(~%$m>@e!g9I7+MqN?{ zW7~(I*5V)ep`zxSieehu@nn4mHEhUeUY26^7oy;qgCPzeLCwsJA!q8UPvfH{KWyV5 zSzSV>3Jplh*e5iW%oS};6egb%l%$VU?DTT;5=?0x-uj7cZrZPvI9&Kh9=HI12oKwv zqP=U1LCKP+v!h}bk9>Q-T8W|-ou+2iB-6(poxgZyE*x#=eZ3ztg5?PLN@iCQw)kYr zsccD8JC?Uw{Tt={g(uO}Vje^GxR=IvQHYKgzJmrC+@ zp2Z{;{t+4t@UJQ6(MnwJ&Hfw)Ytv4L3=bGPZeeyA_#|T%huP`m8iY2rK(~0!a8n_Z ziqez{z=P~EmlOr$n&x{J9%Z_IH&3r%zYSg{b>u16@0S3u&(he=TuvJehQH8CdF{?j zj(^QRekPZ5stEW#B`n`y>*k?O-VRFei%Uj;xtW>O>@T-KYw_F(0!}l6ipuqDdHxT6 zL4m$cdwVj&Zyp0XbQw4wsh|s8S3cECO?^S_Sn5&R$3K|ZSQxVG&&$aJoPVCxb3A6K z>6(LTF-s%aT-uoBXu{kk()j)%&)q$!0pDl3{?|7@Zf~-AI|ZkfFdsjEcV3)hr6vBI z4x+FL+E5{xW?wEsnPusmbsol%pHTkTP!il}zE3Pk^L*U;blZ>Co2lDfURrrpm+xgR z^*(Aw9N->C4;;`1xg(Bfo;eX-Hw9f-WH3EJ6v%Djf+U6r);Ob3sERNY4uB6zm#UCz zo|&dv=-PaCRw!e)jFPHYu^Bl$l21}-0<^c*lU_?`mk~A0I4=-kxk2fXTwM2aL8vi` z3x`PNBcM^kf3!wN(!05B;aOyuM;MjB4Esh-I&O7>-4ayLxKnB0;^R59*bY5g9wJTNXH)mzV&GO|WgDkO==jzKuwKTs;Zlj2J!)$OB%OzhGsWG4VO1fNc|Sah8k!HX2+tJA3!q2B4x-oy5j zd3cu_{W4b}P9UI(&4r};b5 zjua|ql@fs@=GKzMI4hI(lRIo zC>E^c77w`uNYju=-Po<<6zCml@yRMhULu(LDU*)`J!8>3kjFumI?#{#%Ty)Sn2 zx89Z6i1#@)*=yG!G|7{GHz`sFa7GXFuQxKf%#5cPQlle3GZ3Ku9M^UY*|uO4oN23FO`*l!CEwj4lTQ{QBpG(Y)&m$Zwi< zoUc^a6>vrlJNNaj-tF(FYZ-LeZM=q+T7NZ3EfMRqj*a!B9S6>(+|MkWeVc-N4t*}t zO-?OIqQ&HKnATNd4%66y!5><%@vMurls7r#XPRy0x7#eHxAUch%7sL*w%1JeQ`pkM z5rWz{jISw03S^Mwn**u$HNtvj8H92nD9Y=Srw2TaqPZPXdq%vL$z@-(#=F`xkZ^ht z>s@8Om1n0V!r9xbLTOrQ04L^i)Ye|BY^@W?@_;(A?LZ!Rc^C|F>&-xA+VM=eEJgyT z&So4bKAaGJ%9_>G?e@D7`c^OR70hw5S8upSP~hZa@#FEJ3t|+FeB8!%Foc!sBXUU| zpdLP$^{tx*$N+S%eJ;`~RB(e50~{#Bkb{Ef{j7j8Ke}sMPnalQoAaO!lf-&x*L*J( z{5V^?0fz`Mc5##VaNmPfDK8XiULV(Y>`Ul=!*b*JA0H|F7z6(R0j)g-{cUcFOv)gX zY;wne=ufwAp*5L#rIyn5{Q(!7MiyN#G>&D^u&;z_tcP^9ST{Bx$*peZJV7-G9 z9ZCNHW%>HIwOjG_nC9-sQBX5=AK9g0&`3UHKbSw2R=t&cQ{ZQ~!80NWj~{nGB%hNm z{{X~R)|P+aEBJ7>@6Fo7x0CY;V>su~0(y$ubqrWMTX$I-m3HTHZC)q{Tl?%J8S1KYgZX8>@C9OcKSKW8)|AS> z=yv}AyqNm>E`87StnYScm6eXW!8%M@Hi;&ycZ8aBFP0cF#0Gy}zm;>=x1#$})O=}n zGZZ)_l@V>EJ3l)UwYZTa*E8y z*P6`IV3Jv;y!$*?2%j&NBYooB3;=T2&Tu^_8K?oak)w_n;*lc}%NFcIcMNAQhbJt| z>IN6mv*%!C*%QpL+k%1_S8tUo^5I9I!5+OUP2+;v(Pc?wy0A=`l5_Oi_=7+b+C_{UR_>k=WQiG+Gh~6DPtvn(Bj_<*2AikA z_bGH@4KgOhW7tpz{iDTgZqm-{9B4Ak#{dfGEM$&*Xr_h3#Uh4Q9T*;lvhA#5xwmL% zg=C5NWO0y1Zb1^o8loswQGfuz0)Qj1)a>tXF0CMtytbuQZ;Ie0?M^T@80G-&X zGb)#02?`HW=}>9Y-Q4N$%YA4qE?5%q2?U!t;BEkCj8uA#sb{354|yp?o@IhODPqpu z000`kI#2~9{?h)~ecxmnV1#YP<1v#x`vu42MyYLmb!X*RUyB)w0%kCYPTt@Gag*wE z^rh1E5vp1nfoXSYyV(NWMdiBz{98{rJ+n=k^6@o`dq}kBdq+aj-I-NZGucA*Vt)WL z-heL-0QIU`Zk}}OcZl9yU9-s28E$0U**%5;01m(oDf)@MT|RTCM+4q%{mRb8Q+K{O z$NA!=wfjfeA^TB`+-x3im7SZh&fN2i`p^Y-((NBsT}`87cCeUL_qG)Y$-?Iu&wOW! zmhQ^h{@mN%Tg7n+AeiM)%5ZWr54fl-t@RkMuVuTxN$uotZQ)o#c`7=Ba!V7(Ur)k~ zLr!by?Bo~McFS)tl%x(6O^@MzIbUi3y~Y3o7^W&J0u@4nNgxbzc{Gzmv%w@UxGaiP zm13jspfzt7gpx!twhn8)kBzr4Z%skIP~|Z zH62>ZNrpLZt`-!QMTrZ46CQwno|!bU>DEzd65q#b65dRqB$z1P>N)~{FUWdS(nlPd ze8gAU!Iy9c2h@Ae1M|gF()BpCT|F;hhImogfLY@x+!8Z`>x_?MR`LKO@C8R4@y`;; z42vXeGOVW{k7Ga;KeVSh<5>NIU$d+NU$y7tEKW8Le)MYd>M>b^r9lkW21OfZa;g_U zG5o*D=v*~BH`JR>TbP>h5J=F5`IUW0{C`@9SJtfbTV%MsX#{U7#JeLdcOIMpKpH^h zdRBgtx{_D{t4jp8d)$)(6;Qj5(a*L&`u%GDayr&_k*P_k*|hRlT-gyLAdcVw!~^%R z4^Q*c27n`)&VTJ@yf?CaoWtddU887h=YD;AR}+7v-^;07NHvKgh|0xdSo#gz4CcEl zyNyTtW;i3VL#O#gq`5MD!Slj}{{TIGx#smdvkmOy3NUle=UvzooSJ8unYk!M$GL9w zES5J2Nl@`HBydJWQt5?;pk;vz$73ZF*Y@XFx+WOk_ z&HFvXa`{eUeT|*0I)mtasqjG^t+aOVuGphcin%8Mao(A4X>V+0@*$2tHO!B(K-|Zv zKBwM*BA-{Yx71+M<(qBH>RL1^aKLrv7^73aT|UBFqi=C@vmd&*P43wsa69$QTR7mH zW};(28CtFG-6+ZnCg81tFnw@q&Sekw(5oiGpvD^=Imthg*KMfZ+G;jtOL?QXhmam7 z+z+ox;BL|9*obkzXnuc(_`f`3@vgih)uWFVv`p#rXoj7C72%p`it&eTFnZt&4C6K1 zU&ncIYqL+gOIeF62_7#n6$d0^BdG6OMVp6#dCwR%+Uc{IwAddxV7pJ@#cz+Mtr??> zEUhOw(wC|(;O)UY@J>w~3=T36u6Oak^=~3x7*EjY8TgwS7W)8^F zI|k@+kVj+qQReDPt?cq)I%7efFdyD5x#&mtar~>zJ&~tOf;~!YK}^1MsHn^4w$3~4 z&NJ`-0N1KIzMXA+u^WgIMuq&y%MZH4xT~7PI+XTmG`py+?gWa(rH^{D_aEo_$d=|?qO91KU%WNMxdw+-HT-}sM!ahA~W0bWr81Q?=CoA>A!2Id( zUinacqF>yI##ocb9qFDTx;`b+E%p0&UKfDOgta6SIrtIV6-% zU)+hAlZ=LjTq*oN)t|uAd>HSd_|E%Gxz1TxmAYiBVZSkk`Vmxhi=iUuej|l&vd8vo zfIA#xA6ybY;5BE(GrfiOlj3-namY6ycPsKpKM{<7yG;nA;>|SaI{oq@;R_4cK0oZf87a0DkYlOC6Ej+MzP6yMs>0LA>(B;HO zX%=%%2ACUWFB*`lWH5e>H441O=S2_M1K)$C8q_g;y!J|pX15tpHhEJ)LmZhp{1HS&jsm8 zqiC{f*O-c1gxndp^5Px;03N@UbN1J3d8%q2HN9W-Xb;)+*pEWPfJgc6Yg@-xbLyIf zr-d~3*(KH<>6iXlLOL(E89$Xa(%#!q)Z&6DbEIghp%eak%h5-etck6} zx)z5m-0Qzmy=9U`BbH1pmGf-qT`umBl3t=&%L?kAdg7?~tu%ze#b>8`(RYo?w^9x=KHMF$df zT;%XQ=mSVgZ478fnAWk7A)SBM+mspMbHHgN9G^K1JfjM||bkoOJ2MP>L^BdippXIcE6ahV~d11To zt*GO=Zz*kBG$n@iahxxF4_c#X7Fb|b)|Vlk@>r4?0>yw`mjItZ>p&eXihQ7AwRCGK zY;1&6-Ai>TV$CF&2PEeJ4uZ1TZ=;G4V{aU?G^(w=un~K=zZKHPm>f_87frTpNi`Nm zHz^s3Sh2ta0Tz2og+1Az_TT$IM4=c%Tcz0dh#iB04%NqXtG9RtF%8 zitf%E+c~Xn6MQovM_iGRcsz=H5XEh86}%`CD3l^1juk+_0)QfeQM0(exv_?Idz(|ZTwh&ju}!I1t(DtneYliKvy+dQaCpI|YC46k zm18aS{upwp7sm8TzRY1oaiciIQ>bjNA{xGI*NrCI4Q%^j3JQq40@C(Ky0 zw^B(Y_N!6}3~VECjzJ2IZ|_a*(&v50mLuPiNcl$t0D<^W1jf?e z?SE_XBl}LzFV5OG?ap@Rt~1UkxVeJPA2#M_;g2Cp$iYTQz!^T~t0tEkYf@^TXt-%! z5f7AP{nCJQkiMtZpMR%W>X0lK_OV<>`zUd{zGJfJ7yI&vr=L)I zRUIz+^7Zcp)|~ch4DB2&(gyR8baCmL0FLKQ4XKO&0JU6Vo{h!GD7%ldl`QOv!+uN^P*C*mj_^ov{h|Y-b z5Iad3JdxACO6Dj^ghRr>0NkViRzpHbGl*4I+EwTZsbC_qj|d)Hs#jYb_p!e1f0$dUH$+Ca%1j(^WJ)r?A1 zlj@H*FXn}LM%pu??ZsDH>qotNCAo;*BJXHJg5Y|Q*A)htrdnwhg4V_(6dQ{K-dF-o zPBM5N)hV>K7iREV#4bu~Gi)2m=R0%P8Lue!O1iG829~z%aI$Q;onTf(EESukanNUs z`jJ(2C6HRm(8eT?At;5m?jxYjYS(-fHJ>)tQ?~?q&<6`}WRe7uTX%v+T(oXMDt$65 zo}J862UCVqk@c>(Rk*eLakBFV+O~O{FnL_#Iq6)z^du93Kom{Lwk;ZDv*A&{yBAOa z?~-tT-K|SG{ImcJ}^BAk=(6a5HG~u}t%r&jm%%f>hvIEZL%1g{ zOsINg(Bc08@1gTncC~bkCx^U3;}Kjh*>3UtC!y!p1;6i_o5n3JoqwfxmLLqMu}(11SyObR|Nv27p3S4gXfnZDTx>{X5=U%>PDRaH6fU5AZej{g9|_FB!k-Ypzt zj(0;K820P(v6`3w)vtoS|%w2dDB0K|7H4#Y9Qt^7x)>To|g z%kZv^Cy6!VHP%`P+|6?5_=!2k;&b}eZR%*2hgaaOE3Z8uChM;PZHmnZ90 zY;A4zO;s)8jJA)W;3|L5X@7-%$vDsAD>m+Em5C#7><5oM(xnrK%ui!lKnM_YC5FATx?iN@|05iKB z11zj?Ju0fiRb!0&(qKED<(r;=0tewh6In-|)zN9o8p^0$Rom{ac{Pz~9uES#Ju1#7 zxmon*%;qOeI6FbptoM{(MzSw@Ph zoC10ST6@wMnn_$FXr-B(paZ#}1hl!jmip=$Y>YPXZSrR_1LtIOg&d4=*RE;WgnEpk z-E`@oi22H9X;889$KDD(PXqI%)9x^7@SDZ#^?sqYffLAy$wm+*Du_---Z->=wV;A8+y#?S5C2=VRvCoa5=5 znVA#~I{fq!=#t+h$dbN+s!rIzyE8<=gRo;03p`BAd~ z&yG$9e0x)GujA9KXS|!%itCNA(0)Q+=U72|kTlS?#3n`j?>hp(Zo zqgA)QxR%t}-X*d}F6qNWAI(qhjP&}~HR3s%382`rv2eo?p*=Cz9Xj`}tQ)mdabx1$ z7s^aRC7rVD0T<-J>^|*fX_7297Ru79yhs%D-FW_$YRXw;(q%HkA~G{=4nZe?dlTO^ zk@jnsp5`c;H3>6hvX<-f^cep4t#x7atvH-mwatcvo7%^rTx&2{%VQHmJB!IYw0NT| z6yrH;bRXxYYW>W!MQJRS@Okqh5|M8Uy}Jyanf0vgHg$_dx02#jQ5;Gg+lAwTdFj%% zcVuL9^shE+mQ6F*gt?-c>P2TP^I5|!%pOF{fux8qeT+vVBZG>9${j{4tH!*$ifCQI zw~Zp$VqV~!^ZtH;G~Hs$R%?~Bn8+T*C?4E_|CT7|?KwVk9|e6qnfb0x@O zwj2&JJ?csp?@wEuM$YlBE)lJF;xv3Dn}$AN-yNyfw$}HS&jr*m%?o|#-I;+YocG7IH4NWoj80R|+BfXZ-Pq?D?LZj1`9WmSrT`0opmeW0xsqW7 zh84`9^gKLPS11B!BU)S^R1cG>6dpGwh_;DWhIo%NN62{ z6~Q2KI_IzBL|@uNRJjvUL4;F=@|r7`&BBq$J^)M{)Z8 zN79p2zim3f?v~Ex?4bk7woUGGalo%E_K5H7TJGZ7b-cQR$YRDgoCS~((S|t{Q&hBu z?#^3lh}KA*cCxVQD`SRCfz)T3#6DJRW%*P}m%vqh_&25;28U z+5zW*T&?V7K_DJ0vD9p4{??l0-N?{71s3c$RvpE2nv4Vn`AqHh%PI`!hO%Nc*RLyqX&NIwJ5;Z#)Q0y-XRv+<-6-)I&()C5Q^7;Yn- z(K!DA_D|>Ztosvy7Yq8>hWvC#8*&>T`B)b*E_4>hr06e_egBM~|5h zo&X)ae=l0qxsoplcxf#nZP!^USx+*~!{>4ApzR*#+O@5hMAS7Xwb*a2WovY3;d!Ae z41T0#RAdi&f^92Kyt68g+A z63G(?rC*hUV}ZxNdh+XiKJxfpTxyoO>Z{T1b|v zmzE57JRI(~mOw|!I4)IJuOs!K3U^yXt8Vc;E=V)12W%5UfNdlD#fT?&Op%IYN@Q~G zK4v*TT48m6GDzf}NLjp_b30|kE6{#;>C*&NyL8DE0e03Cz#V&6P2uZFVzdcyD4tA` zTp(Y=70+AB(Olcaw$jLDY;HmFp!H*2t&D9PB%*F$G8Z6bfG@$OD{3&_8;h0l(5k?% zh{-?1M|1V9JF6Hq8!2rrQJx8utEghR9+@1~Ee=cDjXF6s3uU&sVsjF>ZKFJLJL0S~ zda>4EF-vN?TE=|TDom{W;|HJ}KVQHC^{u>Cw((oSfg*_nXrr=$fGJ_Kwzs&R;v0CQ znsN-%Dge@8U~WB51vc&}<+7eTX~Yw{6^>oIwlN$WcgLkJpKmR$pKk>B4RbVcs>w49 z85j;*9`pfYXe1H=$4W^ZB8{Y#)gw`sW;g(Qnxh7j96HU`sBW(1mUL7Q$uTiT20r3+ z8OBLD@6$B>Q%bYetX{_cA3E8}mW;7n;N)@$Jw*Us>bVDst!=1T-c4~8waimVZ2nx! z8v;?i5233gfCr^R1)a5_m+bcOL*~e3lgmK6-1TFQr25bWZ9`bJ({607r!slhviVS| zMq4MTCmjGCNvq7;5Vi@x&IeOR9Zoo=O*~fdJkvM`zo+tx5O|ZPPxxSX` zQkL*sOkOD20;~zyMmqbR`01SGH61EFM(WCGZZ2c{B%W%dQj}Q_ZQykS)B0wUM%3;# zTN86}r_W-1##M@b7^pZ5M{N2Z)L_#tZZ%P^+C>Gt2TU=!xS5>q4g4WT*X#IWkPFu^ zMRjX6yvw>NP@}GTsTd-m)3p0tF2XA-C`2~V3?yKaj&t9hrjt+?a%tBoVRoWe~$;WPJ0qJFEmydRkM7J_1SC}9Uz;-9DDtrpg zx6a2cYH2j&2C{(Y;M)wJsw^-1QE))#go=4jNOgT5=Unlv&8WK!w~3`Zay zqd$PI7sOXOrM|5qS=foA!kxu{?e0Z(V472RT@ODpjGZOQ?XRbESwaY53(z8tIu6xF z*z8DOIb{lZ_ZX?{+F3NaXSj>Xl&8*_=s`a9&fGz-J=DHc&AQv~V1V`8oPT%v*0@(` z%~-=74r+AebgX(Mw|ra_I30#i>8LTz?ijnl#N=YEoWCZ0@a^+EX9zn`ne1=T0GZ9{#Ns0(aj17YKx!;{eU^{!u5Q53Q< z=u>unhyMVw{VSq`tu)SjM0u&SW?bvnHf~|JDmcp$GC}-n(!3@1mGJZu-OJ`nar^Fr zfN_Dxum|z4CDQE9tF6Hc50+Uza!>H}Kc#yPm#123Hos=FjKv9Z;Wrilp18^2dsdj5 zt*%onH3-G?TT@Hz*57Ove`t&CMLfX{;k#~eoOQ-(Jx^4&(rg~~_1SIXBXb2UjF37H ztthp&d!)N-c#X;?#hYN>2cT}a_Ny7=2Dr}94zC)zoU07hR2RnjIoR4ZE|p&=bk}PzNKd{jd8*D3Z`gZ0bwQBmklR0C&IP>s;=kWsLl_ z(rWsoabJCsG-+l4606V;bK0rPXEoes3y15p8UW!h6{6trgUwH2F=iu?gO9CAs@s%z zLZmlvdm7J*W95WHhCF>J15Q~VQkYwY+iMvHLO9-iE2z_?ifuPqvsDH$rpn=Q(5?!f zz}GpZMG~|Ozz7z2<9}b9C;2I^lT5aKD?+-vyagxKBl|VHZP&{@v*XZ=WAOE$3R(~v z$Aa~3D03`IF73yBjz}Mqes!;>G=3uREU-7tDn;i3oSn!vNIw)Rf8bTicq>r;%kdN{ z{36O=a8Ffl{i$AGTWR`A5yHREpb z!`a9^R|KK_vOfV_YeyxV?QJ$h&^fo0>bwK|`S%sCrYP-xAHY`mn^PDNb^R<5H#UYLm-khW5LHG(D$iD zdIy{>I-5&ChYEExQquuODb(E4g#a#Tc&6r;6ac(aX=tDVl7mG87K%zJ1DQQ)?w4UM zsj1u9L-(b86aCTL{sWq(+%c}_!dB~{_|8~I}i6p6dzOVQ|UwdOHh|y zn*un=hQv4B7#zMm6lDJZ`h`}}?8l0HRQJvg_GX`jgqk zTFD7Zwm&t^l!`#kcE^kyx%sn!_||hgTArtU} zrSwAufE!{`G6FBkPERxeR^e@1WxcG1OF3o06R7({5y$f|`1?CQeQJRGc>d1udZc;~+AmI$&(r2uGJBB#x)8(kPNNMO9D&fI3n@SktfVX4EFJjf>nspvVH8E_!p* zKGmatdnJXRofVw-auy1(!ZO5@kH8M()9vFCp!q;2lYv$iXjb8E%%~=1E+gDG6&+4J zITXOK2Ng?AeNpDTI)qlyLM9^BVq#dw>gT3UUMgGb`%N;&Tie-|8+ey!U6dezdoQZhk3 z>V>waCC0OLVf~+X99HV5?QWn&BOZ3C>To-cLOnA5UG+56Wd6yD-b=z&P+Tzx0b!DH z&jTll09`9hk4V#^vx;fvRLS!$B;M>v$t3+vO4b&KP#5OjGj=2LgvEYfxz01`%}xQ@ zGuIr|4K~jD+H2V_H5R*BrY{VBQlNo5D90!2Xaf18HAhm?Ak`Ypr;=qBmkV%<8|@6s z(|4%PIQFZw0R^q)wd_V)OPFVjF;ek3VUg5icdFBC7I5n@X-v`^x#MY7RyH6g?oKc& z#if;|p8&VAwu;&iNfE?>R1?>MQ+v<_eMaV6JvQd*8)vzeDB02k`_d3H6n$xIr<&r< z31@)Y%_M5i31Hq^5t6wbanhFR?%u}Pu5PD_2ooEmmBOgW$0XF7vN8`^0HtnqPwhL; zw3}bB{J&)p?(;f)+w;d>n5OEsS9j4{Ev}&@mzQvoO31k~AnKmk`&e&zi*~G@d zn>~fr{{SLo*#29UIQohJw~^Ya+v+x#cN5z|aU7FdkS0YrC{Ij|-6~5@(nOzod64}v*!$N`5!$La@$lxL)yenm(+6LW zpYf^@fUh!R?#Rdf`a6g7rPEUKEhbdFoh6sd-IVA71CP?N@3c5IElzpmp5YmS9kG=I z8*$tpLtRv)3mueCb0iA>TyFR-a!47*2U^+FZmur0=w`aLHn$GBcuNM@eKI=N1yt19ea}*i zl&Qt8!!(^9$3%iiEFm#PB!*U9?B6l#_ld{QRPAeSZpG1tKeQ@r673s;p4sb)rvhsO zUb=bawmMTHh!Irzfw;*hraJzVn%0vhtqchkp>t&MOtSBRuviYNeL>Ii`c`J9i6ALG zsNJ_)wFu+Rm)-I2DKNXHw)7Y7749X&DaTn>Yz$#<#3?~j$k zklhXsd{?Od0BKsqbrqzOqFhV~jxyY~I@XoyspyRG^tm@Af9*4@+sPfwAKBhn62Qsx z?(9{+&*PpZ)hv#sr%h-sr?oNxiJ)z+q!4&Ng;%}4`wf)0CMjiDl(9&ca}n%2nx59} zF6`mCk9NtUSrjnA0F3fIYnbUQ^o%KD#0+HjtgBrr%Swu9te{v@SsG?lCk2mF&rY2O z6t-7-jJH>DURbOVM&rnpWez1A_P`^zUs{V(O-4(LNh~LYB1iuKNRCy`^!6j66akZ~ zn`ovFA&<<#P)}TX3g>Sv9piUZB}cVbxsF@E7G8-Mx0I@=Jplvy=CrJ!yNY5G2Vi(1 zkl>HRPzRn~#&@s-k$=sv8FO=a=2|Rq#^Z7GBm-&gDk***#*tee zx4{H~NSuw*206$o0OO7i(tt4ZdvsYLjf03?!ZeCMjOQHx0GY&2eog-XeOA7kDDgLerniumo;X%u3CS#j zY=94R+J3EE$Ad4rYQvd^PbJ z?@w05cVldOxCO!88U91@HFw4~sr|DR{5cl-v;l!58)Zy#eK^M+#;y&b+ zZk;Zxt6X@KP*KE($_Kliq8Ej3KN3%B?DW|7s+@C<-n0R6bgNsdyIYyy-z}*oB3R)` z?~a7l&_K(E0E5&X^^>JTs4d0Rm$wl-PUGzHMws%@dY`c=(GOkGhRN4mO!Vwq(k z-c6onKZTE7zQYs&p&BY6RZsxn0nk$*y0^MAeV%yb@|?!|7&g`&RO6xcsQ|#mL1$rU zVH?M1Z56sZnHge0p_uh29q0j^E>nYT*RaN3|wB z%6ft8)0zO2Qq$qpH2JKq8dZvA+QumgHa?=Kh7`AgI3vi8H3*@YvA`G{o=@XdHDB#h z6}Zw(qPd-X_PX3ai=Ep-^=_EY6??S+K^3jM63ZkoM;pxBrDQ-0oMR-8rky0w#^{eC zt4MaBCk2i(f$P90@Tyu)n=YFK={BKreI(Po#pi7740uHylmXM%Ju`}R){|vd^gsG+TLN5 zEQLuK$3g+^R1HXV2UV*QYt7S6xO;IoC>>2yV+R z*PTl!8RvoD8K;d#(eI?PONg54H4N~F1=Jpdj-YZsI7&>++>l&Op_N2->Al#K zfr0qY28bl6&1dPFXwzEgi@TeTv`*6>K26&*{440Au&cYWwV9;cYLm-*{iACgx+TLc zw#VFFF3f!i{{SP@0_4^H2gYGK90~xH{O2+!??#f$TN$nzr zP18oPD|ze3%1PG)FVT4k<{ro*S%t1Y}Bg$%`yCnuBcO-?Q0TZXt1C!D}3lW5#jcF$Z;1wCg_ zeKx_a63*i6h6Boha>pkb$F*f@YrD&0xIBT8{(UQc;%MN3=9SeWKv|uR0)f<%*jG2= z7*3<5Gg@8wd-k$TA0rtZFnfyI4=Yqm=fy*wjFap|1`HFAKn_1T#5a*y-cR<4Rz2#H ze8;KA(~tY)Rhzf7P(YBxp(2e!s*ZpT)y(*6 zIBizq-ULXMu;Eca8R$>)t&JYu{?f}PG-T3|`^#-(- zIN^ySjTI3_6;xmW>?$b;1daj6Y5?Z7mcKfsvcm*zV94Hlg|N!s!-1OQby)V?D~>aj zIR5}X)!gd$5ZT#Fb8zA~V;OeFa6by=E>=vqy-i)HqEV18^ghjAgF026|E&MSiO?wd5)l!(?+M-(r^Ny^FY zJ!`nU{?tpGGpDtvx844dCJnf+`#9r0dezma=0z$>2Ed9Jo;jWv+F0@uMo?LE*9W$0 z#(yf!xL>u}O>SnAAtDv?B5kg@?hj*9Sr4+np39n|Pv*dy)*!m<7o0 ze=|;&_9qzR{uBYnU)@i4tX$hGnBun}5WQHDpUaU!f(wAqTmlK{C^;&Bt!_u9S$)3Z z@cFLuV{(&)1PpOkBDJ)OnC;WoFP1;80C{Gqq)!FefJ9x%!fhGd?kZ&Pe!J(}`BqX- z=0YS5w4jfi6>ZqT82qqn)dk7kV~$l;9aS(0s+a2|u^rO8f4tlZ0Ol>cG%O}a^;_F$ z5n5H-8}F7?bqY49{Cd_$iLci8OO7iTj8;|-JgCX!^~*Q=MAxNwcf)bn#Mk!`=I&5- zF$5})xc{O0^e1?whM%q7TfPY4${Kwo($DAf%8a+F73T{4oDx955}%(PM#w0 zB=(HkrHUakjO6Z7vB&-MwEbGJJSTW`y>ii;Aq1XVf4WXTm>->O=$m{m^4ve*BDpaXmafoG{<_*mwwLhE z)AauU8q>9oPY!tY?!qzx%tw=xfLIX8`TU^%HEYJ!sJi4DjlKo8tpH$807#$_pTlqD zYf5tEmB^_cXxPXU@M;KLOB%mSj)%2OE4=fa(CToe3UH<&b4!{*N+N9 zl(Yz1N-02~1fr1A&;dqhq@WID^%Z|b(&pB6Xe^-zbdB>jWnSm-ssw!1>i!GT6F|^p z)o*Z@6Rz@K_#^5EAhq`P3E?!>MbR{w=#0va`zCgVsm&=ltfi^hIdwZZ+LS%G~NI zPU3K4w;gflTYx_USX|tP#J6c_q{E`=V3RNqLaWrKd1LO(KOyg166vt$J{z;slL7Y^ zlOM$W$@*s%N5R%-Sk@=k=ZtxAl8`TK^ceO7093l|@VV4wVEIM)Q|U+yo4Ei|E1tfa zu&ryUMhUKN{$HPp0GSpKvogsv)|WDFWSRJg#uSn<)RMy$4yh!u%{yGA_FD2j(qcdH z@bVsh?+b(@f!8$*8oUKXrl}E{%z&Xv=rsF(CKVtv7h=aHiRw?~T~)rDZ#BdhGQf{K zAc&-4%IB^R;XoSk5Q(_(2R}+pFH*GC>;O|itiBTV##1f3k`?xq-GhUSf!tJ)sK6Cr zRa6B~02}})0+r6HEwyVsJXzh!*CCkA97M$s1FN?|o`8S#s_gG1cGAfdMp+dJNWlYn z#{(yUnvfnbQO$D&xr|RdQF*Q-kIZnp*z{4Jr20?<8coIR)|(94jhM5$e3yVoA7>{6 zaNzNS_|qj_S+&@Va$2sEu%9tXv6-dM80;4q_3!l;`c)k-S+Lfko^3keZX$+ef!#sI z@Bttm{YN8;0I_=%^VnQNYjO5#hmDpwwr=v+jvF2ENn-@IwifVQT(!*6M5yyH!I6N$ zVm;3_Q&ZNV((g3;SGT&FTj{*0#1U=_>dblt1C!qwt!eUDY7u$1(hylU70w7FkU{DNN26cgY8G!b_L%y6 z`HZO($Q_CfjB(RE@$E@^bz`Ym3n6MOw=uhEbG!@l$ew0&`i{IzrrQR@#}oyjFo31-eU!TOjhwj!!yG^O|pv4 z&LI`NE42`I6bma+d~ZI@7urf}Gi)2m`e&{v0xe%vx6yRD^$Vcp7*{M2a>twi2h`Pz zYlXSBis2R2WKiHbm0$?ZAoMjU#UREg0*#ibJ>IK-X!a9B6}HWn5BFv)GIsqbn&kSl zR*{_^2xhoxRai{>RZ~2lfAiO+X#y&x_M>N}qDgsk6bSAST1E;B9^B9cz)4miNL%&WJ9&q7bFWMApR>r%Oqu4jy8Kvdh0y1t;A+JkEm zC1aZuqbwvY^waV?jXjcWKHY!?S~WO4_N^s39OAkA3n!PuX>AqEvAKz(NxHJ0KsBeO zT2Eu9+uBcaCDf51Q#6C-bLwk?qO{ucJxVV0;{1_x`(mKGytc8oHy3lHFs?HshYB)r z$*Rer+efZRtRS21a>OBgxhuCIj1Jv9RQisUZ>m|nrR)neyW?^;aBy-uR2mZ&1#-Oz z$Re_A^?MCX?qjmJSsvO$6w9=Nj5Eh0n!haew&)UDh++yb14sw+tm$<V|tz>ej;_9*_fR~3rh5wR-@Pd%ZAUVceFV!YsUT|957{{U=(wh!#z zCnd5(f=vEc#bQO`TS)kZ%0dTrkPqoj{{V!ZN8v4%2e~Gvah(>S9o5x@kl9|FOOuV0 zg%7mn(C~df8oLWR!5Yfy(ggw8Mgtz_9jlaGZsoujLHJUgPJE5?h0j62%`1V>SlKOv z*HR11nT5ojX36CYv7UHNI2`n-@AS(JLhjP)c(>1J`{0l{1qtiW@(u@D!WZPG;c(2k z##M`dDtNzvGG (}GwLljsTSObWwBy#D}%k5IXIg2OJ)E<(ecC?FXmu<38CG0S2$(du>>W z8u4P67-Er<8{f57J`K`Z!q(d6dEM>V@hlOnY|6(wPIH_b zk1VnE>s|eooOW<*P&Xb}`kKV?j-D@cSwJ5$e9CA8#joHt`rL&Z3o`FgJAe9(blxPn z^CHkZOpC*(*=~op?fDlUg=1eu=R<8F1Ql(K`2PU)#cXJi9b3Y>&WPVMs-o)LcicH3 zejtzd6;O#hX&X(XX!`6dO~ePuk;h%h%Adq@_}53MnEXZH+1eES{j#n6036^PmLHgq zW9e9a84IrXTK7qQWs)y4Ab;nicps?S`qhsBY6}!`!7F6j$YGHi{&~I!PxrQdZ9p8< zQV%_`%1Q)_`Eox$=T?=en&pFN+O5@?99m1hKX{v;<^KSn(1Z{O=xef+uM>*2Z6aLK zgH5Lj*uZ$8Q)$A07L-y7Ge8OrI2vd)>Hu8Pnr$rt3MnaQ06l1>#TcLtW2vu5@aDf^ ztytP<7g|eB@x}na446@k$0TF_0I%;}ZO{Jzs=Y_TT6A6-@a(#+@e$lyuHaj$Cs04B z{5>m*cCqL}_b*>++E<6XojPc4Vo9=)#SttHPj8!!zSUaR+rzf)CWj5J&9mKuB#?$? zW&^okPCq*5EUy<;)o%P(dFly1dXW?bAlMzPW*9h({76ZIXol015K>4UW9#t@$?I9?&DR(@e-EV%wwz zWIm+i0zWFl@Lr!Tz2ZBc6W%T%Mk{QGqT_%E&{p4x12oTXLVfp5IFAZyf#tuy1F>9%%tjO0u35 zxNC6@#PTVGLyXA4jFwT`0CnwFW4VSKdyCyTLnWGzGUraYIT7+wK2A6N;@ouOJ*s<% z4W!9ocCDx1#fYN0jlfdwz>_0`zzE$1XWye6*dxBQMwf}j)MpDdx-QiUqktQ4UZ)~} zBSrGkD1YageBbXLTk#pk{06VvFCwVK3zE!o%yLhutteSyQzM5jFdENe7R z6BY{KgSCpE%yK9J>OmO<5mhGDY;E;BZ8lq|*7oEUiX8mR03@7t93H-unqHS_qiNAt zSj1wsi#u0wZlsb)Jf2CZ{>yG|mgvD5xK-G)?HhugNC&Pxr~%g#Exoj}vPj}IE><-x z#{)P3bw1TwOVmHK^yqIs%X4eyjlvt03nGm7894R)YVIiw0B60+(F84*g$xFchOj`Zkntu8Jnw}R#wW`Kb-XyCMD z^b7}2#;R*N-KK|c1lM9xC!HGHaUYyo( z!#R!yX#*LQe;zTwGy!J*#?w=@Hn*@O@G%6&;~e9upL8h*qbn(d< zk*>o2=`o%O_2Z|wt2&gIap|`WVH!zxBPJA(;Y(wHYJ85Qb4<9nirxpBXISEmOEa;+ zP&$%m0zEyhn!?=Pgcn5tlt=eNV~{se4 z%AA9d$gH0bO0ZhS%n8hxy7urKw z&f6K)7%`2zjFE%fR@irHkub$BYBIlKo}F;FFx;wxz*B?x)_vu{x4SY70VH90AKhlp z^Q)Q_id$Stt30w6i08~<>N@}hCH9!NmyroA1;Q@y6sG=2QVu`ws_c_-#a;gZS{`&1 zWrAsHm-(AM6TbURox*QI(Z~q{wnzT}TDl8c+iTG6Z*Y=`+@tJl?P1g(dcyGbpCzH1 zB(iIG*aLwU!IAh6TGX_%u+jvAB(}8@$YgK`UCeruT)3~|yB*jk`-tc|`&+Qnuk37Y zB`ZDa6@&#O5<2oabswEtyP2)+W|lZwc@YaNNJdt|{{Xx5e;{g{ z-X+sx$OdVD-BJBWAO?{xwf-tlH$wDYqJ5mOP-K z`Mdbedt20xE2{Y5Y}b=@lGQ?O_)?_{%( zy0@Dc$>8T0_o`R+4M-JqpMmk0!_!%159mV5Hb<}07~Q{y<$R*ppU(de-6h#g$=0?6nTIi zrx*tvx{vUrGpahNeup?5Q##{&w-Kj+t_axrQpi3<1*FgD0e)F14g=jm4M z=ZZ--$F?(!0HDTWLVdC`pQQkF_V-D3yUH7pP6LJn6YYafc(gv;sA`Ve>G`f;j?!8>HzGY4DdQziE(s?~Xw9t|P~mCf`tk`3DE(Z>Oz# zWpkb|vin|;{{Sv_jPcrlJaY06D^X`pl_x;J`X1-=70`HwP0@IN#Ok@+zh=6}a5I%Z zP+Wc$lR6fS6}eO-2KHh8HM5~F_Q!_xjS=~gSM4x*(Ap?7MZN+ z$4AvKER+x}B{D_t6Lb8J{yRi%o_iYWr7OnA4QTSnm{QY4Eo@>uQQn#<)Bv>VZ4?0D zX~LQ)2iAZcKs1z4A!!8^xS#~3qJc~fW+n4k}y?K+@6BHFI2I3tu&7ZY3w)2 ziEd>blpK~n@GPJB2p#LrwCl5Bs9W8H4q=gG3VIwI*Roq)T*+e|t8u5>TIMbJdCu^d z$6Kj)bgUhyVC!J8SBm1QD{Hnt0I&ayRTmH?O-_DJtFNIkd z7rFWR9x>~h#L&#~4xtsLrM{7-#vV!3Tic-j0G?UHG5-L3kHif3uCq<+YkX zq@gml?WLHGaC+y`u{4P6HHlMLu+r`s(T3UF0C*U{%)XT`i0)myn`bYTUCtY*C%046 z>p;#cN!08-F>|TvEp;%7!4|fK*oiQC&tgVKGuWEr4b{vyjd!`$d4~BnuMA1g9-#5h zu4}2+^muhBQ8$>3Ow6T6A2u_`;43ofCCwgvcScZ5j&YC_ascO(=~p9MEf$wH_pmJ1)5kO|oIGq9PdMO; z0A`~N<;I^ZRu@ZYbi)zO(eK&MU8k=ZsqJHu8(3qSV?3yVUQz%qK;^JF8S7N8^{Y!Q zTE|OqBVAta^3@k1LX4JU*mnGWwWLW^Bn`xN^`HtC+C{y#vw5lpmF{kp5x2Q2sH25Z z*k>o|O;P$Ze7!VUThT525C&X!jb0&YY6!mWgR}%-MxpKGn(Fk~q#W znp?X|>y1jrXf+16wSk$Zfnx;Ek%b$NKn_p8wE$lfZUk_1NK`VFIl@0OuxvDrq;DI)<4A-PMeiGfFob zc^fQ)CmHu62OYDDf>`xt@dQ#O#k%P$0S^&UWqEVQJpcnAuN^U@92Lr(k7~|McTbmF zmqtnVU&9!dNW!0$PCA~M`G+3#0X_Av+iYjGGfNMeg*?bxYo>dt>}i&k!ph1EQ7n>( zV^k7K+num6l6#tqSiQKg(2G7UiEgF=WSAff;B*A_J*vqfvh85iS6aTF=JF=fnNV8Ws(i>m`H4Q~ z>-bXZ8cbT%fwP`z;*79j(7x64u0K0mhQ$P@Enycx}YO7^)bZ#bCzi_$o^ZZTd2d!ul zcARo)xCgdr3km?w(9W)GoBL>53!Ue0*-I7M+pm7K>y0j1^{ahBZ?0pG6lFHb*p5O* zGQ++`R%WfWR{&EMK)5wk+M5f1F$f`BaE z*~5EhEv?E4AeBlw9^lp`?YuTRQ$qw{A%ZL-4#8`nW+gis=WXq^Icy}4SZijueZZSw zcI`a}J?fzCB*~iQi$)%msQKEYNXn`kBd=Z!SJ#+AW1Kk#Ie~0?GL_@;#aYv|xEA6W zt*m#vZU~cMb{zViYe!VjZ!S^H5n+oXg5)UqST}m_#XefGk>%i$l?g#2pM-DTOOp^`~9VLOrU z{(0$IVB}|^u5y1A#F-IUvyWGkAJVg@@n!P^<*X5UVM#x!u2Zz%((Es+qm?i9Cck%; zogBmyVxEh~Ui{N;bURy(TH92XHv3hwGDiE3FnBz7@A=mkb>a<9Py=5|xi|$5%>G!c zE8Dl3i_a@aSLH11TlM_t1JW<9wBn5v_mimH~9MmXb>jGt`R7&S1ci@1at zAOd;!$NA|;_Nh<`94PFE87J0&I`-931F=H5P)_54pGs?LfspSW+-sYk5DjrP$RVd(wG%*If}2|3IhV(oM8HPsUy0M zbSms7`LN58AZI;B8<3-~QCuk2w%RS%GA81KYp(Ed*KR@laf%`FVV0HAsb1~}K7c;?luHEVms<~Pc)_peH>W5!lrY0{b1Hx%Ui zPzRD-!Q|b`w}gB;k=sAuYoYN0Tg!b9#0&C?7wq>Qirq2%$KhF%rufwx-9h^Q0QKuj zK~t*uYgf@*nGk)Z5PIZtK>UyW^-YL>ixuwljVE4)Bx%Mq!a@{4$rkH>C&1rngKL`bvRRLX^1H( zqJRTPX-zQopa*z2!{=Jn)#YFGOL87kdNJ(3kMgbm03YjD8ja<@g|xnBxnLz_=&RrS z`+L^ZjcMRt33+)9I9<{a{BD2F1#x;uo2ThFo-4n{+w}vs*+~1T+XLVE3iG7ydXZKx zwX8SVm8XU+TV|Q3r<;2(On^Db^*_{lR30b0mr>SX(X9BIa*82N1Zn&VeK0b|-1}C9 zAv`PLceuP6yPp>~D&1L+F~)yZZ=v<6{u=0#+d|(AV8|e4ap>t>&`z4#=DzwH3`+F$xEff zkKz=;bsA3`r4m(E4Y9g5J0EHQt1D!j_o?A=_GF2BxpzOHABQLY1Zsn^1Fto5#R~zN z0N1o##Bo}QCCqnrsSUA~IUDzqZpW5Aed;S4M=^;CVM*(bwSGIeAdwPQ*h#=Aq5NnA zsIVAOw*>a$wY)rmG`f7=bWuuTX9_?p zI^dq8o}-F(sj4=Y4Y`iO?)B!GVOZ^uF&W9pB!CoSsh|Tw(5~=@WX@ih5K|a&~W{lQlj+Z^Iuc+TmsLybhOrBM{pWWN4jA2H4lgT`P zT6VXkS?ju7x^446+2tx+Bkd;)8yWm414PwS)NJLwmdZPrn&uS^Br4##1JIGwcBiXB z3`-h1s;B`}9)hWa((G=oFG5?xaX21q*a4gl22XkblUCKOG+j1bLiR%)yja}9Nj#hZ zf$l|36~bIw$2?`WNP*WQ2LxnrdRBD)BGCXL^&32Ap_vcqn$MfZejSC1HlVCW_feRB zf`Bw_^=U3Oo68TdT*no%sTWc%BaoiU>yG4m{w>z-bsK#uchaqr=KFyZaxhgSoDy*gFnQb1|jl&qF?tT{{Rvyl)n?S{in#VxOVNls{a5i&{OQNcN%ucr!non_DdgfkEmz&A&;H9m@y4ei;@;Uu`>ap% zpbo=a)8y53=d_CY;>fcpGQe>71QG%5n!Y+$o;QkhX-5;Jf9|0Exu|570%|vNU_szudg63C%uq7#pEr}U;&Y=lfWx8Z z@vk|PT4FzYs7T|}%`N?EvDGazlOr+qQ%5Tkl1Hf<`y|L~yKsFBt5CkRr$hiZG5rt| z{Dpam)-6Xxl>P(!YBR1P{n!}&TNLcY?IYaui9A844t&Rd_gA0Rv+ngBD)EupE6vNt z%di9d>x6xNOni_a{{VQCQ8vAFdMs=7Q~ot^a*MoOjOQwIT(Z?2^m@gev}GdGoT)h_ z<~@HZgzHPZyn1!6PhT;2pXXkF`pxOj@A33eRy6%icA32CnTFnk_sFB(-r*TRu3Kn# zKk$%VEPG;0cvrBFASyQT1@mzCVSa&E)6iEOx_~f!?pHlPKf-+}<5E6qfd2q^<2gOZ z9X|@qn=2)u)Jdz{w+8Z7&!miMl(!1sGr2rumd~bp*FJS1P#y~b$FD>FG?Qvdrd8Y* z18C>3LHvaSxurbofsEvw57Yc=jl}8_MhAs$qmI1QDYXrTCw;+8dywO=UPgOv{#9A7 zcG}y>$i@#a<+kw5F~)wF{OA?SZ0ZYh_Y*9A&u`Y1O0SomyEnhE{{Z!WI?H>Rn#yU2 z{n?aneBfl~1Nqbsdh#vAskDLtZM>CSjs-glnH>aILtheXBa1FI0yN2?@#{J zRmoTAHUJoa2h*m13gaWxCsKi)~{khzZ6`%`JjeZ_cPz#Mv< z_2z}uRRV~K%8!&Q5zo-q7H7C(SWArhj%sV0gFK<(%nA@L#d3M>dG2T(&eb(wLWXeo zIRVo-Z(b`((@~9F7LcT2i;`t*GZEiCy{pb7#u zv~l*ilr_r_yhlpz1p^ANc?h_+k}@(GNUIcvfIMqavN65QvoBnLefon{JU@7J&l1|) ze+0iP5BIqL0MLN0zr~gTFU*QKagkg;p%F~uf{nRI{_A)A4KOz>!SLUWF0GJaB$Qmj zF~N-W1O5U?`qOV8(I03ikA@TL?}t1~cBYGz}8pL$hmmB$`0d86D<*%EYK2ScR)%L*9Wy;7|j4@=-Sj8+TFFhGoo8u zy|HOfD0W_@dE`^Id!0_&J8`AhrPQ)ci6@yLMUFq>bL;7W>)x~m0OF0qIL|(m0PfY9 zq}yuH-CxV8-$y)h%uTFO$FxHqI0W@1@t>t!ySs+Q&TG4w1aLxzNgVW510>OBc@6!P z7naZFK{^Q|d=a@w$T&RE1#M?Xi(9se-fOG4BT1H4`!v2;lOMvwbGPY(z~-->c&zDl zVw&_?Qt9`Pz7sQDEMv(*k^n89xg7_n{4HHcG***IZxYKoqZs36+8wdLC$>*|0FKj5 zveV|clG4^FUgkqA%!&b#k8*qe0QJwUStFXy(j?TMO1FJpI3vGh%&7);DbE9vdJJct zwH@7+?E2M}+h%jKFE=87ID4zF(i^nKT|*xU23*gceb{77bzXZ+ZBQ{)yNq*t1jUYnB?sl zz!^1{d3~bAcMZkW#e&>Lkra}$2Tb+BJdb=;N&Ic$=nfxIM?R6OKk^2EG&Frs>iTR~ zzht?z5)+876KjkTIT_=nMSC`=HLC=*w}rI!5B8~DzGXQ1LX7(TYZ6b0S~zS)9mJ!t zR0H{uRh!}l^k0PN)sVqlCBik+-RaC;n8Eh^sb&rOC4>(;%wP)w7Q z3%rs~PQYg$g>rA>O-5t#!ES@M1fS>qDzo^DRd9236;EJ_G5F&&0oYHY+T3fl+OxF( z0BE<3qm2ZIXU){@_5T1pgRX@~MnKriykCG>2 z?}1S^zabb{5PeQ*^0IxbPfC--_N084^FP#qRHoMwU_h~t=_76j@Z!Arwad2qyBFxc z<54!Pdi`!3f4j%>r^@;g>cyUbb%|4$t?gkxsSwZWRp!^O$lCY2GucQ_<%;w7x|&1# z$(_EW)LvlCJ2$yL)ohX8OMN7)1k+0S?!}1w`cxwJJY`Nm%i`p8`X{&2{D{x5P9bWbf~et&X4WEoG;2UKm?QPkMaDfoVV@64063O z-yXk}W8F_Znp?{<$r8^HmL@;OGI<}5^rl>`&9;qctH_{Q&nqGldXbKPhZz3=fSO@+ zXw7$nH_QoNm!Dn-^fguQHc7Y=rZ}^Z2su4DA5m1&8E5d-*0bh?f*IC5olBBAKZZx< zY8w?>{X0~>n&d^~qLhq)46aWA4^9u$AkkrSBFCOF5;J8HOsq4X^U!{ET`p9lNX($S zmt(u2ALP|NI#?v0Sv5SYNfQ-9$1*lBpn7x9;Z)#ql5U#}gFhl3N$vX4VRJKM`$P~( zY;SHs?7hFwwJPc(1c?C2z`^J}`}$TE(f}S|!2TZ8(u%~kSdw$sjL^dEn~keR3y&}Z zkTP*mNv(xqj?c)*IO;uXCtxQmfS+1WobV}+Q$kH%P2hx)fdKr!)KWgBF4So7$DPR8 z1!|Z^{ORcn6Vi}bmZa4rYiQOW%Wzxwg@7rJzzk-r*xR^=%EsG%>Ne#*ir?Tz>r^A6w^QM-8r@qW{^~auF#iD8KHz`A8LB&|6F~Th z<+E(FzTF8Urpb9<$+-L}HT%yyPVn!G5NTgm>i2G~!i?0*r1 zUWWmP#ahKo09gB@_r+0Hmd$26!t# z{@d0Sr9y3O&iPMf^k2vM3f}RSyEddy+(Dzq{SP6HrmvX_|Z*R+|Ns00fCK^*zmU zJ|Vjo8kC@Y$o@b_bKmu@w*K&1*v&Ra$Tsi9ry2f4S2=dWngGBKt7w28OO1NfKQ{3rurND|`R;FNBTMJmJ85rajA zjkcL(4V9!T3=oZ|i`ajj^;1%~)ggN{(=8*M$vUj>BVl5T_?xat^u=o9y#Ofnrd(XX zYXePjDn$|uv%3XV9;BX?ouz4aRyVqh&DN(i=h~*<6l^x7x(wkIWcu=Z;Bi(pO(x4) zvTH3yA3EKbF^sVQka9X7S^&BTBO<6;>sFVV&GwfMnAa9cjWcZd0c?=Fy>ZSx{f;ky z003|RqmIIWDQfo@_PSlfx^0-dyjA_w1;U0TfypFrI{p=6-KT44jlv>MP#F~tR5m#P z_Zg`PP%=(C4A5u;HY+Rj*KRK*)Y?lYiBc;e7y>iKShrGmKb=Xb>9*Rwoi&B(v)jx7 zbyq4#&U%h}Qfb=7ma5lc&SNjxXKQ&*(g1J$x z6z42X4+8`9pbNIv@Y&kMYXSs@6jOaq3YQ)zz_R;R1SmIIL+yVN~1#3-W%KHB9&f0M#_Jvk;0Q`jK13fdr=}gvjE3G!n zO=qV|e=(6zLmLG=oMfLtRV48bhwPq7KG|))Lzgg(#f~wPv>fr?smtSiED|DF=J!+p zex!dY0O}N$1B_?2W@)f$klyMNU){qr5=afKai-rbG0snNf2Y1HpMM)lz=$kV4$UN) z{Q&;8R!e0^^WyG2f2= z0FR||V^9V!B_-q@cD6BEH!ZmyViX0B7$XyU>PiN$Id)UF((W+Y$%0XXw|5O7T^l!m;w@ zV6E;Of3WMzs;Q)`^VDD-vp z_r`xJ+KjC$7}t&Ce#P2#HBS`k?KnpclnOyk6o4oc8Yls1q@@OcA4M{qOa-EniUchL zW|E2kwXI#r<3AYOKZ_s3pVRZL8)BOFy!Ve5be$|J#)G7f{3-{0oPI;r zvh=wZlq1ijoNH>QA*xf8sqmM)23z^wyMJ#t-h~h^&TI;JF{{ zj-OHKUSaDMbwhLG9~s+dF`U5@nXcqh!9T=)gM}X0uUu1WrddTEQX6=bA_8y}3gkW- z_;s|M6}1bbKW)FmwtA{|AJ(&eA#3X2=rOnMh`hX;zt zWiXthAEB>BmtF8{U)kQtZL3^0qzMFZ$gvpMD8MWU>-tt)`p1LTL$kt?ObJ^i zT5pwa7>*^n25qW30n(vA5p{^6F$lV9;1^8DJaq*?jeCw2WZ zMTC0houI6O(tEo+&ujjuzwi<{BDSTuwX;yyS1>?5Wsy{VroMfeO+x&axSna5IK;B< zY<&sMG}y?YUwV{otTI#|Ly9aj-WS9^8?cMZO;=8iH6-nhRU@8H3sj%tABCgNH9f?3 zSR_CDEqJN3Ae1fx_5^?k`jbxN~h-$LDe#X&6b zoFIH23O+gfaYcZr*6Z>!NrY}UFF5=vHnhQYEJUDg3y-`#K@}_BE;o$)*%B^#`;3aN z^8gB~F)^RrNC3~S4iCS*I}^->k{HBEDjcEUg4rs4_!Pl`$Ofi|&$@Zdy}P=sd+rqp zU1abthpe5c&g?`Ue0fE-fK5jC+kRL zr)svz29c&;*|~qT#01f|1!PbIegx)_$sNasyw+%=zm8lid=1Hk9OJGrpTzpoxc!qG zxsM|_r^gi1q>mJC>ln+jjD;Tm0Fk8AZXp_8qi=gEtIZmihzEyV*y*2Ik3qj}GW^_J zmXgD9HWo!kZ@|1q_1bG z!FY`A!E(rG0y2 zZDnxk_V&YUDo|xd){BnOGft#S{IH)dAA6HbI*q_(@}ppx`HtRkR)lhG+8u)b0CW?N z%A%Ity7QVEDlIpnIu8Xln{%v6HI$38K#35|zV{O>0~l%zAuAGXh!Lh!@L0dmYVJ zy42^o(`|J30NYyb^4A?p9FpFqw3EZLIL_L$ABLts^348Ju0B(q7nA=0XZ?Ty_I>_l z%yFMufCG#K1L@wn_3+Gttbe6A_;JGWf`Qo_aE?RUij&HA9PX~Ev@(P4ewA8XG^=vB z#Q|fU5E@Yl&1`Vx*=a$fr;O(jJtwPzO8Wds8iz@ILP~ z=GTy{fG#lEFrUZn{${?O=X0zVEf_Q!_xtp)jz zub%>*&DR6*2lK5z2uL-*3LQF9H^~#(wtGn*F`xVAANS33+D+?eelN4SQ?fbO2ln5= zAA?rvD|maxdaaxh$jNoG^4LbCk1!sdz=A6iLd`Zp?TI5^h);3sYo?uRyEBrl3oFFs zMJ**A>!9WxOPXk98wB(FaRhN4wSSAxvNb-jl5wNm{FF( z%z3vw^#1^4`}X>ltqVCL*Ze^x)1dyz(r~dL`?5*=DnA^4L)Nmi+c&h*F5}SdlIq^% z?v`tH4Ki`lX<$dMQfb#dBGdFg3jL17=1aIyzjrKUBx#$12aV0Z2l1pchtw~ZQF)qhk}Ql_m4^_@E7OT7Cn-ooZJkZf#>FvzS)0Y)WBpahVBLXMp) zPRTeFviNrL+S116-~~5oWR5KS;X5%Mf#)Ae?7S!8d1ZgL-CN1_c*a#qADsUHg#bZq zraU%FJcDUrl~&-NN{uxui$@Yq68Ryp%!HB$t#o&KM!S0s)0h;R6;0#wIZ{lwYX-cs^ ztsJr&(Vg8F=PA~jHdHqYrwz;zlt`n>md=TWtW3uTvWphn!z zgZP`AbH)W&)~s(e9WF~-3-e(#gb%a?+{(G<9E==yuRVW^91#wNJ&WA`06?{uH^r@a z!+BP=5e~#g#E;Ff`cnhh*9wXY0#tSNtk^U=D11S4tq(P?ZXyttc?ncOkCjJYNC)fn zuNITy4~uTH2BhG1#BieH@e7*Cxz+XCn73SNSJFi1A3W?q{b&Q|tK(wUl0$yh=H12} zCo8pwxI7xllf~W{)1U}7TP2D$3aJZ*3I{*}=Zf$Iv6CarAxjLY$zbQu5uBQMu{%yk z5-;D3{o(#J0qpl*6g)Q)6BP4KeItc|{{Y9aSoa?nZ33UOX}1y{-eZLRTdU0lluPrr z=Zx{Z0=rMY2Bu3WhSg;o$0~ZOk4)!^0POBQEb0;rTIsOFbJj^2{{WWS%ewfB;yaPH zIUu+H0IqRo{{TYGWC-C>Sz=I~B#WyrxX8^e0<3CWmCx>`$r$!Mr~+yHQQ}LqEc%_$ zRppFF%LD7T6`d8hYqrs$8}D=NlPwl?clQ#|OVo z)loC3-M!bTWhE=oMNYS~0flT2VN@n(x7a36EV`?%?lK4jAIOTd_VO-|9;ldmW^)@6 z)mR?m-mgQMdq=q`yPWlz{{T8+a!yGmrPA#Nsi*2QM*C&7jb;FkzN2>F20H!RQ+z)) zz1{Sdx6$m1XqY6dIY;UbwHHI=msUmyG;SHjc_$TK(&B4PUI|#CiW$|3$@zk?KhmVv ze3^B-i7Y40v$o;1cRhbx(zy9MvTKxUNtzkd$0Fk@!;zjx=~CZW%ct2{-AqT7c7@|A zbHMALPNVavyhEtRu3kerq_MI>BaDG+pYFUg(y3T(;^`)cleb$s@4G<3+=k zD7>0l%i#I-^tt(AoI=rU=s5YapHeD4BF-IG!}`taW?w$UM#!tsf=+TVlfbH0`i0FXZ_f(dSI=rlfiAE z0rfP=Ww{}fD!qx{pUSKVH+3Y6ci9UJDp6ok=#fSNBD{O1O@NKv@+*7BI@Q03wbs6Y zq>3*rMiB5$JDeYSpt@Aff7Rpgs}blkw?0|?s#`Zv8?5UOt;Jy+(XPuV76^du00SrT zsBU#@%bhCIOgw#MKvdrs?I6e~4Fb|bcStt_DBayir*!8KlG5EE-AH#gNSD%*(w)Ni zuD}0#?*kt$7cQ4M=j^riIcu-&SUkH#%QfsQGx~I70zud3fx3ECz3QM6#7>K*xXf~% zaQqgoBK?J*38=9ueo*5deP)^=KR0V7E_i0r#6%hpWevu~7*47xtcp#JmSr{@rng;6 z?Y*rH3!JW#GW zxuZTcu32mGM|Y2FY zDDvjd?+>>zQJnFH#$|e5Z+8iN>t1xf|1ph3Mxe1MBwTs#E&067mJ5QepMsxW!L}D_ zep$em&o_RsV*Jc`V@V4OwQ7BTGYmb))?Z9^c6A_J(TAk)CffQzf*;=D&Aw=R8+k)d zg)!=G+R-RI2L(=5>I4#p81ksjqvumhE~lfo8-gBj|ALI`s8y~h!nPP5Q$O!_&)*P7 zvp4sVZ5N!!aZ<5-hcihuv8~cTBm6wl26qe`yV5)x3nfnrq?l~V~|DX zaxJP(OmkzkZfFQ_x55od0{9kCT#O(Ob}u}UV5P@GkY!+?f3aBWLl-Ngf{|(ez0JJl z%wFFcW8>qYg7vbO_fq)!?)F;I0Xeg@$kFH%qp**^;Z0_do?oU?n*qiaYK2}9+Uzo` z`A56Tp4g8a8?tOqa>fOopMD&S3am-8H))Sa&o*n3-y)XGdjo`^-%S|Kc%gfsdDd-v z+7jnn@MripcuXYukPRp|QGJEw8%Y%*tR%{mdhhh>s>ljv-x~Y2xy5~LLF*g5JK9RA z47KJ>QF-i|ZqFTh&?{>6Jb)xHAdGmn4{Et{_FLXcCM-j4>M>&0*VFcobg++_QZM#i zf7@8KCr}lBoD7=~ymOo4uLeG1J2MB4wa-fMDOpgbvnE|!*`Ac8>7jzzM4P2~6h4I< zmM~}(8dvV%WQzq^OlbJT?!6Ij!l!s!xAv z>mb=+o0+yPL6f!#*eBw<@8peC>B$kR_@-7yT1qfh`XC;tj$1WB+vA>od7*d%8@qZJ|pJWI=YoaGtRG z$IwMQpLkj3a7?|-Ff6&ini&O?Q$&+m78tNCeu?yqr`ZOvhi__-i|g&%h8vf zK^sb6eVtCrvCUQUFkdYJX6=4jCT@?n<0Luz{1p`9j04(?%@asJ&VEZ5PjJW< zi#yQ^>YI_SZ-qxHtcZ;=)|@Ba&mVdA7^_GqqoM3KIpuoS+aaZj4Iq9`#%hfgV-_U` z_CEdmLmTV(`O7(mS4xHuw+~c0F8LmIEFQDw@p*Zcc+2c4$Vc3Rs-_nJEsEW)r@TUo zH%J1&^~|+YUdu>S(;A3wuo@f5A&YDsN9fKu=ZWg!8{#UF>GWFH0?ZiC{Ow!6pH#!t z?iJ4Ce^Tteb{-C9f7v)_PK_H2(5>E=9HBPKieaB7n$QWDHLp$dIkW4npDVfdZ+I5D z^y457w^J2PMXgiV%!g`uzCN#5V{T^AE%|ETvJ$V#yK_E7M{K$Gyq zO|L?o-ZVy2L-5YGb-SdA@oS^B1`==7W**z6Df+6*QZu(3i<~KwT5-{D(;KUUsqh+$Khwh*cwg zx35ofc+BR*?4Icz@nwx+Sl>5#q$>T`{>4#1H9Nd3?Jg9_hPlc&m8zN8uVzYvxog_V}sQSeYEq)lA^MM6`Z?Ve^l zNY%2oJ4um?C|WHqaDLxfC&#O~pM@dPY3n1G@HpH{q)XGSo+8Ra^& zbj9zA+O6r}FSo9JNL+4JJZ&+8Qo{5#jV65XvwiT3N(LPRqPNjX%5yejRc2da3GTf< z>D%x`;;&6oi_H++kqxz3FLovHGfvlaC~77VS^bC5xIsXxcfjdGSM)_H7m6;Bt2d~D z@+0Z72UfL@49PllqIfk`F=CuK?_}MFR!GhXcch@lX2^+CN5MJ?cQA{*QY@=nn(7zaP&3tNL#iS+ zsa_BlUb+9V|Cr{_J!JShV`8y1Zlh0wCdn%m`)TIVd%t;GS?pJp;v7+Epl@nq$5}(- z9^!P($Nr3y4(OIgTZCO>g;wY$8X=hw)3fJR+*`MmKf-j_$)TRNE;5*z)Lhzo@c#6V^3);4pN*Xiv{n_R_dk_pqs{G>mHJkfuv9C7= zM`&hvM7&dAr~M34-zUj(JoF1cx?j+C*b9?MRa6g5kVLca3`}>FLU|V5E?HWPW`v(f zwEIj5c!d6%9-8VM%gNhunN}uB8TfOCvqqTXCH)EupX1H6(G5R0`pxjI@5IaRN@ydF z=h7`^!Yx977JaePsAVV>5-468$h=f46^_6)9!-tX06zIMRX0Lv%LGcoeGA45DBOWfIYnm@A#)r}a0 zFrK_sALPAOCf=fQO38XUP<7cJ{jxe2H~dM&vF-(WYMmPM_P!~9be$fp5PL4Z94<-l zokMupGmK>BJ^$i0!Cv+)f2=)yi*wXGp)Pz=SE+5n!WfmEA{*hsWiEkzxyp7)z-{eN zBo!$oy!g3>Qbn-QI{M>8>%<{X^D{C$Ji*)W zmOiYR%&`{hD)DFz0k6!3#lTf!xS?RJ@K0|1nuf!RP2Jz@!Rt|T7}4}X#lTw^2p1;o zS!SrUNeQO6CmzYZuO&{;L_`$Y)C`#2Q5z}l%tV|m-*Ya0=eVBCHuaemPFFm8RH67myPrSl2zB)beW*>|7t7Io;4X6b z)gA$QUUPHj8A0ZW{C)CO0x?kbxJZEn%@8a5BAM#E;=+?W%YJy*Fpvo4Tl|c>YNQl8 zW{{D-xzw&!{<+<^A$3S!J1BTIiLH?`#vY2YoCh9%X6*CyUlWje)P&DS&WJ{Z%xtRk zp~QcpLL`1^eS$liAHZoiB;+@vUfdvmp5IJ}fTwB|h!hFht@#v(7_#?`wTfRz%hCnk znF;4`g{}zXtc71NTgKgmDSNP2kCelhsbh4VhsGTcJlnvcW{qdIjJ=#}Lhr4N-1#|E z$F_Qo_5p<4l4;S8^1I>TTms~dB_dh@y3k2+v47EkT`!8GB7qB9B8*zfy3b$x<(|gI z-r_GTxRf`=F-(lpgK(s;*jdgs>zAt(V$Vh#qs5rB7r-Anv!asn!tB!YQ`|)VyF>Tb z8ke5xR<4PZ<8QK~Ox4t_NoVn4z+S*(XF2+t{t1-KPD#m@j>HQ7$&LQm+^YLjh3Rec z1SNrAQjbZ8B3((Ksk(y<^oCT`mN2OQAuK}*dVKd(!3KXbAT8f!ULakOM62@Mi=PB> zI&tM7Ffa$KyLft2QQ!h&K%IH>jVuycWvO?l#Zwnn=N=tKxVir$80f8Yq*jkNW%H_gBx0pc@BLYoCpi9OOoMXVRs$Vd$fA=2?cVJjstl7T^zfgZcpZvL97 zXQR6*S@Au+88p7PxSPc%DW{y8?W zUxi{Plk=y!Up4PmZnO`{$H$gJ-#uP3eYY-HXa%~470oxb&bZB|@aVI2KAOcApz&@e z>MNEN*rqObIIi`Wypcwg4|B%w;(x@Ptvlg5(UTk8i}$z<@7-C+K7_5Sysx* z=AATs$z966CZ6*(e$v(hgQBT0u4rkmSd_O8+lrV6did_{i;EFfaTMXKvsEKhCH#4q zoIq0HzoHhV+&pu}T4NIRfwr~fbpSGF2-2G%TgHzBIutL)``Vaoz)-8G$>9sW8qvir zqTd<$4JkIR4?i4DAQaHk+b4EIkIH+n!Hmjo!Vi7D(y2^)56l5KND4zB&;ks*L-LpA z`qugkp7`gWwRfO{yFl(tm#tVF1HJ@1%?FpBpA^wbn=N>8byE(xjFRHsrCV97V2Zld z!*_&Ao8JDo12~NntKaQuylBq$Mz0{>ucYmAji=B=F6{&ZZVn<-J=w#1AAA`6M*P$N zG}2C|sTSmj!hRn;TeVXl??5-ADgazhYcp-K^3jND=Gi zGxUf+i@vENQl<-!WZjh!j$baG+QO@uQMQe?wH zQomGfpq7#AtJ($+vkGKKA)ZnGYA}!KXP7KAs{=(Qm9oFa_8FDY_VXNY+8oc(zP18! z86??CXN{FZL~_AOTshENH=xyah9@}@*#pm%c9rI3fp zJF_?**$lsv`R2Q;_0(lq!6h66`F_mNzAKqLOU!X*OE(-HJU1#XoLmOlD@sjL5I z{Am@2F0|4Dab2L5-+IJL^tLpuvjl8oBNaO4tKMKN5K4kGSf%RYKHU{9zeG?FHl?0% zDpx99AS~0ww+||edEuj3mE1B#8Dr9!E{o2%rH`jJB|G1EJ~&^=Q376WW8tCiL448n zg2EQ%zB@QCrGm|O=d7#kTR z%(2E~2`H+xIntc5S|3W1&X53og(ohFG7{>GnE5VcJRSyiQ7nSzat11b11)xyHf3a* zc~iQ`{?2A3OT4+&!KKKtmSFy^0KS#>Pj3b-g}Z#TbUZ9xQKNkKQ3N3F?ay!C>b3pB z8MC&Z+)LM)-SfbDJd1d<2Oc!igj=ny54w$&G>lSQ2pc*RtrAuYBh?OytwJt(7b5D) zNY|=}av7jc0UX$dZd++cS`=+~pMnjZt}5wuVqQ8vPV8i4ZzLMybOZ-eVJ7?iMoej$ zn=Eq7$WxPB!Fn>#TWVd4AimJOWKe>vQdQmH_SX>mM4>pYh1b-`V*D z6X~b|yx-(bkr-J)*8~%}ysz~{ zGkWXof}I<&f>5u6bH#0GdXK746K9+)Y+x*`|LzOxD{};w=i?~<#(iDP0R@B4JoStX zVJN8NiB88L)_U6N=RIaW3?~5Q#L>sa>9`3F z%~6yY@^b*M>L2+j34p_ow=#o|GCimSBWazXp8&VVo&H305cd^*&yfT#7sCGH5^tNr z>;y@I7{|5e3S_LE7((`?hLy#8lDP5x_$kUx50X=bdS}KIm``s zuvS|8^9A{-P82k@VB*#>um(GB=d6Yt=}Sa;HzjQOP_i0oPQXK+jkA{iVfhpIevBHP%bMdHK09Kv!~H^%xX2=a5^cE0${ekMvn zTMGypZRzAccOGZr%}Wu|)U|G+UBi>VkY&5LIhr;!Wavnpe+Y@)VXDsE652YksGq(b zp@~3}W3Ej%S4L*zq)L7zb-`PyIzw$$KaWu zk5JkwdDOyUiO<|+J$jM_p+8t;#fxKoB?ju)adOjPn{(s>J z-%nUU2f>3Dt4|Ua!u{E)5ifEgaG8dumMU4!6Wp`DBjX_=EMVO;OtASW>KP$dvj_9sMro ziuhSJMON4xnND*>C!N7bRQIfnvf<2aDrZyl`#62&LFy}5N>PA#?6Mqr3O*<`! z3eiilCl2r=dEBlNRP*Dn`lO|3o0K^Y96nw3P{AM`hy;gzUikx8B0U!1JquIHa}xC4 zuGSJgt~&?DW!-T`Mu%(_)R$zP80%pfF)ZSI9fCYbpH9|xlVn+MLz4M-Jxt@A=8jaX zGmnuM9`GJRQSxitM}K_b!kB`y=jXGiN<1?E{oYUW8rIrdSmmziALts>o-gEZ-@XjzbI_#jjA@ko$GaSYCIpz1IJ9Y`~| zF;|#=kLf36k|u{-kG^JfNmxlzEX-!HwgFUwH>1$B!fbEus< zW-3&7wmCL%&}tAO%W9CoAXcC^gpB2{VaH5i7|FO?C5>eghnMoxkFUgw+!fD^{y+?9 zCt{36T1pSL`6fC@@gjgxAWB0xd@S_)0PDkm%41)f;z15u(j^BEaji*^>CeR7w@ z7Gl%J5Z7h%QIx!CuqE*hN=p3+-Fi?B!$=-@Rz(8Dq10~Zw*6|6XX8n%8Rh!*p1N9M zl=l*5^*Z<3Sz^gbd2pNu7Q4x^K~^W6p5;) zy9gxmvF^Yfles#jX+*@*US}$=Qrp)VAMD5Tqr)e%u6sSIb_6OebI@}zOt{&Y?S7|~ zHQ~ql21;$)S6bQbC%LtJU{P;Z-Ff~Bs_aRbfqm@l3#S!m;7!T+m~7`1+W_#J#OHI) zI41+%h*{qAlVw@a)jYH;^E&p&rEE{1E!GmIVQcoNk$#j3NP6N5p*gey0u=mdUy!aB zIUBVm?l+qhQ@l+ng?D>>A#33$TW>6+@-Sgkpl?rCN0C)A7|vl~;mKkMcgzE}B0=s9 zed)_dSfIR@XL8c)a-yK3LGrCgB(LX*#)YIox=<_Pnfb^}xtKjbvcSB>p)VL^N4VYP zW4gqB%_miJxq|SU<8K;(L7iP?WD@R|uzHbJD}ls6IvnFxGP^G8fkq za5MPsp!~%8@yS|iAmcdq3etss=Dz(nGeR;v!;|P$TLUgxCuJO|$$~Zu$#+!OmNp5q zX2Ennd)5pPM`oL-99aP%Iu~@h7xI#PDwBNQka&W(!Q&Ng`;e_VS+kPeDn2h2=%o% zOAYRaJn!>vZf&LxuEACT;Y*V)nJm~J{c8n*#VBb3*`~~fPv3v$3fgz_; zPv0EI>i>copX2~zyA`1B95wOD8v4J>wfBHDeg}98KY>euHPBF}isx@R!Z0Qj8cFK8(7kKRCMWBb1cz%B}Ye%qI_$a$Ugyjifq?GAYn6+M7i8pQ>43Pr0uN6n+Tjq1jWDCtD*JDH-qbKf0_ZMu%ok z&_AKSh?7CC!UXFDPB=fV$8H-4V0*B3%?usmnd*&tyznt4*gn#El+4_=v#!Qp8Q`o* z*hQ7`pht>n=_wi$%wE3NTo6P_7J}M`k!e?}bP!%3lH3DxhHmdK2*v0eHh{Jb#{vG= zz$;h?NhzzlsdS(s3Jb;DmZ-l(wU8(0@IKt)|K65h`|Rrjp&JN`eS~E`(bt{675Gv? z(1e4fNji~lmW8s#zF-EUS8pVq01e)@CF1mtXqz<%P$Q>O zR$VTac-CnyP;M4)AWtZ;i(&}w(Kg)FI~M*DdOu^n%KB;i6Rcfh`DZ5+FC1qB3-clR z5PA>D_iEw zR!j;}&b@rqV3hH!nLbsh4pL)&(+{E?y_Y{ z$}Dk$$VCV&+bOz~-&s=%bW5W4P5&_uTXCc&3BE!B2&U>_8|t~Xu!jS>=NpND$L2_6 zrd?>$h=BB8P&ULqw*jyy_fs(vsoaVS{K&jw`&N16b`O~Xdt8j$;_bP=jAEU?*YCbxdcRe&^l6bcShHR9sKv{J6?|1R#&zob+c+ja<2(Ce zmu<_1V!Qn=W;i#p@$>jFbTMBE|32`dS#N&oxf7UqBdn(DH*#LABt!b;cgr^UG%2a} z+Tq(E*sB^s1)qVMsoTloZoLv<6l8qGYWnYP{yeV-oyr6HFn+|e6JLpK)YdD95{KsC z0$K3nhLY0$bu~oA+Nin7z1fT-)M)BS%IRrBHe)}62+DmkexH9lYbecmO*mTUr=;FV z%<5pzS^#ETQsoR0`6@%jt^f7Ag%=M072T&7o})X@j05fuh_82R%68xe<*w1{Dg2hg zIx#Y3?7GwzKXpBQ(-N$l>-x4tx2vUm;f>3-fz)laiH%Wl zB8T5y?q7fDTo4&Vadz38wjJ792eVjc@YDfN1OIqR+Cn!*ew%5^L^JDDP=Xy4*~b z1~f7C-qg)W8MbuV6y}<^?G%x@{*yC=+_!%KCn(Js*J&nZJ29HiBk>9pO@zo^J#e4B zAz$Ur7L9$pcep4Y9`vUGgLS*W@b*T!7fDk}&8^Zg6kbNd=h7J9ecjuPc4QU$5%~F_ zXX}MjIHrMv%3n}VDlncB7i4Ywkd?MD=z6=;v$Zpr{aW3HdgQA#-*pAUpzpzR{g%0Y zb$uzs*p2Rf!Q#R){7vX$BlcgA0~)l7Re4W%N%veaq#EDnix}>H7nuPs`gOW;TtjNcZ0<@>1&I)@uq7U&~JCgvVuI z2!NnZqnwpi=&M-?j)F_Z7RyE1iGBrIZ5bbhdI(mf#V86j$@lXvvz|dWh1T}E;u1Y*Big& zl08T#%7lb*SjB60b>UQtf&g4ueLHm+G_yAf`e{3mEvtBpyAi&DFe_nxd8r`4xLvCwy{ zN|1u7s{Y&Ahe9Of&IQG6~#mP@z=%*nN~-)!QNvqP7=P+@K7X49g5o?o9= z?eS1U>Y$eG?B#DiYUnm_^CO8Gq{w%@i>2!~TMc+t6L{@-A+3rx;Wu)C|59@(a4qTw zX51nA%B*u@$ZJ=1bO+$PKl8)rJg}glm-JcCX~hNC>P%{ z+Ib&xb4R1z)^;IL$i~%nb2>mMXul)e18>mQ62@-W>lH+|)c+}+_f*^pjLvI^xH(wg zd#75H6cu{v>9w;TTI;5@XRxPI@ z87u7qR*6Mhb|P>e{>GIJp4Vu0O^4zf7#NI@lQSTMP22xBp8q(rZ^nKg|);MyKjIQxwm+18gX(XIKbLEX27S);2fK=UkN60k(~-T zn($qKM&A4=r00GXOY@K`p}Lx&^lbj<^cO@i@!>CM<-d8A-+H!md#TSuow$3Ar?Jy8 zN6xwr@^LYw!EfEtNp(IFh*O)+EFpZh$~3rm*^Oh{7T|FDTy^#IdlxmkCS1te&9TO= z_#y6tCr50TpVPrjHJkd?NkOwkL~pv>sgW1|{-O27Q4TfxLrwL@;OpO)2GR(RE{XSQ zH1mymH?Lh_E^Y+;=q^+un5C*t4|6JS;(@bt%rkpElbp=9+`O{w;MjPf+QZf6-Q^PP zzU+Y%(}lF1xj~zF^yF&e%c@0b85v4ra;GJ#PWOzxpZ3h$X&1YPJcpBDYY^cxJK!6h zvFk}5JiR2BKS=v^^WnNjPRT-H0FjUn94Guh1xI4=<&al!k;rFP!b4)Ej>29qCT04z zW!jrZBqk^SzO*=4P80*TAXu6{4~(X|m%$*G_mZxYYa6#v)iguYk@M%O&WK44A%)Wu zYavXazOZP%ExW_LHZ?s9>GiWzG1CuL-;dT6%TMdr^A1$PXem9hQ(0Q*K0da#oD&5H zOWwl$zC~Z#z=(4MNd9hpjl!fcLq|OVw(_hE4;FK$QWqbbKmUn6ACzRisbC(2*`hyp zd8TkbbTeMkoe=dFy?`NrfnAuYVu;u$`6As zShjlNpg(!kubXHEz3J8N``KO65r>99Ym5%8m&>+ZV2OB?{ezswS8dMk4(np2NZ@|f zcVv|FZn#*6hgykJ?S+^1^dc=2cGg{JEsNwhKWsAe_X+9id4AmxJJZ+U{ft{erSGAR zJst6aNES}s5I4(m#(d^`^1|aO$g>fUUpKgE@1I1>I)RGwRj}LmlSgvLpj%u}sRWd{ zZesQj*-$z&>aXbk7)n_EIfZ5q^$;8|o!X6)VEHWPXYS@|e^O<*YH5oT%Uc)N3r#kJ z|GZ%3TLN-RVnEYLq;vuU(w=F6w*xVD5r>{aW17A2I4kpm{MQ5 zd$Da9&P+B7_R8qGh-3OD+0S8p&D7iOi0^5If zrqA-H&!isTnnavOoAldBf*i?Jj-QgO$eP!4WE)@na%7dJu~6KO8`}PO9!y$UM`Cd36k0ags)#Zw}Qb{lq;h>uWW6WlrJRK=6Pmp zQ}<*HOqK07%J@i+>gp4<8ooI+95$tyzy6u zS*$ic)j5o{uX#vaH09zL$kjC1Qk65Stjj7Y*{78YXr^xaS;(Yp47{mH8blR7&chLY z$DrduI;r5A2_*Q;nU_FCftD)d#`3ay^PYDL^BHa9L74YmO)3~pPS!<31>g9W4l}>y zxAJ9h9p01ollU0h$LSOYrP70)hdhb?1$|8ern&FNlY-R0EEs3!KDit9p}Q}Y{#5xR z8ZMplyvuJf_Dgl%ruBEVe?fX%OaL~xUw%BV^lGfZ5tp_D2JpNMc2Q!!s>L>1Tu1V9 z;=?CBxL5P8j@_067DMm9MEEt32b{>Dd&`wE3T)MAZX|OaJ3J3PRS3dy zCVb$*z*qqH=fb|+^!^30S4jbL<0F8-`W-9~VMfnm{rEu(OhViDfYEC1A5Y+~ViF#9 z50-BL4uf~VoI-ZxSwsiSA1V}y#R~*&qW}ssrv^+6KoI;45Za4E5%zhdrvV40=O%}X zGE-sv1@}01J4#0$t<=K#21=R2S211er(0XBwtQcSGhRQo;AqDiZ1wi z<{UvU?f?%A80P&fX>5@mLHQ;9O-+v0VDtTh!tt3I zN)ffxY)8h1-o?uvGQ%3LSf5lpACJg%=eEHfFg#}`4^x6?;40EqH_LC%(CTb!Cigx^ zKelKmS$FSf5I^ONtLYI7YBgMYf-_4qzEh9%#5EBPo^nA5;2)ln#wEUbGU2l1s_T>K51!WG4XBdr zuSPN9O2?6zZ+}FYNdtF+gGUcx1M0O$a4J_0kyaQ9Y~81X@DXiicB&!D=&?K}Y5v2Gc~xNyQYy}?`Rld$XRvN9X)Tpa^}r3(6HZ$07K>C%lXhd`RT8=I zVFHjLO1{$67SSMve$AhBEG?nPLA}lKYzOhKVv! z1j+HyU)3Wk4Dk9`Lk;T*L0wBQrkTJGjdUzE@f)iYAj)W)WVe=}q0ft-ZQYw@BwSmdf*o31+rY|cHxC)qE>RxJ^45Uye9_bm< zFUHiDH{`(&M5Kp&yy4uTQh1{;&C53E+$s1?brOZ{m0qTsB-iZ8(X046yW(fVGRXqGM>hZ4Ba6*qy$eSofrkX_leX{Lg@p~p&|)P_-x z@#{hTGO5todIO7l1?ke>P*@xzgcW&9YU#;ED^dHrxbk%Z|FvG?)alT@%p>fk0<@~D z@5F_Q+r18;!D4AOv(XR2U~*y7cVjS!ZYFoFhy3rN*;CUmlT8Vv;wx|;U7lkyu725ZL84xTFV0wF{BR2+Um%Q7?UcRNG# zAInVGudDl&YFR3+y?Is`4o^LxtQPIh;qA?9|( z`HtUv6>~#%k9}E)CQ3IpXnnu!(L3|8f4yAF{bM!^U)Fr%VKJkN=j-J4=l53-M?bOR z_C`L?c&c-A4SMV?z=@folpfp4U+timbx73k)eC3!mDcmZ4m=O;wsA21fR9b**zs(G zLYtabs&3vkpO7;j9|?kqsk5!VTH(&~#EUMMY2w)n;Dcbv>#P6{q1IdhSdvB1+FW3$^atk;_OIyseilH((M#NMmV(x~DS*QN3sb z7JtcOpe{#b1Jqd1W<#WyQO9bMApOgNRD2vaju$TU=DN~O+#*(Q z`o>6h)Wz~GWR2l7+-dT6-o~g%%>!!J4pr354)s2-B6=LHC*o~ofNKza?TWK1DM!zqm9Y`83G5yHL?lG;{X433HVeS^wgV#~S0 zhE;n-as6X;(~ln#!liMvMARJ0!cCCrx(I8JyJMP$OIZVik7zQwF29XIE}f*&bev)< zB_XAe1I3Mo1;m1@5(!e7;ES{>@li&Q%TjZiU;%lE&~=6NcaiGpeWI@J(l>G^oq9Mk zl=R{kw)GhFp0g!tABpn){9p>6Tl`iLgEFqx<)Bhr;JGLkrfhw!furt214m}kFt2wS z)&CPYpPwk^Li*u6cdeDI=K_vL-nq)Nu2)&^*OW2iSpe(E%hmn79QD*ferr4^7a@~8 zksZDHV)8U>336NhtE-+lLtnp|h-qpU_H4}HbLDDFzJcliC08Q3L3PWvwQ!$_w zZ2^w#B^^tp_H!8!9%n1lc6O3QSigS}$k*TpJTDr@+v zPid~v2i2B<4=mf2sXBMaK3o z3LkWP^b2(}U{a)R`xmZq_ty7!(0k$ZTLAl9k?lXfsi+Ra$&VF)U+5!4y(k`1&pDFR zZmP%oW|-SjzWU}ph<$eq9=V*mlbd?31NNHim~tG{tg2Afc{)&qR9M-O>^S|L0-tT} zf04^4eE3o<9u*a26hEY*guZ2M&V7 zz30%St&0N)WfTW#=@A-Kx1y9^sK`aCh`yv{u*yT8Q5?htEi*_L4uWujZ-X?BG=Je~ zcrUCt%?9vZcZBL5Zt+KHu@%LpdsgR=VJRc#eyu!_@Ew;ir4rl*sNb+6RA1wPQ&~1| zI0cSF@Qkp3JpocE@X}gV%-)kEqD$Z-tsl|(>PZaDkk^lzA_Y`~)mB7JCv{WS*yKRt z9s1V~yD}BJgjQT~zc1hGz9zub43$XokAw**y_Gbr!;G+$|S7inLvL)+4d9l?IynC%f5$jz#jHG z|3#~p{{<^0+;N*eFN_7X1e>P%txhT3pKr#-(QL4>J-0X3>k0HXcr%$^hLhOa zoKpC)^9MmI^eeONZa=~MRm7!hO}hx?@816xu}A?f zuPK?_Jh>-%EQk`PQJUV0hK=t+T|GMji|8(r6;N}L(`1Ul&GS)3aXgSm!fXBIb7fjO zwEGSFF4q;x1kcoiBWRn=? zp=tyYMs;2)VYNQO4MSbFQR#Z91av%17?tTmunLDkU__-z5KpRf`-M) zjJ{})hQ1g02#xpy*L#8+q{=gR==$U_fks>!7f`q_Z`B&dhP5k$0;A20)KdL z?^OV;W3RhhF#k9bIb$``7Fk1+(E6+8nzCr1h!WA( z*lVzJpH;#9lxJZU4N# z1}hB%k+;VHseP}|mwvJW8%Z<|DtD=+n*EHnjOLI=_fee&y~O#FGYW_P<^ydu;q0Fx zuBd41d8EJ|ootXClX(Q^;TKp}SQDr^5^0 zkyB{Ie8PNGEtS$I)ppcZ4M#l#9uc?DT{W1)`fGL=%H$d<-!hQT?_W)DtF^KsH*;z5 zaqG#%5JpLTgIxg1M~#!h>fL^ZQw#~4!gO>l9zf8+JLOmr+i~B= zHeXBdsAXQFomh6@?PRjG&T`3_b!zc|aP%aD`;RtZhOtC>b5V$LY^*bdnBFBo(qV{9 zk|jq5u_5_7H^hGi!DCwN;!2)#ceYc_NyBik{*{Nt^pA>d+d6y72>;_(bJ%B5Y&R9_ z=(T@XlZqZZ5YiqKN2?w50h(19;7rq^{U6N&BG+G#Qh?r1$!wldJeoJsj5MG|k@pH> zqBz)tmK!4T+XEI5Z}(LOo*we3JQ|opdqyxsk#v5qUqjxm=@h zK3W7Y9}u%OMDv>yhRRSyj2z-?7Y24;Y~~i39KIRFZ_PU_OitLE6u~@CCWdAtYI2dz zSb4;sQ5+AXkyW7eF%DU#a!;{HDAD|H}D#rj-tT2gV;F$@K(u)v) zBR0~Ws%qk_$WXs#-56J!frc+Oc9x&MSjK9B^BzL`$_AYv=_wX4|DvvBug2Fe9vlb1 zc>r`NE1VWVy)AyB{OD7xbf%+xJAnao{hg&avjv&f)&0 zF%YSG8OI8o)cz@AT&XSy@i?^J%OAS=U>;9c_!zNciwu`1w~sH4NQjaWi_#?`T`q`#fV7~5AflvngRlq^BCv#X zOQ+H;NH@|-H`3k9`p$y)-rxHlh`VRbGf#Y;@64GqsDv9Dw=DJmtf)$oeX7d_gs#Ab zVJ_%PT|tiFze7y2tdbTeDa|iyP|Fx`zQ4RjJM2(#t$Z>3*_BnNE%dPs8T#pSAy34L zl79(~c~j8qfMG~*$1|Ki+2s^HQXb+OUB2xCAE)tOYcHVi6S8c<-Ru^IC9;KYas_Ns z`yahpN^Q}_*IitqGV&OAIt?(4RL$GMZjY~Z9nP>}`Jw9X9zLH&KJ zUK{YUg}oEwulEOOo6oC%nZWk?i97J-a7pHfBpfQOs00(=`YC@?>b-5_5#p5G4K?Rs zqWCD`C_hM;q&4DkyZONfZ)xQxV)IG6iq>c~ebph`@53xt6q6iO3+8VAp6J*YZ|4g^ z+0LDc&+Xh>Y70*s?TOkMm$V3p-3}moNs*JR&F*wY(jOHSjZ7G>&<~u@NYP??CUVeq z{;W@H7}Z(8U%pL+e#56(h{`Vc3Kc;LF^;W1iSMg8_mbqqU1FF&gk+$GoyxL3!!XD` zLPhPJs&$vGMotfeF@e3%{n=aDiIMeg%o|DGRnN_>!@jz!;$6w>iZWlk<7%XP8uVG7 z3aiKPag|640WqKIy}0WB>lg>5IF0;HZ)SugL@v;Yef*xSB&HX2Aa9R+MbKeJ8~-zW z(DKE6*-gJHNjmq5z;o<*T{c8b>%}Suj=D0=Gyg3D$nX8MBa2*RM)HmotJERh?}f?T zS1IfzuP{q7bStMFe?kmo@Kj={Z9=?7ePq0Rni>U1t+|=016{ApLz_6rtj~$#^Tah= z>|VtgURAL)v*}*W4=A`|@MZHmlIZo+YRBhQC2`^c8_Q-XyzQ?M9Btd0$Tea$_k61% zN6s&IrkPF<{U1a)Z|+1y{IFdMbi$lm{@{4Ei^h_^e`37VQ|8G@Y>~ID2vniX!et|1 zFZOjj$~C7QsxF#rcrut?{k(uE$dd4(VPZTF>(C*66GHDGOD^ki5mRqES1fz-{4zDx zAj95ZpxKqL_xM9@svBSt`1q=={DG|Iomxd^uT@;ZDSho{BZ@;#D;SvNkj%SYHsoS_ zkTRTNH-Sqg zp^OnCV>Tq&>lRlU968JnV~B6sd}onpHNLR=|MO)dRhbQ1oI&(O_? zz%}8^$H?B(TXZ)#@7tj@CZb*ma!c+B~uV;k?KF6dQ?N52#rkhE>T|b;KLAkYjN6IOT zR)mPn##2YlpTBED9A8=9Erf5VJ%049OdhED+}BR*NSXv-=Y2qlF4V~&+P3V z_STy>U@`ZHSeYmuAI!jtk6dN6OY=wx9CZ|CJ*rTmY^--l3P@4|)&kE@*a7^?1Vxe;h;uu3eD1`&U>A&qcT3uUZb9dL!{x>e(3UaN? z1jFnZZdDh7TcDS)k(c?4c{)=JCSeV|r7t|2?LF3d_phCEMvf#Tc)8z@q`hCnqDVN( z?06LH;P#Qisn777Pw%|Z&VEgjdYv!seSzL?@s&2R#d4k>YA^VL9GakXoMsM(FYeaK zn)AK1Q5FW=2F_Zez+yDq&-_#%lHY9Kj`PRle)1+CCPE^KDg7I`2Z zVX?J{dD|-BK={Zia|9z2FwMZhe=noSkm|nectu<2pUHWmlb7Yoy>Q6Qr^}v7_2^bW z?|yD@xM_GY8Zta6hsuA-n~5wge6)fR76umk!xKC{TCJ(& z*D4su*d#_EEouo~|tp8`{?GQQjJO<{gaC%~530W!Xl@|4fyH$p0g8Xr3f$YVGnni%%qBNfJ~Fm@_a3@e}K__ z+0^JYrA^_+`}uAI^ILc1T?uTL5wZDfxN+$lO_=z?3voV_D^!FQVmD}g1LTTrDjd}zFIb+tZherkCGIKMNL5u_0=0J*(1}WzI z0qsq=4jX38IIbRDF^N1LEM_U~(L<7NLQ%h}ugk@}cb`x2#4UUoQE*3X;)6qg^}E-+ zd4C{%ipK4%lkS={T|^2!aMzCkcn`WNJ!=DhxG)-37Lpk2lPoLHZ}I|Yi9Y+%BmF@^ zPN?__G4)N{1L(aAW@)0^h`BeWppD0zD&{{Y=6U!mk?}b@A5$@2#n1w$O zj(y+8w!k^@TURW=ZYXu3s#ZBkVQ5NW|4)o#wHJ&L5h_wGQnkF~!i;3kFc9Ru7T4zl z3%zAAuHaTl7#n;-=$m5sj4*Na^w?AC6&3nuhAEblC^RIzii7kz_DFVmaLltxuPIpe zbtNGKxo~ZzmDoHub=R9r=W|*}UfPBVw`EXZK`r?UOgqe<(2F{r!yEI&-Q87jJTimJ z?y%#h;1@lTQ7i|{^3aUqLBfDh21JOgGNT1Z(!BD4o;Y{dFvV3lRM|0qV6x>!owVn! za&$9dtKunTd~GO<bn+yB#>>q(&E#3{ zvM^Re9OTRFMzKZ3NU>MHUVHGn^IxH9@ZazZmOLiDV=KobTN*uGor$Q3+JG-t4D?Xz z(1sD2&C+W9ROX%{BGym_wex{Og`!g&XyVI9JObgTerZmO6@+lN^IkhG{!KgkcV2wG zY+osP#FerQbac%G-=H3vu#w;EZhjFqp{3?cBa3Utnv8N~??fEMIG&R9m2pnJm-SHz zYPvyGz)0J{a3tY>#t4WdUH6JQS>#Z5#HY#OR@+bsVe$RBoLhqIpE~E{Lv}@PZ>PAq zd*B!h@(0W5RX!{D%yp$fg3SGi>KM+g^zZxRLoP4($1Sc2dTKJhYsJejU{CB`JEtx+ zi~9u@U5KfU0I;B3bJKhqsL01%P@}JR^?2mLOBeG3b3+;p6^NM0AAVF+>Jhe=Y{@{w z1Qt|=fxi^LB7N1)?CHH$*)wg_u2bIw*fk}CG8^YR>oeObwqr$9uZ-%<&E%O6jr`+d zqHPgpYZHj9gN!S7UF{rlN%xI|*)mhxzt8x1lbCxrf&&HR!ID@HSZ`(cu*9=l{C+hvnF<0B4JzyhP%JPZoQF$?gH1;gs!y8_(eUgz}SGD95 z7nP3s#%gQ)V?NaNs5<+cCNpc(z=21q6|BNDp^(OMWe*s!&@1N{ddt{9kZ9LGkgelC zkU8^5QDY{gEwAkvlLCvqRZwEjyP+gV{$kwd)>DT7nD1kY(-Xfci6B&CR{l98zl|0HOg?QWXMW}JQ#P&g zlF|G-Wu~FxBO+t%cdvZ!kWlb?q-sY(7B5}YR61g%C{XvEX(8gGWi=x#H`v>Nfn|Ou zQb|zPn#IKL>F%N|+wb2EIe6HlAw;?e1wY{di?a-G3TjP)w{7%YAxX=D&g20pAyb=D zWP(E1Mb=rsXLXDR_z%@Br&ed(Qevn^cdqV1v*?#nD{F#N1rJMPtlzkO_G3Q(Rn)h8 zn9D*1UtWZ50sbO@l-a_q9T~z+t>_vW&W|A^l9(?@3{_prMV7`qVJlzJGYaE?o}8$h zE!H4eFM1)9b(bpJJ0*nHR~J0WIlW;V7?0dW&A99^K(A;QSi!O$`*KmR1W47cZvICm4bsF87IMnO>FhkXSGn3zJY9Nt`B{`vii=Q zp-35~^@yY~SC6%mZC!R% zajkgXKc|V^?JHiQ}76{^r(1M1ou?SVuJ6l-^&s)iVhV9m4Rah%PQu(8p z>@8p@Y!cLM;6lJS^uRl3zjfAxG+~jREmc(xDBS!;1A?OL9pl;)AqNoINdHL zURGm2X(LwRv^bWS5Lv~=@$%d7l^O6ogo>H18CnA~SZg*Us16MpQ$7&oMeu176q)x3 z$qDi!dL&sdt?o~sNxYuozQea_g@^9!sx22Izol9;RKz~0?BK)X{qYBamnslXmk)wr z0hkQ#`#5UHCG`aBRl^a2tBx6-UEll$oTaVfG30KG^iC) zWPP=VsG}y}YJeJQ&Ca&0#?42&3!A2XeiL>!`v=k(N+CYZb8?7wa}pFw0&@`_N&>i0 z{XDqY?DyB;eG?ZUhl#I(tdj%YQ*o?{yP3h9ah`Cq;@6@vd{X6u*Vv4WO4o$FHj6GT z5aUWuz!AjY;{kc6oVq9BD}&EvU(`NNq*;W|TFHIc%RgDynsU7rwImQO$kC8zBRBiV znQmDd-d78{LL_{L|C>h$@1gd$Z!YK*L~s-@8ufF&bR|$0tDu{o^l4CDt&K|3XOeCWTI7L9zS|o$hVL z=CINkMD~db<4CfH#p^dkJ%l%uEO<_QjW5sh@{*>#xF46jg zXMLh(5)cj8xjQ-G)e{I++a3sqo(?14qdS_P7VcI;&?eX1Dqo4-#M!7Vk_VdTh*UUy z90RV(caYx)%E@KcOurb*KiL#g=V)nd+O?#k&|krRTbbbNp%_PfEXcR_(X#-YwE0O? z13HlFV?hHnwv&ic-Z8gFa;I#ur6KfBSV#YXHlf0 zZWF&xwQIv&q~PAMabD~j(4}4`_&{HyU}c$!7a{NQfZ@yO$85`2U4GRs=W=c$UB06{ z_e)7B6Vas+T>c^jYX&%Sx@dHriGLv#;qAB!{`AA;{yc7Kgo@<1S5LzfDUXH?5ZP_y z1|1(!o?!pVHv=U5I}hau+aq;TCJE9d8rW7rttTu|&X!iN`O2G3+)d5e9iM$M8}sZy zo|DrccmpUdJ+(_e$#s7R$!*EDFRIKuJxF<_?-*rg`L}vJiq^`Oe`G}|0rv!Xu#H2@ zU#W^(@l(a8!=_S`9Y)U6A&r&HakFrja-m5Zs+`kncTF*-O$QT;4T>^pa6XdE3tk_Z`X^@;5+x|Xnfx&y_IYb$Cah&qE9!%PY5dXj> zFScK4OHB!ZpW``s_JQ%1qcc&?XTjaOA)Ja)MnAY3lFu<~0%|d4KSlGoEGs)g8w+j% zbHj=3+`fcade|D7<>*S3T0N1d{;CbxR2D(D?=#se{B~kAEggRi;L;fsAmJ=6*oX0V zrvrZ==40tBR9sVJ5(-Lt&^+?K{rq_{Ba}WUQ^2(BglhAs`!`m~>KkJU6_=jf=m9IF z=qyEc<&D3hcH4OcsLou1xGxNPgN^8(7n6Ak=MelFPoC(bMF8h#l5IG>14~|%eP{Pb zy(d(jySAUz*vua$Rl*W!&3}B4p(LgVJdGI4);A+K0~a0s@fMbK?4>84?ULF1eU5|N znD(p4f;GooiIS}lzIw~;QQ5jmMR$XnKl{X%-`L8Av|+JAI^$k2z37BcYY$PaIp z#iwTXgb%4!HeGTn^JNH~j_&2F{?ZdmdS?u7QpYI$=e5T~jy9qx2~?x250Gv9M*`SK z0YA=@#-43#)Bwo*1DO(DK5^G%q&3*v0nRZ!E2&pv>tXH8a*|r<)QY#&0CB@8fw(`> ze;t4h(SI5T=)ahm1TYgv(f6e?gy0t}0~@jTMg>{@mjy|+(gHgS_X-)}g!?89gstEy zn7jG(LcqJ-J{-(PY@D2G$}9BTa^)e7IbhaBvQZmbtjTK{QG}-}9;um7 zou2oq)JZM((kta$99LMMR(5uH0z zDf_UVKNp*3#T@hak}ta?R{i6R{^qzHbdHl{gD)@ff%A#1x6^k)DoFlxncguMrYsT2 z)4wo9Di`}o1?jGGiB_blC%o{!0XUijJx4mH*gPlgZK(sUGd?IdYu#V@;f&0_8s2>9 z_LkjlWZ>fmyv-lo_woQK){GAB?dRg^-st;f@)t1|tys-o*90eq$d66Ws-4_DtiAx; zlsochYt^+~b}E> zg>BMMSkqbas?)1l6{F#L@)mcwT-5GjNX|e69WV>^n&;W6-P{quYm){|7}W^k23k&st+DuQ zDyuJ9G0$bOsu&lo5^LO4DcL9FUrf+wgIRhGJO$W%gz9@4sH6>`(lkFoU<1qtNeZNH zjvLm*a5Pyh0%d$j`yM7wNA}42b2@d&# z*0`{LK2*+s=AzL!)_hY6r@dnP|UorGz zfci2mc)3%t;TgdB-_{>LS;LlGc-{=3;YN`?bLQ4BNUR(BDv*8>+_~IGhd7G_+Z*yT zTJmR-P-s5mI4mKvQz80Mi8#Ma?it+CIygS8r22@FH9lr^l?KVKjm4E8^>14sBi3CE zrp&eNyc}ed2e&}UoBPYvS@@vdCs+O@Tim7WL+26I)y63;lk=hDPlUp>H+GM}BW4lH z&*tN``_O4u$<#FSS4Ol-+$tZ@+=*+`+b>A&_5+mTgSmFy-t8{?o9#iGpDyt7rRxY| z#^1cnpX8VXJmT%8N}wSQ64CN1570Xh=uYMW%rhC4M=WTLM|uhtuitr0I2aUh-o5b~ zo;;Gn_bcz(NHjsijL%&#-?Z89)iCjE5U|aPW35j=q;quQBdZY`Y9!N;;Jq&G%BOU;j^xtD!j;Y>>O)+`ikSe;_>n%+$hnFo}PE86@wy%B|e{>y>W-v%9NHIG-?V z`_}FOS;a`XR&GQS;h;`erveK!fYBP;P0Koh#NyI!bLNN1j^vrY7pnX$%v_>wfAOPF zTbv1L4egwAjQ%fy$S-L_Pn_Z}`dXHPsTEu4n-kxiinZI7I|$09P-_rkBDITd_p;BJ zGYd$%T4PEpZlesgL_Tk0{DDje{F-CvLY-0`X1qm`1ZuQ1Cumq*RneUt=oSD{VzNnL z>&xOV(0xIX`8|47jE6g7jc$+wrI|xu^M6^YEMBqyV|;r!d^U#BuzqU(0J)lf$Z2^i zL^oi#8WH(bE?am(;~LYUZ95(JCi%N|LmLd}@rJ>fQ?%!IYwkrqhg+GM;;44M!Rt429Bnm>$#}^O{W?-WkW?;ZiaKWOpwZGZbFv9MljoK2b~?(GTBGM8)BY2?v7XyT zSPt`?`(kkANX?lLL5@*gZ&B|86xlQf05srH*4rspzbSnR&>5pn#|lrfA%+pvqNuaQ zyGYy6$=3;l!d;o0pn^_A@$;W?rxInkpa_I9^ zbN`Kq8)?PK4PVwq-UaQggS`$2vrG07xwG-|O}Y>yDXotRrdAObmO5ByTfD-Z0c(_| z>YEQjw83-&Jp>8@PfA+JtDa&6R{VJ9Bk3O>EUI^fYbodt#Fd3MIdghZDr5-rrMLD| zYGzhEtcf@6xvf<7ATZI1^f-=!ZTKB!n78N)7?3U`DW;S}XiyT%k#&n0@O{8K9Iq<0 zcGSY)aKR4W*V=l**Vfu|3;Muz5svA!0&E zdp9rgQ6D-VDaqd)>uwZY-+YdcEcS-)6KuZR#`6o8e7)0}uqv8cY5~qC0f<=XqAdkqq0PhCWJV)Rosy64L@-zr3Gig}3(TwBTD$sE#}) zsZX(Cm46jy^2!rzwS=W5-ed68(_`DiN?-#tX#RXSNBEHUO9*^3enH=%|dZ?MK1fvi??sWNFW zmtA|j-NPEq!TU70--n&{nyj#Z755#sdHJo)D16;W)%5oHU$%o2JIZs66(LirYP5n+ ziI=~|07o{9m;d^j1+S`-PW3UN#lbC4qy71bp&OI3{WR`oX%*$0fmG2)#%-{!u^g&Y zP$1Glxj<8SnZ!X|cl?sy>^K#50t7FG<}TjX?6*M3IQW~_K9i!0;w8&zL`{iMaVY0E z&p?7BPBj48quYJs%XU8?Po6v!yt>Sq-!{2Ye6|YZW1`}QP2og+Z$et2?^P3-$`{&X ztE6v{>d#Bs2jpFX+HyDm*ix|6mqk9bFynYw??_>TH-xNBcJt~&=lZ`^d7=-5gTrLB zXhZ+x-*j~S8FHOMU@b?P5EC9WKlZL>O%9Ms^O?rP5R(SttxZ0 zO!j=%Jr8VMygu#26cqf;XsZqDhdR~D0g>nkHCKLWY*=NuEgPj;#&|J5?G zk=g$w#pn)y=*|K3e0zHKv2^V}nhyf#DuREZ3e>cKY-9|YAJi_0i`;FXbxio%xV=58 zuQDk?#TK+s)Pe5z)$lgvq-4zJ0=4yKp`I&`n-&eW&ZkJSmRFuU9#I0K4F(GqyO61`fveJH$FFqq4OwX-~=CE^GDtH7n;#c~1V7J!E(xH9Pl=ax<%9Rm%j??0^xahn$2 z_7Bzi!MclJyMMbX8NH#T0jdH^ohyjwYj)zZ-{J9R-{Q@$UIhR->$9OY`}38rRpOb3 z;|-!=jb{&O}5@5KnRPk4wTA z5C3M*UxO*WZ+Y@D?5PR2F~@ZgG06%_M10p}2Y*p3Wwc4a2k_8L`>^^Ao7$VryUOtS zS@>~aVnGU+hMyNaHfM%Y3f(*Vt0Qar+Ww%Ecy)*SjtCW~1MkqID2#P}Z4Jk+H;KWq z4L8OM`2%TM(e5AD4T5K0P$gP%X1a!j22&3wwEnEnRAs*NW}|Sa!a}=3c2Q-k4eSNf z^gokeHaVkfop1I00a#&R#BwHliRMeW+{XY-AYMw2P1Z@}A9!E;7qPuqucJFTV5n>0 z|Jy`?u(pD2qorK@z)P(OsD25zK|cU|`$E6XNYNV~iW@j>CDL8rt>N9x!h9iENrjE9 zYlFSZPew<=Ki*qFM_SMg)XPbFu`YxBRCYZPBS-Hsn1W5cJB|`<={WI?J>E+Q| zttNOV?ECuoS<^bd#&T82_%4LYhYga$zjjvLWu{@@cl zH6Mb%Zidr|vi$Hr4ZZ2!8~E~HDYL{qL*_bnH>Cx0y8nV*K`6Ysffzsc{zFET0pmq3 zXT$6k(h7aV6f)&#_y?lYwzg}>;Zg0ex$HNl8UH0>nHWAP=6dRQIsylc`oHTJl7S3% zcjmF-pnT6tUZ>`&8T;EF-;fG#pFh8Ox$aj=RIqt{Zj(Rxb2s_d>8+hpl%tM2Q$=Wc z1!*2}GN+w{935Nb`W1n=d&T1uob2tlXD~_5_nv+m&zSy7S-#uGibQhxEWtJ)wdaz3 zBPHVh=28S&GQ4b$WxDd7SrU{+6_;8bF)Mm$e)G4KWI|)2*)BtEBtxPr*xwbWEZsF($p~Gg+wXk2g(vEz zEB3`TWh;W8`Bljnt6r#nLb$(8_$-enZ89R4#1^IL=p-=lW# zHl-4PPipy$^*)%?15f!J$XGV5wZZzPV)Xobid*mZT=0jIw!d11uXugQ;~n}UAX>uw zdPyq3XB((UCcSYElczk2ywEK1!v2|&V^vCi$}^VViA6owv9t7sU(ac*p@?NQ6*7u$ z3SBYZK909LKAXf7H}fu+t}gTn@f-1uY|%wjh^gTIz~m%DNB!U{D3hg!i8eZCVa@jdiEsR*r_bCS) zJiy7do*YF(#(S9ONen{Q?AynB2I;mX_PiY5QqRIk%=O7@M#_G@3KY|=<+~zS*rF+> zjH^6%Jf8%iS{6h!L8<7gds0s)717GWXOn(Unq$AlBXw{0GY=`F+hPgf_Vf@5xNom0 zGM^Y<_%S}L2uU}GAT~b|#R*+rs>O}W^C+G9BV zO4lN{J*qEXCRRZ5w0hDcTkgGfy47oJ!zas&OgH+lBlT!!)V_9pW9WC-;A{|88Xh?j zNR)ctU;O9+)3aX8c`L}P_L)s1Z^;&$g;9g~KC-U7<6Kv+LTyX#hKdhqZ}A9}bs0kK znrA}BEfSu~sfT%IEDm0`frN#?bux;$_F+C0wjDX@1%Jpp^A z?NPrk0v}^*#paY`pF0ulwumD>-P`Mc^AKMVpGoj`3+&oft|9*DXrFcLcZ~1IL`vpL zRmvJFbQi{OD?s9u9>P+=#ZO%-cI-H5(Omu^UAO#9(_0pE)~QH;o|Q^W%3~r#?wR|i z*rn5t!BCBwfaJ1O+wK*Cp{f^5*qadV_ZpE~S3^>e=xawCGu$oN<;g%uVBb2{u?}V!xsVFB8Co&7&_G zXRra>`R{$ci_GB|JuFNG#c~ux*3d|WPU6Jcb^VFg)kU9Xh!;*VBm>@nH+yyO7Ad;; ztw8DUQjR2Yc&x^j^vReW3AR!F&O^Bmk8haIFO-+nBzJr~K1yhx{0Tbbl_w!N+0YZu zDzrJ@MP}zg$DaOy?48-7*AD*oXUNk6OM(%>DBZKjo`Sd!RB+dNU-%78O0}U^uQh8b zfjWJi-oi+Cs4$>jSZl^!WXzz&C_6HL=!r7ONsFnI z*=RdQ^25!|0Y_b2?-n_qta<-1knEOs;b+I-uuC3vGKm0u(1a3@)Ee&6^%|G)~l2gYBMQe60etl<&jFQsumC z_~j*=a#tBM4%&f8l9?^*$!XVOJ9GZ*v=1MwL*;%LE(3FoHb;T3)@kJS_Um=OO^>Bj z0iq?^cRopG5`H01Y5N1K&e7j?&~|=qy^}>`poVtQt78Zxc;_7$ z`Jl?p%(Tmi+aI7dR$D&yoKhCj?d-2OD`-EL*0Kw6)0&FSF;KGbzgcMo3{^J1Jj_r1G%>b$3Y-}VQJkvvKO?MBFC^k)i!v9ywOv%Xf>M0eB}@VJYdK#w0G&3Mz2GV(@+ z+#<`mLlqrGYu{-4$GF`7j2c7-UI(byvzfQc6fJGJ3mUsfo7m?iNQw?~z})(n(tVXZ9HykD;_F5etS!#E&GVfKqXs8 zsbpiY_KlG2oV34wvnsCjtlX>?tn>>2MC-Hl{__kEU^sjDw6PcSU>R<)v0RXnCC?4X zNm}>=v76CqgA~}hd2)Q(ibv4u!4&LDgcU5K+|Q%F_m-FHlHnBO6~ZvTNW{`SZ%dtNbO zJ!99nB&X5DSi}%m!gM4=O1)mV+!$2L@<3Yx+O=8C+?;H5 zCxNcJLx*FV85Xx*)r7q}>tdwPIt|2C%_!(A6-=)xs)@RqblAt+1U;kzBL(=zTs!pH zE?jRSE$6$I9e&C~-Y%v)^gspPPDoW2{Zk*vu5AREs-6f~0G94r#r$u4Vl)Qwwg zp8gf{CqHma6pE}}CCVRK?+Q)HQfr<1e9vL69NPGK9TmF(f!lRBqNE#3nOm03iAn^2SS%_!fwJnhWD0le~uQ`i0fIcaz)Vyy`Y;bh z{&Q8s^_^$mHJSjC1xw?Vt#?}qSOqinS6$rIwhN{z3cI+}#wKTDiuuIa9XL zZbRDK?lb+MeRs?YIl(F3rz!$&?3fOeME{}lF*O8<7MVMh$ z?-i@;wtt|wSe~AXXX}=7)!^qFu`Dm8x7)0)e*He?I!{aQiYIv1bZUC+{CbW^kUVPc z3gOeN-l==K7yav?x{h)!#Q8WO{L-f@aHCKhT?C+ zuYI843$7gZq87dc7+dmDm#r2Ja}-CV1!uIPq7C<)X?jB_yNJ~lJT7IDOwM?~FD3-h z&Roqi7>w7=Lu1wJU=3OZ+Xxp8wVfy4u+r{eoR}~#JuGjP?t53?g$?0%Q1{pg`pt<| z-Wqb$W{i6JX;P;OopM5F%WR3ODRMY zlXz9->xe(Azyd{a?boX6S|_d}`?u4);*oecM*`7Y;Yy71OhKD%%rOgb#f~0wR6^*8 z8U+6SH}T&5tk4*w`DNp|bk=wwd}}4oWB|HsJ;#9 zsRy4Plq5HE*$1UKdLCt91^YKC00=rZfB!VE{H8908Hwy(<(8}jfunyStw3-KR1ZH+uJ&O&F8-IEv9@6l{X>0=nZ3MLOv z*gMLAOqt%VmA8bfzGgLdc-WDFhumz7$@%syvwf{RyQ zC1NP{5rJ65IvXinWJ;xz>lHq+D!aBwZHN!+bulG}807 z6*_G_YtTH*c0eaH!7(`z#R|DX!cs0!r?A?1)q{hx>g`Y2v*_!zu_W8eKZx001YI&n zW$Z^ZgKVjyZ~=v^Lia8i0oeL7xgiA}aLkVdxq~^rD4ZALLj0He{oY0K5A*6y0k10L z4up@vqfe~zqwoakY_s*pf0ySSRv|kkGg!Mt#_nr^>TWn(M)DWp(g~P#$#1atn9@B} zy(HRWGk?vY`sLGQz?i9I_yt|eZ9a}hYvPP2Bd)`aJSTr3Xb$l!-zd8}ef(f+QOJJl z?1`anw+QXc$E2Ne(d5==x@huP1AYNckrwcH=unUTL;*_R0Vnq(j)q}J#=h}F*w#u` zVO}=k(#V;i6pI@7eXLn91b0hKeor74h7*Jf>V(w4#f_Ze*2Gl#cR$cuAQypUn)@Fn z{$qW4@|OkV7H10JWVOrk8hr-x?%$u|CAHM0uwRkt#({R;^qH>tZwx1TrFOb>EN{;= z@;Ct{Nr$=%JC^O!>CY)%07z$z0hbsWKvb6183z#>bVFKJ7;!Pocn7`9qIt=U^|>iAOf8Zlsdk z6Ka7)=UH&T9O$U;|M$oJAGe>wRNYx$zq+BTAlP%&!S)<~-CRlT@wMBNW4v*lD%H!m z$(vu-;fY!xhX0Pme9}LFr+}rad+))7{Eezx{`>d$F=CI^UsecUITLcagEOU>Kl%IZ z5&!Nx()|H6wC=n;yWslz5ajV;y-ugZ>1Epy#B%H z_9H4}G0!ez(P3_7n|U2>Nw(w(<-JE)TZ~1wawkgkCR#@+grcEr-J!9>3rF;6(|hTR zjQpvA3Enc#ZbtrrxL=xbuztf8c8(N~E_!V}`wf#@Uf$}XgU>Q_i)0S^rB2#0Oa6_w zCMS1|$FHKNNpocW4^qyt$+)HVM8BCQ`vikTYjAR)4B22zbt&7i`ar0fj0%|UlB1_)u$HQB# zt0(D<{mX#>&5YmW=%W`@!D{iZ6zsTxXHQ)*(j=IqBVmaBY`KAgw%qB)@$gjx8(oHT zDUd*k9E7W*#*D_@$zVgCX)BV{krH(ahbj5iXXR)8Upp&?=sC0t%Q&6Kj`#{)@w$Z> zhv*L|4Lehii_8Y_Bfhd+=>1c%R#c=A9U$!rtc?6)U-S(0f1gZpcQ zi{$ldU2I&gba5?Px=td^zd_#H0UBk@FgTOB3$2}aJNMtGaq(BF8%j-9 ztr*g}S2VFH((M8{K;a3m?N&S>zIN>o#K=Xu0T=_iMUU^$Lxl{efporK1#mKNt0uo>phhe++NMEjPR_;h(q`iUQKN4SN6>!s5}af znY`QX=7)R9b=^i*!KPk8wbUjwJZUU)?x#7Xt{&;XPD-UGH3>s(NkMQ#PUNxozIPT9 z+g!=+bVCJandw6Y?i5yZs+iOoP0vw z$Zo~L3a3`-#*DDK-7jpPC~j}DmsQO}Wvq@eb=BzhwTSf~_hCuRu@X_sVr$XMk$%OD ziSd9f>U55#Ti(8HtPJ1W+!kJ74Z0{c(UX-AWehnGJy4Q8{ULvoY0oRQ$lLP?c8F~y zE^WfA!1isA^RL^RX|w0f&u)4&Z!I$+9LpMKrPP%nXK9=Xp>6MihR=l>-KHXQzvrw~ zA7n(untneVSMI#hj`8d(mKk^xYQ*5ThxhuIby`M$9uz##0%r$Xd?4Jt+bMI)sPgv0 zzR1Gz=?GzoJby4#F<%XBlu@`v%8tQ@rQupNxa(_sekTOOGw=3>d)Wjuv_`_cVkYE) zj!M!fxD_whuArpD_u8CS3toBvY7@F(WEM(GtTtCrMvw9~daiyTKDqBRI2A)?xxrM) zREWuQK`}j#kJQFn4NI_1{9}Un+)1QPlLwOR3k?(=wApg0@k|E468BKC-%`COs+W`i z(PHJ-MEtLgk^672kI6Y#uyXn)y0@oR#`@YMR}bJAL`q(@y}6L#a=dC1jd1-)cdyGK zeHPe!bnLe}e{HObpQ0!^OuSLMe#{7D01jMfxF-U?xJZLMjuv2y^_I}F19`kweVHT4 zrCO7T0GtNy84y$oLFtS+{C|d$Sz0x;#rjNr_id8=JzB8NxKD;3()mMAOgvwG>Q?nr zI{%a-{^$xzN1m(2WHd%W^yKiisY3m=r&NmWx>e1X{zud#0Oc1}Zx-xEeRW~-Chmk^nf}`(J47w~+Isa6wK~k;2 zlJl&;!UTW)STzEP>N{>Xt-P_~C1dICB*)uQ1fTMRMXh#QDOu^Q3Wb`M`)t^|meeSy z!~o?a?SM!-7(GYmoW}2`W~)XfVSX~~NIW`<#$e@wY><4>qKCl4*hLGc7N=t&E#WnB ztdn7q4NFB7d=n6HL6_x&BhZPl1y5*CGXq7Xt-W zJ2!vHk)892)*%l|a|onA=*6{K^RmGz+QrX5?hU1F(9>5$Km}?GXxwJMHi2Pw^6G-8 z?ZA5(Jgi3Tqjuj8{iB+g00*T0e#skNoC9X$ zVp%ynttM=ruBvJ?gUr^GBJ=nz;RcY?ED%>lemI&fRJmWxt9mSCvFK+aB8Q@YBK9&n z@7^`L>p^7t{5jaYcTb9YvH@(~Z|W8&1umh7%J(`fZ6Y4p{I-LgqK5w> zEoh$60-N)>=Quj$6Fs_Npquu2N|*iGBUgiyrODBim5nE&T8SYQ&e#how)~-w1lwzR zZC52)C`Ty|BR0+)wrGg@D??|8_8H@Fjcw%sovHt$eE?qFIynQH&rL{#$`DhriL8O( zm|FQW-87Ql9z^olW_j1SC(~l{Ghm$apJ0>L(#X|{OV+y>mTuALmjYHmE{#oZ!o(6T zl@r1KwhYTv+)XyE!&cOsE;TWhtG|QES;233qVeVZuA^=I1IN4qXX-Y^5!)-D^835+ z8WbJ7KX{kP?nQ@Agr)Hfx_jYWkP1O1{OhS;i;3 zy*VZ#CMF)56xUYXat*(6Ya(fW$Q|W?$-B}O$>8J7@qK9PUjb^co-zJHs7kr22q)Sm zHJAEGjMGVy2%myB!wlTK*Hof@J@m>i-#B6kT2!ehI^_SJ1DxUlBXTy%CLatRF?W51 zxzcU|wFHtXV--8DPLuzI*?ZxjJY3ojw$2MnJ-4{0*rUKsXs0*93B;0@;8{|}xJS># z-*h%r=3(l(N1QEQt3T@Z)HpEMM&=}sJ#7F=!i5WLZE$X(6}U5gNQdRC_n5K^Fvp=q zmHBfHjxvfb@EfnKmX2_WNrrBgoCDeR&LY@@evi(7XO#_$M?j)(qowen-CO@HM#4M~ zskw}}dG(67^0vZ#3@840zwLWu1!#cX+a~5wV>clQ0>R5u8Wy~pDd5HJ;H(3`xyHH4 zx2;P3^x>%!SvzF)V?uz#FH|ct!;vy!+EV8dp9yOwXtsnYX6`uHXDmsFkkP`9t1Pz} z&lciKgCTc<{p5!Bp#@q(!KG~k0Y(xJpt0WyKsU%^{+^cL4XKs(V%XcV-L#Kq0SzQ= zRY>zHS=L=SW9sT8 zs(QYoI9>#ftNVdkAvu#f{^o;llcupwSGsp4BZ`f?rh8rR99J~iJWBEB`uyFM7c8_C693Dw9L# zB(#79dufDDC|2i6VU64pQP>|yT_5Xs)^4r_*IxU8;ypeg_1EOj!cBW9Fbzs7j)3-G z{}ILSkyu|(d5$#L$u|Am#B?SWarp-wH_s2tsns=!w~D3rgl(f?lLl^9iJ2`6a8q+a zqhh>8tgXlJ>iVH!4;76F)iAryY>YH7eebW5>>Q=zBr2~eHWo=QG?`J7J}3_2sag(q zkLx=FqNFF!*>U~6DglQ#$Z{s|EwH8ze~L6c6N9_)oSlNd7)SHtbdiq9bG^IPsvQEE z5`iU}J=YDsKk-YNpNJ2!?|=OZbe-7U`RMcs8*Z36i}f)o67Eztr-76^Pa7ZnlJWXg zL|iDVU{5l*t8;^$wDq3ztaICtNjOqte@ATfl#TX0yvGeFOyZuTM_2 zSrbHs%Mzqb41A@jCXf4-K34ZVprGPfj-mgj{pIljBSqR0g#mf~$LsP;owdomrL|JF zWU_P|!zDN|W8JV2>7)3)`R#nsYaOU=Fq8f$;CRRVhbAbb!O;P{HKm6-6G&FZ@GTi| z)09ZFm&M`QS^}oUZCFQnC;s}p_R6u%4K6qQ0?;vEtt%sFBnyK)t?3Ger~L< zHJGJ6I_O*0Hh6t8a$vffuZsD@ONy9^I{2GpygrS=ko*29)R*JIn>{uyZ1eFX3lk8=S&>89aiEku-x$P8HGPv z-pzQ`_9u3>Zogh<1w#ww-GC_A&z<*8cu)7d{% zl15x@rsm?V#5*WL^?)qRDDgR>ZAsS<#c(X$E%2W6t4Lo^+c=D+x0u4}qN`|AgX`aY zfw!*Z(VoDeU8N&hbcV`}nX2(Wx0eGY>#YqeW`4nsPKqlJ%^xCbR1<~RrVg5=ap{ng zYe!|G69WPoNh)d80rcF2)t>=D9YU8hM8eNm4;P5h4v_b+YiJjEGVZ?qGN8z2YgAvT z1M4K)X{X^(>=*q};ZwFS-M>SSNy;O2zn6N1uDIvE1-4(EDzD|ch{|f&qNt<9;qT`P z+4M+1%`;z?_-6OtJ!a9LD++Ox`mP{tGwdF*_EebNI+9HMYA#Cp(bDEWPtt^Z8xTWa@XuD#n_?{?s zF|V`-UKvt*z3Noz0qrZb;(NrQC|aEzA=?tvwiro!B7(sVTFFh{S9(50TNBx1p4p;&{f!4y8_1EvwfP#3T}Muf1<_Y;e#&r> zdP4*;v+|$Kz5Co9i$)34xIU-dLgX=v=tznuh{eH@ffsbQN+oh$-drmj*HREe@1`<) zYhDAJ=TCJnuiHPhe8A#&Zk-fiq9h&hLt1p)Cf%Mk+X;%6OY;q*Ankcp3*+bRB^qAe zZq~*slx>gK29}Pbuwl=G;0j~St9t@xp9}$}4G%@Zxxj=dY1J7{A@b6EQqV?~= z^X9m_&r3ILnmva?4PZmm+V5O%{yWL|TM>hD)P=FR_OpugQi;TV?UL-}D_p$x=I4vrRI7p3 zf82GZbFWy=K6Pssx!$%5#6bit;O9%KvZWpYk^~8q0xc3jdb+h7D=qy3&0AsGzZ4%y zBJ((ITd>CzIGtVrti>9@--3@C;gV&O5pmbkJqbh5WuThMYHZ=>zrnOX6K_=(6k^9Re}EP5k>4)0*p7v>MJ|DJ+2nJ7&y!PpJK`e&2iG3ZVSN=*NO=wAvR z=Fjga&sgBXbuA*DD~VHoARlN!5#)8-y3X+WZyKMw#73H=4gz{gN}St+f(*RZ2eUYI zUo}NA+!pIuJHkx}(Ymz*iv&}Q8Jj=_OZK#f<+?Ic)-_Df!?p|PEo83^{S+J>2;BhN z+#<9GIIOYqCLL7rEgVW^_Pm0xI9A>NA-L`~7NZ9)G0KR%f&kx;-h4~SmqcWFdr)kfB!xn&;qAVYv;KeZ8st^LW z54fwGm1%Nk;aq&tT33im&cY-HDSQYWtg_C3X4J%=E_$<8gZJvDvt;rMXga8f0kHIv ziTFSk@XJg;%y6B2^(gV-0$9iWn2;dR4>bj4B`#^u`Wz%YFVL3rbi%+$Q^IazOtny9 z%E#+ov_m3!vS;JT+CJX{)SHhcv%GM#*xpES8{LNjCx$5dJ zdm=k>C zG%JMyJ7(yn@IHl=n(Qxarov~bGL!6bB&&u}&$qdQ<54hHzt=OxiiN5KAwmQ!=svqb z4GL4*$d;c!4D&%m}o?W(KK8TLGW7{r?bMD zL7o)iOQechOeGIN58MhEI7P+jt%8H6G4Y3VMbFk{AF;|hWRyWYH3mVjghl;$4NOdY zBr`?^J9X4i^yODntLy!MV1mQCQeAAs@&-uvxP^}hSg180@jmm)R%L7b5JOY-Ayf=7b}Ss#+vX+_CS{oz2a*K3rQ0P(3eSX+OH&GliBE*#fwM6$QkvQI>t*n@=! zsHZD)R(p;?M`ad!GHEw*8j|ltG}773br48zO~2REWhuPU4XwyYum{yfYN|7pvq<9H6Q%FkRlk z3Gf)fjoMfNiCn(y`hKO=M-53qDE**!ahqr!6R*`XyF0S#PNGb&W@v?LLv6M$rY!$p zQNK7$@fytwyF?GbVnco6Y3CEy`hSH@zwBLRlf8SZ zYb>Ed;5~>&S;JeFKNTD>NBU%g5$M2-LHepTsIF+!4z|P;#A5ts4%D;LxuzIlAX>%cgX?(l4%j8$+%O19Yht_MSKfxp{ z1vK}14a@DhsPl9-JoBqj6>9S!e3Csezku!M?h~_{2XDqLq6*}H_#Ei)(cX|PRuB;G zzDij2C}<_Z7ZBO{EsJfHO~XmKrTu4s>$3HAukCm(pHE=eF2l+$RNI7hqQHu=>XK>! zD+w|gyz*~=HH3z)ivTM{%}wPqo2&&}HH(a?m6<>P?nBb^hoAliZzE3yYFQszk zb`^Cb`<;3((`Zt^)(zqOj|lZCmaR+`AJS(Ugrj)%@F{_C`rF6UV*zj_>|cM6;vG|Z z+-CL+4U`B=0PgGTCaCLn2@6E4ttu}&yRZ7Jkqzid;EF;{cZ-OTm~oU`AG_dy=q{kN z@ES7|{Z!DU(ijCizDMlW1iH_9E(eWs+T=f8u2f*gsLGLD-aOu>kA~aN(w>x_=si6- zJ2SawlrUr(!y=7 zob`ct-aS9hzvlQ~Y!PqJD0H(Ox_!Zixx8G$zNX`w1|Akf4H~3B$W3fDEF+u0`#qc2x`WDv>&X9DETS;`FNi~v7dmjfuz1OIE-$8KeY)tG zd$^QgFF}y~aBXS5^r7g{A)k15PGQ3FEWTOnKqS!y;WJ#&U-!_yjpEHThwXM;M4`5*{K7|1DI?Q5x8{DvBi9Yj%aO$1Jq5vf z=X7YqfL;W#;)0eTlJst$BMa}o{YH0GlAOznQFknN#0j@?!1;!BSBs?`T7hOCmuPGp zNU_S^dwWOaicP%PQHj^xiPK8c#jL)Qv(>qyvGy$V^;?A~{-&rdS*S8P&_Vo;6#2@R9SgG;}i6#euI3&5Uxb z+951#pk2;J@>li;yWbo|^xQ==qXPT0M(o*UuqpANcg_vO&HA(Bu zA~!*4mZnI#X*~~Y)0_<*x(^P4%;T!$PrDP&Xcqe3vgg85MjE2vt1nzmpXao@c66#+ z;ZC%J1!_Lw7dc;k?+v#7zJcQF9?^H>d7|YxavG)_AMjDGcjs64hT#mGfnQNMk8NUA z2kpGn-J1gMHKSAtK2&6qMiG<(nK! z9jjw^U^El3PV^Jn_1@iB_grSGEcn_R)XBNjWbMJWP92YJ=g<}$wpLe(!sa|3g;{|; zB4XvR-}hi$HQ>5Rwm{eUz@h=auUDi3wv}snlRq94B5T)evO?aQD%FQjQP+N z7BxaFIvR?P$@*q~@rSN|dnmsWc#Xv@W@ErGQ$I{SmE|#upxjfxtO+_w@!z?1(^&^nasd`JVHlI)77w{&P*g2n7tC- zT0M>@sIM?Myat>QeFY}-!pPz3s5|^f|3Tfk6m#ep4+pp3fmI=9(|7JJV@0))Ne+UD zKv=U#O4B0yBaxQzhC0ETS`&urA^{U^BpSnGtm*tRLg&iK(4*gNOY+DhP6R?9+>wQT zvs%`KEi2d-RPz9A=?H@&@KyJ6&$&(Dr|5UbgLh{~xydeCUrTDMF$bSWg(9v17E$yS z+pc9TJlKAm#8$=3Q^6mUxCY(XGx|YRUiJr)JFBO+hRXzQt_%MI5!ml!csB;JWR~(^ zS&AQadcF3wB6x5=+8Q7ZxXS#d*&S4%TO9&-fNCOapw+;A(eD8*Dbb3@a69KWf$!RY z9iaFqzNQC3QP}iP96m1jw28Ye?JQNe7`3|d6q{feQv3dzgys{g$q0_+-La|ztq+Dy z1{6XOC-ndbf1&tPSC63Sv;xJ5bzBol^R|QeZ{UR_2pd=pJswJ&9UQcWb`@)cVw)Iq zsPTY9T|XYdB5c3g>>F7psywLwjwPxz@4bY*^Tch(E^XJ~%xU*9LSbtE(=CtV880M$ zzG)2Ju~FN>o)u{6HBgq(QaSVJIP>&+=8{$$rIODW8Q6RMVm{EMP zDMHy(VthpUU$o^Ej*n(t||CfZst%b%U+af9lHMZo8w-)(4Y`m&(pKXKada( zGrPC$Ed`x*`+swjgZXnd@kB`+u%*RILt3N0#-aS|LCwPlAT{`Xrq|**du{t$I@5CP zyWkBsTR2Tl6GHnt|G}19djCg!+-WluNQ1uFBxJ?uPUiqm;=E;YdK1K&$3~f# zhG9nW4k&bQ#g@vTEI#DE)PTK!z1h_&dQV9^&4YFT6pkz~o%sNmDYsy!WVFCpy1*5v ztM8Hw+*g(|I!C&u@B8Gj-aosMlBxcCUm@f`IpceI)Pj`o>MiJJ6=&bl)Y4|peExKo zRoM^?{tpg)&1W~HU%MjLw5f!HwrOpvjLnI_mxMx@Iu)A4CBvNk!_ zL%I8zi@eOHQj`G)R+S8M%PS7aT{+LIQqrVGZ1&yd8=oLP<7|SA{VtiKWm3g92bqay zIAFI?L=F5KPAIE1zbcCuJzw!`gre#iDnk=t_hjgith(5IwhdVm1r>wNbD9o8#INp8 zblIKaB5!k?H&{!Ff(7nJy13GGy3hySs;{zBG&J>l%0d1zW9vIAomJ#qTot};cj=)+ z8h^KhoYN(C#H4LK%SoCD^%{=xhR)7S&QWbk3cPUWT5Az48j7?OF?#t3l3WV^ zK%OMF+X9SG>|(6_w0j&3fTxNkyyuo;YS@e6@S=kx&cn6aCl#j3>hY-EqY}*pW#{vJ z*Y5FASJwEgO1)Yi!hv`-us_2}1Mi4&Zt`)`t-UpYE8WPn%nc)WbVhCJrdM~LBeI@& zcT9PUcA?DpbNI-hxTf9qG01yD6O6`=?l3bRaHi-)$UL@gdwE7OrOVT(-l#rEU8oFO z#2K$ps!@Po*~*YyqdbOayLe&IJTPcym!nECT3iu+F*cyqvls1ap^g~PQ^ZgEsYDMh zc(ee0Sake8in;#fx_2n=wx2aUzOzzQ2C`G*oojmcv3qO5Uu4R*%D<+En)P^43UMK@ zwD=OWyTwYU96R{@pn@ZYec18oZO3Qpc;zB$AAS0(cQBd2P7QZy5N)>h)P?aF%o%+> zQ1r0hS$h!ic{y`1m(o7`MFtw%$Pu=0YCNvTzM<8YgvE*r*Wo9&>3i{v32vL(PS=xT_soNtZx`zrBgk|{#4#YiHgFTX zEN@d5A@-O#_6;|yPvHBNXl5xCFST$g>EtU+ua)+Ao8-7RyjFO>NqFw}#JGbCf0C<< z!^@0|1fuGie0EL}dRPv?Yz|-r(ZmIi4kTTmpxvyE{m#nYtC z!ofV6i*kV(vZcBB*taSiD(F&JTliv#w2=AGu8M^X%w^x|QA2H+_5|!-Z|08i#E5Oz zHdoVqj)ew~4(@`iAh#c&l&E~bC@>58%u{&vUs+&=qB8Okkzf*4U;dDbj~rmdgC?PVNP%WSn;t zv!s6K_IX|>+D!F|;ieBs+KmmP^-^!gT=7(QhTy;}GkXmzzvga$bL{s9QyU#3uR+(Yr);mL;u-Pc68B8)2jc*J@fU!tNQn# zE$gx_(t#^&Xp1!bYfco}*IJWMIE<&GU)ddh*!(aLv{?CJ`MIH31D3R6^nK_J`@Piu zH@xN1+(dY5^6R`6?k3Z5K%e~6fIy$1DH7nwCW?y!{>KMxM;mxWog zU*{jqEVQ-`y#EP%*|G!*h_w|eICQ_xGv}F_`y|%5oXLf&deT%Wes0{2IDrjj-a*c> zH?zJ~Z`FRo+cXT<|8_?h5b#AN6dkBO1&QKWbof>wyWJr6at*N|jqCv--GFNPwdh~4 znpG6C4Jc&Qy@FH<-Ca@I;9eA8KS#cM+x~D${4W6s8an82N}-PEWu~m~n@nX9c&yc2 z7WCI$uWTDzg?KbtwnPqTC6DsMbu6%iwutEtDrEfS?ndSmD}1)$nJ!F}t>e-Y%Wus+ z!gtQkqumyO6=KcQyb6AeGBkuO9MVoU4bbY6C(avHh%QqH`u#pCF8sK8vv!p(exgxs z+YdR=bS$qOwTxfZ>%rz6SYse#Nk49}N!^uW=mVdn^TW&6;eIGuRTQS)oZYvgPs~lJ zJpOeg<@uf0t4YsE!B4sv)475LmWg5h$Z<_>>j84i^20HSo{=W?O))zurM)Z8_deVe zkYuc!ESm2!_xGWE$=`bulhm=>AfF+4)XIu5Rr#ty!>xQHb5jrKWF1@WC%fw(n`5V6 zBdWr`ihCZNT|Jmj7d+D%`96SwLvMekeGt>*$vtaiJUFK8VZSfbYnd(sGjKXK&pbHz zJMM2Cin>9WoF3HcR>J`U>%?T(IX9T&|DqC;tzPKbCfdWv5q2WHwOjWAgaaLUgvN?% zD89BloASJkvCV2_yW`imtV&;7TwhoYso=PIJA{K$iG+DZycbbR=I6>6p(xhUiTb+5 z!I76m61$P*rzwdc$yheAH8&m0dKrZTfN)&cDt-ty%kf{pxRwo%%2!=Zn1wQ0Dw>>< zW-h4!WT)NRL%&=e#g{(RN_{@^3`91U{B|*`%SC*J%H3HT&ZR5Plk}qBexs6{n_Hv( zzSy)mISF-fD4dEU;M#RrA3A`sseMT{+HghF*#+d@8wGCtFDxN_S8)FXEo%Q-3c#WU z(1w?&NJ$7WM)jh#_XWu`q$)?hxGjAgW|X=OKltXzZ&u-wX}esS*9iBcnTgspApxY4 zqGa78tkeXM?lSNJD|;rFhDJkIZs%>%FD94I1cb>9?FuO9fvwavTzEr?ASf`4b2Rp# z2h&Fh=#I}IY?+&qcgfKgOk8+LuqSlz?KY$9L8hD0w%tbC$59WeCuKLROiI#dM~Znh zSpOH^L%V_sL68DM{oOO5i?up$7d|7`RgO7RwH9w+f|hfl2lt}Kz`jy6hi3Esyqe0% zSDtxTURgtl110HWFlMM-)i9BpGOqX^wFoZj-sfh0-a-B_^=)l`T$tU&{vZr!jaO~L zi6NPfl8!+vb`dp!F@{;l$s%4}T3oxOE^%IX96pQ0$5LPlCVY)f`xS|A8IO+v^@ zX|2CEYC|RnAWqQUfX4r*t>U(|){6*+FY`17N+Rt)H>R_z+{lr{&q)^fF?PoV<04lIzgHUXc?N8MOJN(bFz;ds%Py&Z&e#k zJ<9}lId%fP79fXMp^>KXj-C9iL^_iOz46B z;yEgoDHrh2U_Qupt%=SFWu=qI3D*o9#tFkqp{h-x{qS1!@QiYkR^3K(1uk3X#{YxW zvX(A-iFE9JN|Q@In-@clWr1Vf0Qohd?-?O+yvaGyodb-#mf^#gBl6M^&LwG3tfet0 zHhdUcH>`Q;{JQO9wd-c1v3?FyK03awzaC@C32=g4kSd9}`ist28`tW@)7u*yVD#9m zFGtR3>Way}xP|AsMasGu!He(3{EU{TB6~Kc&0MP(Y9*yIAnCBkoL1&4Yu~o*o6hC; zL035o|HxQF(3o9^488)Z>B219^wtU0m2sr6e|=8eQT-%?lk-z3v3AsH>fVOYfWxmR z^a3fVUiTMz)K}Weuhx@#n^R^Zi=l{pv~bcx-$Z1sR48qT8V8j&fcj*EfeYo2!RR0K zffxe=DB?w%SD{`x6);;>a2UEA`ui3X+$^;X=G5=09nJ%y_t6nk_Q4U*#tqQJ zU$p3(gO-@pb^btVL9m$N*>*}ud#VmZB;o*_>ahk_OT8oAsC#~{0E4fAS?NCl0EY1x zpy$CLx}89SUWF7JKlnk{PU&^j>~==kg&Iu*Stt<`1a1_#Q?w!yb*%kcJn62U>w!4T zIrRl&{X_XcL6k2cr+7#?C@qEV-FDmG-U)%;r8ivmZUReM#h2L&9O={i191fc=F%vz z%Z4tTUPCutA~b8CRkvd&S3g8RFw*|Z^x;$4qmo<=VAL6)mwACz6=^Ens6#gsn>4Qc zfykiSl*e5=^3LK#=4+X|Q3|0A2uWXV+iKzbkGA&?`wZ+uC}Lg)#5+iyx> z_TbN*N+T&P$U<@P?aIs6jlpWyP%D4`GJLz61SSWc(slt~xruRG@Nti4Lwccdb69!}=gB*qMl{M@GBbSvLPk#{8Ie zwS%DyUN0W<{uFW@A0+jB37s3rd5jfC<=~b=qAsUIfhlovF+FeTO5`IpiLiWqZG}c& zhR?=n)<^X1Fy0xrtl{urwt7I$lDy>|T3|yF7%}kqY&9;uPhHLvM~eNc^O2BvU`f9R zeWAUA#8D3G6SsS-SvhjyNt$>r!BWvID-SVqez+Gpl0sZ$NmGjkARIWiNt5#!{7D1k zJ8@(E$$95Sn!(laxYDGcz%!{vfW%Eh)d#g3yjBE-_gnPpJ46md7)i_>D|68F7JQCQU<^jXc$qXi^Z*qNM<@a7J$1Pj_z@@al#GKjZ&l}Jw z#t_ReS0;JPXUrfADJ`Zoh~s4#F0(bXm0Kf06jt3~*{}Z@(<4Uc_PX4tYJ7*ygt_Y5 zdG-B9#G7)`UKf7+EVntW$>xJW!O&p=4?DfLNS*paPN>%SQgEkj6~TwfW9#2VLX7z~ zu59v_GOvI3auWA@`4PBymzjK7h*DVXE#J2Ka`VY1H!m}!K{b}l`o{a9LUsK@twz+! zUr!zm?i0%8b2?Xe`3F+^Z?ZUHUqM4#FN*Z0<^Y53?s3|}B?`wO zmr-kZ#c?K#6jrqFwd%G24spo_`=clK={r@&IaHfRQo#5u*Qx1K;P*#%r#U zudXbKRfQ()`Wgh)gQVCQc;BUaHw%UyKc zc&Uac;uLU(n`yHXq1}U>Or>T$>DC|npY+rpwf#=R2pTH4n4dGAexm5Wrt@jhG|x8? z0B*bw>DNtgP$~ZJK#U=nP^16X6k7M|z?l`5|B({fphIXXfn6ZBKfBGh8$cMxY>lv>im(@WzT=g9tSU6OjmP2 zint;wixOVtc(}L~zgjWNk?@n@Q4nx>U(?$j$ z=-*QyPpk{pW|DY~2w2edIGv4BaD-%(A=dgrkGmCGR#$88iO3q%R$qlw8>KkfiXDn8s~`TPJV1KEX}k!#Ek~EXa>J8?WM4 zRVRzowbFw}M!J68$CZk2toN#N{V2D?DEV$KhC#kS;uHm0?D(HPYCaac-3T=9#aP8$5U z8D`h$L2Ie{yO83pO^jvu0ouFQXg~es-96q+v}n0xUNE^znjYAXq}22Me@-O?-2}=9 zEil6TZ9Ll?#<#bJWL;X&;Kotz&dH~k{ONNIB3BIZgSbcMV_31WlS7dSujfM3Yg^NQ z@TO?nfSs2APlwHEW-P{{|2-Io-C2sy< z5V$gl1Nsl3USTrpD!*tv^?B+xxgB*-25yu}+XI(RUkJ}{@;*NIUyvwA(^I89@8Qb6 zqiX+Dt134#r{a!^+kXN=_BgHM(o;|jMOV`S6aLUmnxY0^FxL1O1(KK*zYfI+ z)xj>D!IkY*jp}=!a0^glnL^Y5EXY?wlgm-}Yz6MQrXJv$*B;y#^!`H7`LC{*TB)bO zaM~_e1U)kUiOSQIr&{@?befsxiGOt=0KkQVL3FdxlxU4{=9uqNV2qzdS3q&w!pQpq z=hAUj&^Whv5A|_Dh$~Zl^W#x4>i)ytDxL9$%IWB+72O|ud|gR*(+TjWiUK5D=BSAh z9+2XH>g1M>C7auVoJ~X+b|#MYwkg%g1%+2DJ5gNm`SBxGysqEKSlQ!VtR+Er1u4cU z#;}H)oUH)6v8^hzc@#@V>wtPMBg4C$8_yrMm$=T8!%gwT>*7*56Ugy(A2<^UpM^Rf zV&*hN^@ZUjipFVb+_nryYcEjpJ_Lv@M;mTy40tZ@*B_%H$5{lz0Nd^;Ff&U-RBv<| z%9b73QzlzvUHiGdu&afbG2t4 zx<`5EI^JExOX?z}?m%mP7VgWAUe>G$(yQv*<6jmme=*g}%JqqkUJYyWi*AD&9lZdL zOa<2`YX6Sm32){(9QwFeuhPVCyA;4X4N;T=PmOZr@O?@DqB%Fc%TX zsxbq%z%c*Zc2G{bW5txjBmIEQdQ`3`_dz72^zKa4{jrW)?}^(y=#&&_B+&u?il;0=ApwzOMeY;niCQ~l&%2`S*yIwP&qmrP zSL||s=g-M3I~520aT@kMTyKfEUWfSv1V zEJa?Rc_Kf{x@(yTWfX7J{jQeuz$i^Q?^J=`1-TB$LfdR3YU4+3?cd+|&<;VvnVTLTfZqW$E2|}(eK(bUmV@;;sISA zc?ufWaN5Nu2@e@V2e)ctNr##7OAemoAc_z8IQ;{%{M880x_gWA-198QV$I>>O{KANr|wlE15T?fyn#Z9!|{jZ58sn6Jq_yG5AQrc8mo1tG=<|O*`m*F1;FVR0`p}*djc-RzW#y%#nDS z!^yZ6sDi(^jr?t1485bApvh2(fx5f`6Xs(6J$^QeoDgX@bc69#+@u9IK*rcUG<^EP{hXyY1{Ib25W zaKK_jWwDB7PNA~xtNr;&IhBK?#XWiq!>TPihESKdM=r8b(K3>`d=U;_^iXDaoEUz& zU}5C5c<3wpyyVod$6%k}Of1ukJUG>9c~9b`K)%Wi_4cQaoVWb*3txzb8FWGwzU`4_ zZJJn0z1voQYSNDOg>~Qyq`_m?YiBfUm@x1w3bmL8(=IXuZu&rez#uX(*TKHk!w24CZ9>=hww&x+J1>ZR7l&C6ydSyvqW zw>q*Bu+L2{#>B5G>CUy9jmLJ;3w z23u<1T}ydMBJaelND?1Ir2X1VU0s4oIGDKzP^hipUClJ3uD14td75tcq`2*Bs^28} zeI>lNA-!f|cU09iY$utmH^f>TYtkIwMyYQW&S}93vQr+-O49!zI>PCk^W1z+-DW`+ z<>JA+rTFj~a%402sD42flfsiSl%C>B_t@_F$gS%t zzi%1mbxqOx+VN(-t9tNu$6Am&rBLjL<{OmRubKSbsyzKz?FjBQ2X(LIMu#H)%DTr_ zdsgz3GP6tN*;xI{&ortY*T26a$@m~buSj%Rj56(k$?jEbMQQ0(&Xd<`GJC(yhOuk4 z47TZMuIe{8fNGVLEcX)q!=u%a`YvOX&4Ot?D*E) zT9WvM!ADtmPWeR25DfWfCQOOd^p9B_%;0O{JKm%4pve*n-wjF24T)PHMnYA2eI|@! zef-?*VcOuj=2sAdgI6@(6UtG@74%x|si$R_ZgS*S-Iycj}1P577uf@M}=Fe1sq=YhMVJ7HDhiFLN z>EsWEjMa}zepdd3Ix-pbcCYX*2;9*V#AD9TnykuneL&*GkVYs;_{FV4?O={(!uHCH zjRqfu)zjR)a*pt_kxKORPt}7(ZptKo4BM|fDw8rm(Z#@OJ4fccS_Qn^;(UzURzC^YFoFRnnu26ku_6a z4IjoG%)V&?;$mAvCY{0AqHm{E=N(gEcXD?Zix0cDduf#LBT5D;i*S&1&zJ~<6|*(m zEYC7;U|jxwQnjlwtz*#yu8!?7OFSe?aPfKYiEgLxDWR^Z-f~)sLZ2omG>*f}8?Qxr zPmpFp$FS2R0eAImJm>b#=*DuhUTy$4DU6CHu$l?8CsKaUIBG>_F~Dq%deS*jg6q!f zB~|@74^wL_H9ltBL2`THvCb996WoZ;#bI^3s^rYSByPzU#Hqo-#Z;B>yN()bex z#^hZI63d9GqHE`4is!?)z95T5l%=kK10g-a9xd}Kp5$V}2o1@*io<+Y%l;69K_d4> z$;tp%Q`R*Gg=b0gS!_1=S@=o?@m7!;f5JzE%)A)lW*|FJh=S*dn;?#$Cj*kw5ashW z_$F*OMTrq{1g;jaWnsej%H$fqduc!=s|I53Osk`R$Y@_GY=l z00|Ph(jp5X+;sh5MQga!{+ad^N30)D$RRHVA7&^MhIN4>_RBn4?>Ex?$S&9^(L6Io zTfW`F#-^F|j}&fK(JA#lBtEz?&__=oso!~I`b}0ufkS;y8D^A`_qR09;(N(IJYLKa z2;DB#xc6l{@7qrLboi~uRlN+OJedg39O0E-=q4NNHxVa_;k|>?mse(SAz;@;L&^-> zKq;lkY!dX~Gf28a7B95=OcUt&E$As8IYg6uEN z@xRZsALR`|Y$9BjVf}TlQ5c;dUGq(`eA89>XF5eN|7@O&Db4rWMCll}Xj0ynq=b`YN-VhmL4Ck09!MKE!lO4)LYBlzq?J3Ax54`3ZNFE(+mUv$bYt*JGs_ z64622J^{)dbXEOIdLX`BIH0-J0i8@zUw8!FF0F(wS^Rw$%)tn}i;5G06$S$0vOeZF zW2o8xYeYq41F)Cq-w~+Zu*T9ncU?mHZngcs3F4h}nl?A8*M>d>LD7D_G%!&e8D*wC zx|WF}d8b1v2it3QvaloF`-<+a7B0-kZfRN!ZEt{t{m(-qfFXd#OGO-bl+JBWLQdjM)?iPx!4q4`4gnOTgCg8nm$s+Jfv|p zZX{DJ_n5hBJ{nCO-ok}9TEUboLb8!!od0%ya(E636T^z?*)!^TpY356O(*xs^-))& z8gW)d&gP!|(wv@?82MzA$mnQW${L&ZSbE~;h`xAr8CLGkp$`=$@KX#Fm>@Z52OPMY zpM^^a!lGM=v1z#0kiwGHw3zWte>JR|JQ~=T>FotPYFLe=uiA@}OYV31vr*u1_3x_P z8ep)-)V!C))uo5R%m!yJF`XWYWFt0Sf|5;TF zL@YFBfA6Shfc;(;W-NGpU-%k?lmUi( z4D-3&L56owkoQC%ZtmpV&5JQ^@FGR}aipRTw=BlTep;vr&`fyRi4L+aqxIiBjaYT9 zuL^oa@hi$mH+f=~U1hb?GEzvPn|nLPPOaLMK*Dox$=AWbrS7A?>=-HKDRg%a#rKuJ!Bs{y?B4D%dIUy( zryrVb8ndhi*#T{Vm*v=1FyZy*cUWSH&_2^E7l1#sR#T+N1MXzCU5R79cvJGw7 z6xd&^l_t|6o38vn|A-=mIf1qnWL|b>k1tvUS6Qc}Rnh%dV(zoj)a^xznCE=;8Iav$ zFc7CHLm&6@m+PafsQFE~Up%u9qLqxS>o>L~77dUwKIhDTJlwMOvP_Ij1yW`droN-3 z7b`EsSWYpZec#ZPXn*enuc-8HAdi|_ZTvL7UYA~gmPNBoWKRHA(@~a1SaA-1)m!=u z{|TztauG7M(kZ6J!pJEzx42C2a!wAf0f?*u5zC9R3WkWhNCu|d2hCb{_9TdKqOf>> zRC`leP(?tXH;I4R8t;hE_T|pa*X}+9C%Iw55a)MiV_&)_b2tnumkMR|ON31d2+O_icRV;Cb2hzyX?QNxh40g)IJ(3mZDjuolB*k|4v z{kCemVL{v4rU{Go*_|eV+vfN5o}%I*Q%)}XN?fwu%~$STcO}$GnSMY)O<7jXmrPf3 zMhO|s$x`ewb~UuQBUy4_k`{A)>AcIIqosr(4T85;dm> zJQpM!-J4fSdBv$l@~+P$#@tSyT$k7wz7cS$OWf&^!HDsaFN;_YP~WhP*ofR0;qN^{ z*Dufpe3AJZN6lCM+b1;_v|gePAOpIc8U8uKEkML!Gy?2qi1P6=LSb-;MMF^CH=Ii6RTftZuCL=$!hcU;O+BUFPRDbhg~3 zX?KMXELJ%zBC!KrVu%PjYH&@B1QJidDUJiW^fTb>YK#`kD|LTijkU_G)v6X=xey`x zd9yg|W4cxa6_(_fg81e%jL}@LwWJmNh7CE3;tI2{@Re2^O&g0wdxBSoq$~B)2VdKL zZD>}mJG_;h^uH|`%r*F&fU?4StP5_AA!#WFDGyU6R=lg*1Y@K9Nu7zR<4q;8xgFnF zuKc8rRet22acKi%+N1@c9!Vo6o;Gfh>mP`-pJl4_y+|C9Ao%D{Up-BxEIg|_%#UAB zCQCyU=uZk?59sC(K=cN!2P7&ai?OgI$ku^_8^qx8-4Wzx!W_NM+!?}B6g~E#4-%g? z?jYaB+wuy+6(p}=q3W%i1wx5C59HLwVJQQBt{Qosw>#wK$uF^jNhSj zmbHBwDe|%iEzDCy!?pFxG5VQ4m5hJ{tQLyQo9b2kv-jnQbxhLM7a_gmg6p=-9INqW zf+okd=Mu3Vm^u7Cud!Mo;@v1Qx^|1pgHbaMWE zoAoGf>CfJWx2ZN?M-7Me+)4tAU+SF5eLKI&QJ+lw@9o3A&GQz?;+n(1K@o}6oB}(= zC^)!c?G&7>MaKm<(OrD^M%6&5*st5;U!S9@0ZCGzdq$9xz6`Xw=!1(MTVeyl@{NN2ZuGA+pgdLWq?!Aa-GH%EYv*tDolH@ZS+3S3BLRXlHfjnJ+1u9jP|m_ zvEj=8psdUmPzH}fJ`Cyv=pNl+SyCBisEg%i;HSImaVJ9OT(s=~JbyP%N!q61`j=6G zdp85etW<1_?tMFM|c8MPueB&Ah52DNLrqDZ89B<;wAWCVjWgm!}F>p0pXn z8dgRZ>F9{JmIRy>v1!{=pA_;|%>6&6-a0O-t$iOJ8kJC_Tj>;#p;M&0JEVv15(Gg| zM!Ffg8B#hGq#GoL?(Xh5zm4ZS-}n6kKQOar)>_+r_jTVFAzv{}E1su-U*|z*@{ped zWhOtPeddd{k(_>W>d|i}Y{91+#(J=4vJN;j1`%s#1mlBCr`c2bi#uhM{611&1N?-C z!STX>{O7w+ol)A5ployOviUmG$O@xGac-!-E%!b@c?!r`)@L(YiBX*}mUT+J^AlDw zICNm%MlJ(~F+Nms!>OnHYO)-v5xEm;9jUPBV7C8Es4P?uFrl6N8WnI<4I}~r-Z%)B z`J>Qfo&!-pdI5T}lr{1w2VCN5E-}gnZPWE}5&Tpy%>3G5+Rr zl(R#8XP^nvZJ=HwC#}O?2C;sP)B}Zf93eN@SGR^;n?4aaFQN@k6pVwG(+x;M%PG&0 z0D|{A^*Lv?2{I;5n(lPm*X1fG^kmD_PSVtodIf05x3O0DJ1x+GrZ2R)pC@6@$r`!y zt>PlAI?|sH>0IF)5`}Y}_zjJTt z0LL2$`F%+%?Igs&Z>AkYH@^UHWX=Fy^9M%21d@Uxp}W4ipR=y~r0;HD-T)$K^;d!c zk!frp)bE)w`tmKT)4riCHi9tkAfz!BvMmN?s;Q?sc@(Bmzl7BXufGZ)3u_}L@0Ja) zO|cKx-2eAF3>5Jwv&8>O7eu5Vuw_EDfKVucq(tJIN;Wp7M-QEc6HHtW3L-}kVm0-m zCtb?F72SAh6N%FC8iRWLE>2l{c+$m*`Et7=%;@7tQ}(JhDId?5vsdLm`~*0;!h79J zjSP!=;6C^t#>!tnT6+VPZ`VdpH8d72{%Qa~TIv4^=M&%pF)S&@ogEo~@xr65z(^BO zEokV$A+(14EK{@@5W-!9?&&hXA#uE2nv`88G1rGz&-PdlCKjpIF@bo^9{k|o@m!a) zkn+WCZ7tq0{c0{MHs~4?_3eb2?f*`P%_U=tq95Vx^h>wH@o;gpkqT%N*#L%!_Ll5x zCicJY9!wn{HqB`WM}19vya^>ychIfJqW`Ugodwr#q`8x6e5^ zeEqzyO_Ker;hV^G=2Kg&Se{LWWBB)O2M!LsY}j5#JO^R%%X;9%F+(TmK0aDqq4~4( zQdUWXGgHrWzJ(nS;8#%wXdCBG%jRvDTw3+BPS4&IE!B)C<1JLH==P>E$5SI2n4L^_ zv6!j-o0Xb(KoWv?D$f+^_NIgw97)++Z;N4ySx}$R zpjW1u*Cu^2iT_>5L@%4>>Fvv(Hfqt&_MKCdlkUo0D+FC zo2W%S!}mu+r7v!6#tX-R_}nuaR~dLbK3sq8&!a&An@77qYDA~m{Wll>6^Xx==v3^* zsiEU{^m&YSKmwKivu+tzmjF1mRnh&^o7$vpfv2o?fNZr6@#(2;fvfmtV9<9ftpg_Kb01`9?ST*2LhXIUze{}!Z+0UVYzhIR=4bq#nW+3w(*IU2APug(mxURYY`|D7Oa zlWOO2X>86H02Jn-7w~_>0C~&11rOgHJ=#D6%tH95zoPtT-xR6-Psq>%NF)B#TbL4) z2MTIymKW{nVV5-#-=CTFHlmEXiEbhq93M^OqZAtQexY-#&ya5p?Myqdvx{t;4_8Q3 zE$e2JG#ckFE)}`4g}nCd>J)$a>BFw3Z?foS%A*h`ed~Ri7rNwPi?iV<;&PAiLF=5q zhXpy~BHYTeB!AE}xQM7~l{1U{ey7TrH=6KZGk}FIsftiocF!hxo~fsE@N*2`U; z!LW%2bQ;k#4REZdWvDJ-N7RV_CrYZ4bRaf1pl&?#h*Q#&(*pseWNRRqWuStrT0goH zix0}0rGR*%Ad-O!_NlBQ1!VlM4F2y6-0?F_qudLupddkY$P(1$y=ByEzZEAmY87IG4_;?^VOEa<4|Wm5*;dCy4Nu99o9@}0&C^J-0i z@O#bhx-?SNw=$pJh+Lg}eSDERX?0&-c=4-&>SCg$t07HTwT8e+{PkOXa5GkZzyHi% zDzJI~MFdb}5Ul~|#r^>`0xgIDONSD)@>#~r%-6erslxud0GM75cu$Y-%X3?PP6Xze zKX-ZK;D5O5AMS4S=4VrF%_t!mJQ_CTz`SNvV4#f$xMkp14^GGQ2-@@`RBgnV9`@fUJCxP)lEnUFKXn@}8e+vV^Si+X- z!z!SusP6CEsbIk+fS7Lc;i2woLdaDTSBxE7T?KGacQYPY&-5P%C*D|&n^(o0co02r zWH)EP4hv+7FK*QAt(ssf!?>%8qH2pBhkR$x^KTCF6p^Od#g=ks0n$2e)PW}!V0Uxv z(8?Y&Y6`=R`gMLo3Cz4GGSPh){ROPh4^aOt0*&(Vmv;|90(ud!5TwPD$n5^MI}#7Z z2Q7!EKm+>!-Q>r2;R*~u0efoP@p1o&RFB6iP}EjYBQ`cLcN+liYvKm|r+XS>R+@v5 z8b@(Xb6xV2)fOM_ z^5?@?8~uaMjvO<6xRi6ArGhDBPYkM~O?+6Mi>A5A6-9&{hM>FC45B-OQq9lvt5EcA z*7WQvqwTr}9grQi4-MwVRs$eR25nAG9%c>(oSpBYo6GRPtZPe*B(yiCb-paiY|34v zQMDB+73FUYMCZPJyvYzZmhjSU)nf>LEmc#idnk5YPH)hge*2N}0>4LSQT~WGw3H1` z&|YBekSs!1qvCQSqtH5?t0EM-J-OGhtcmjvXw7zZqDN@Ful2N3o0CUGYr^hM(*0Ha zxZAyq{p#CySE^Ug4ik;kuou74e|1=3VW7NjSbXj!D0xiI3JZ?2+v7{aXZ?Nv5O^>- zyj?F{sP2x|FrQRiEk|AO;<@)E%1};vSXl$snRk?W@beQ}4ecGo#v(u9?|jj9!ZR*q zww1&E<=8MdK8`TzO#+fBlH~!UOQ@qyi=R+Rin&koE9#3trkaK#h$q*4^GNqk{n((M zl7gxR@l*XikwR-{Ye>GhJR-G%-;RL#7Ft98N?Kt&tRQF$@?NPs7@Sk%hek{phh)U( z#J{U%Pe9KEIINwLZ@&;9K&lMP)+IDU8Dhn-g@F<$hzSBff`AIV3i2OGc1EOX^$J-i z2#t>)e@;yWH5olcF%KO869E<2$Df#lm;mx3%-!KUb|(DMkpT74WHl66lZ8p$pFV=x zo+KJ!Y(dPS?7aHAgqe3SS!%eOs;VD?dE!RZkOz|n`%Xt|Z1EU4d&u3<%hTR*M#hI` zK8x#BH4iJsy3thqq_h0W@(!{K?!TV`{R8qELB9y1z3}e^3iMf=4?G~UMF+6b^~ zz$9^ildQy$E@`&1_cOI!swcsxMw%kdgs^6?{d?T2f4PDNfnL#>n@8%wx&I_3PkdKH z*7No+Lm?omcaM_vD-Y-ly!=0*`Cy1eb!%WOF=B@&TWU7wl5QB zKq+-PpSs$!d+1gAr0;kH|CpUHumLC~fF|)@Z30j@?uee=yZ%))HW~QN8m~7m%5pNU z{%R9oOUp(7dq3sQCLAC0CqVhM`u+CrZWICb!2c~ip~r|kd65s09{x`cwJh5ktE8xY ze*=lfJ%I1Px$-Ue4w+% z=%N{LjUQF9Hg_`qo?s%NM#+Ji=s6Hb)&j3mPn-ip=>J|{M1#L9*P1-L%bO^W@wF6O ztRI>aE$Zr4(SYJ<_W8lPO#W8t%&qx9)n2#EGSxZPX!z$JkmN6A*3Bvpa41|?zF_C2 zUZ05dRAk|vjc>?pn4i`O9lIktM~>*O{+%rhwtuhz$&2dQbJ0nKRlx_NsMY-R2@={Y z)(v>8o(|d7zwT7|nfPWs;``*T(#KvE0_z`suJU=-GYLQaE)=;&<%<6eU*&lpZv^^b;=Bha`W-&~ATIDwu=eHFo-zo(GK1dWv)d*56 z5QdGmp8K|=9gSA3b)@xLUh&sMzck?%p(Ox#tna0qFxuEz*^r<;6-?NSO}CxCQ$Dg8 zb^jQNt9${$5VcJHPUA;bc;|Yh9l5K=o|9!%QF^XjkR8ZdKX*&z!h&a_XZo zQT*okUj7~V8~iNZ+0QC=O47ze(%AVzP`9`4=|qm z`#=Lm@&E5x!E)p6YL*ChGjPPH5*afB~ zfZacFwlvjM{rRH(R%+1hS)3`alfX)SFdulz>x@7^EuGVT>;(QXt2B9#!dUGeP-gJo zugQIw9Bg>|JzpbB`{^p&ZhC}$46Jg*1v5gZ*L}Oy7wa|;Ak*eG1!^~vczqaK|JY) z)$8hq=b~Po<(^aYT1O}A@miJYDYLprp=!&MMGu!7pTbt(xHnzd_wv@E zrMz-|C4{&PI!BdHu5QXEMV#{x2&dFI!Q$ZbSzMj;SJ8brW@G_;!>hWy{aLy0%re<_ z$>_4Xu(FZ(4JH!hhMr) z+puga`UmuOOL%wj?!{4y;?Zc{MlQ{-@#BdQvoAM{2Y$obVwAl0OM_|;9r9Km+=aT~ z?^&4#6Wbl}=J-$DzV`&|sY685{6s2oKzCK@=omjaM0_LLM411uZ78z5hw;-XMhciT zMw+EU*UHbZjTNyk=6QBNqM@sT{vz?`5$MePX1YYS%$4bwG=aj5^*Yx$-W&CC{X*p| zu`xp(v6|^(KUro(Xzn;<+13$4!nldtCe;_JVWAi$X19xbm-|M<9WfAL3Grc0vxxCN z1)x&&Z=uLE;3+4}uwVp$sVdW|po(L^Nw7iumahz8w&S(~TLh@ac8ZPqsGuq}(OL{S zIV%=x*AChXGLf4vL5u%}*U#jbs;faeJ^>%cO-6$v;*jY36yuoz#7v?ENKAbuNs4)> zPf7uJT@M=D$DeEdI)DtQsiOhv;otE5i98I@BMP@;iF6^ja`y7iHv)J~bijfi@Owk? zO*nQ~*e?~*d)5MvFPua(@JL6#*9L`g!T#vR97IUh@YI!aTX?=f zDMIPh+Lp}!N^CO8PD^}S2uwV3;hZO?+0{auyP7HSXO{0bvvoV#Z30bLItU zZe<{IrMUib(o8_PHC3R3GlQ!_e4!Eh(a<%_89VTyD|>=8(0ZBUB5FC|6S>-%2dwLw7aciG7B=PjLxI8ib3oViB=}stcv>e)oN6 z6HNa~KoZ?lQ7Cl4B}1jI@P;*2nvC-Te;=Qe@X2AiO>;y`*EC#hbVaF!`jUM7czdh4 zWyr>S)fPFvmT}gO$Ql0{{V=(u=}?a}q_$J;os+UUP;P-&&d!xsr#LkXT2|+#!j=lN z*Qy2JD^|o{q6XHO02Zs?4|om79!09I6sfdip&tX3pSJ8%eoC{&85;FdR;{b7Mar*_ zHWO1qm+c0hONR)(wOCHW!4{YhXXKS-=P>`YuVyX_Og5aMOrc0iYj%2<;lWJ>2ROzJ zAsH2&GOLbx=0-Lm`u1P3cN95EDQyFB6!jxi=J{UN%O6rge877=jk&j!>VKrEP^4RGji0m-m4115eA^%b}ZIslynuG&Yav7aV;b0Gy zR}r-DW}yL3^7Zv3AkSqIQ5p_D)$ncWb@6b;)-U;0X&gGL&C8WxrG4I)%JH(>_bgbn zoO!Z;sKfTkMV~J6CsSWLl)N*!zlqRn9LDsWeKqKJ0fPQBloLpYC1r+%sZDqvytlGm zZ;1!Jx0~O1(RupTjd=S|KVg9q$~RG9Mw`~khn&2;wh%jXKQyz5!J@~QD`AzI+twTN z!`cW9reou&;i8b0#BbFkOM1E|LhbBl@++aOflNX%<&||_ZZ7g@P!LRx>GO!!*L(VQ`Ed*pJ4$`3i$v(=uCtE8mGEkp5yEeE zT0e4A$52qCBcCLPyRA=fOlTdWR5M98RuvjBSGWfWSxS#L2;~j)GVppY`KY4jYyE1pqwopq zIDE}%RS6>=Pg#03S77GOkgYp5b5u?nce z0-0C*ers6DXuQz5IS4ASo$*c33$Gk}c5|-2gKMUbk|)Wa2fC)|G$L&{8V+UWhFAW^ z*~;w_>KUGQ+&)K7c3i&B`|cJ~Vt+qp`O|ULJxkt?O!FOzBund@iwiIAJ?i9>XQ8j9 zjaO7`WyTuVrSYV&3C8-f^!f&VFK~IcZfg#QbgR05KFGNDNqoM+!L$`zkDMPf*_WE> zv?KZrOJnD=GyxsKuffAX!M*-NSQV6022%?x-dbRq%cA%@6MZE+K~qdxUEXN`3R(rL z6687+J>%R%R|Ii~;bGHR+wf%boZ|cc)IIx~U{iz20TBKI8k427d{r?*kD$@0%^TW(a1+1s_X`? z=>8)suKDtQBD)ZhM%r5z6kwm>asHPdS;RdC9L-RvZbv(ui&EO+n@(%}ZV8qtjd)w@z zh&1e)U7KW@Ju@e(F5VYi7@O~3ukC%8F1_PF^8G|SCN#aOyw5cGwodIA6xT#l{Yu+< zPa3@Z=jv2T0B+IJKsa>w$~X81SJ`IAxU(^*Y)s((9gZ#kpyYI##!+lxIiZh0-(tK% zRZzFw>6hcqGZWt^UJ5aqn@RcQefyfiwW#0g*YHe|E#~i{Y8IUAZ+Xd0Fe2pWhb4nIvvi;R937;!gYko(D%kJ6qL*WLA@Ys@ zTNnB!RD)q!4siFgNUd>s#;SuGzsa)(t5#LNF%q_^&9P=Z2!qt;Bat;CHX=hRG^tvh zwQ?)!GVa~vrnYRg(MGA1Tyse{8*0$#^F8>9_yw#>!Nusl~RBBrHEhuL{};MLb_R_$kA7_CE`4` zIFoC|FUdsACk$Z(0p3;szS^i-gf+5`Ii~laR)q>(orjRm(@Jy@kQZ0@sD3OD1%0dlz-`Z3l; zaGg>$MwiK!>PLp8GuBlRv6&ROrMx$?IYhbbPDQ%focVE{My7GpIhb1a{@uylakFyj zi*a)^SYhp#Ke(Z1-)9-18!HIw=m*82FIe}s%o9yo7v(GbHTJ}M3&w*^nsr504(&Li zrLIoD#^l7p!9wc6;$-GelSrc@OR-;Bq`TTS7x-J zntV6~sOBaB#=lUIQ#j)5Es+KagVJNBO7Q`IaW75&ClILK0C}w8Z|(_8JD$duN8?ro z6D?bGk1?yF8?m+YeJl`-4g;56I|7Zj45~m9`dRty$>Os3q`LtyGC*k;U{;hUx5;@h z)doI3M)60uHnuQ1mXJu)%RRKEtv zJCT>=2RMG_V5*Cu$6zzof6=m3{eZkMEvtUtkrx1vyrr1hwtuq{lJfuz+}=EKyxkj9 zswu?1_Dy-X1z5x$zD<$n%~>)#_E-3%x* z8ZBjrGWbo`TvXZNd=kZrBWcc_0v~)RR&MmqWz%mIp8K&=J8B?L`zI8A&6AenlAxm8 z2KFnl)L>S;P${bTE`XDmqKHDN$G4mO7sVtyXPsh$=EHG#OIv|5=FU2xC@nneM&8XK zhVN)+7VVWb0WwAZHpNmPX`uG_pD{QX?E>|(yy58?Eo(XK*I1ltjJj>KAE7$$1ik{8 z#*(5BWGM0`0Yc7}qnKU)GyKN~A|!k7J=IiW!9B|3hx~*8@Ap6OmSs9%txooq!{wX@ zJYlPcKu^)j>0ET9f@L5j$I+WVfBk*zQX1B+jCK_~_iFS&U9_Xe+0gio7B+m33M3kq zfrP=ASY2S%wBh>;8-5Z`so^gV6!gg=u|+K@;64L*43A-x@a}YLYdH&$yMI$wQ(f8I z6r&mUylIw?uUyk8{-u^h=UjoWt_j`8NxITS>0Ah}=LtxQxZj?EMEL89vtjkobp^qp z0d7Qf|M!1D&un<2LS7PIGJlSlRdT*s$+Q|yOpM(jiZPg17#*g;+ne9r6{eq&_Y)X; zlHptN?mLaYcfdxo=Wa?}a^lZp(+S$S4|Lj>l6t^qSO>wphP0Cw$hs(EV# zWe1~Kd2Q53A1Twx(rTUMI0@<>V%a1lz9IK;9VXIiS9=i{jf=7 zLz$gkoSTu6KA7R3mh!_yuhQ;HXAGUjfxF11K0kRGiKvaUvmE(FGqxFmpsf#)`7R>n zPQ$kwb}#v%h?()JfabikM$<$YTIbp@>*sfYn|uUH4VDM}ay^i6d56Otre6-UQ|;;9 zh`jvZ>ri1uvCdptq!_PUPYtyJC+4s^YzCCzv&<(94a5B;H?ZQ=(O@eR5N+)Bq(t7< zFLk!gk?ZlmiW@)wHn?O3ubJ_?QFqQ>Z zTN4?DkN*ouzfGc|ZE=T)wA2heWrp5{gL|n9VtG0JVx3k!FmIS3Z(wYE6HKPeCCVv1 zfC27Zkf^z2T>a@Oja3g0f={8b?ubb32(!FYPtMMuwd7@y;#67ykb(VHkz=8hRj&B*~k!=r_Fc0)H^Vvn2$Ww~e^Fg=gki<(B){6_*{+DiUVLwE_ z5zKG8r10(QGZY!&T65Izu2NFTRAh=y4;iwy=3woB7R`H zbx0A#M~&gTFYKa+%f(PT*_UYow-3G!e^uVwTLHkD9IyVjaheru^@l(rD!{0T)}1R~ z{{wm~e}q)8Gk1pkXr{1d$3VP&z#oIS{j}epx)=a3`GKQ<3&Likr!3>Fve6}HH*!B73du*tDThl90oSXrK*EnJak zmZ7ay;|XS~(8S5_*Lx-EJc(aR@TjhUWuH1um4$B10Qe+eli>6IW1!Uhmsnb=r7&Tp z&Xd(IbtF!ehv60tA-ejANg21daswdDkLZ;AyfS{O?L;|T*H^{Q+>2vRZ9GB#zaXyf zpW561cg>i{peF!m90goD^y-ewj7~qN#fuSW1!0c&)8L353zYjR^?jNVZBEi|)sq?V z4^A(nlZqNo>~_p`tM!`(uRPEF`*!;c&(PCc0&B+lsu!Asv4cN30?eD_e}N=axOkGwnKNy zt5?;tvH9DaY!f4b^0++T4QAM( zxA^Ua?^UZc+uIDbip!+4o*j%bkvOzrsS%Ur+L1kVjd<*(VBZbZ0J8c!flmbW^-uYW z{#bt4;AkBNjjxToRybB|$N`f_R;ysVJl30M_kHGq^~pTCpR5bR;NW-nlA^a#O8(;9 z_OU!gd_OzSnv_gWS?o&2cWgu+WvB)J$$paTTc)KRDV_(E>s#%&`L;fT@lCVOZj&Z- zmfwFdZKTO{c>f(Y&-nc_c`G4nbooXC(8u(N!G#?oXUNFYyZcV?_`rSdjU=x_Kxc=lJTJ8AK`-Q?Va2cJQg5J9&!q{XKS(iI10icd@t{*7 zM{^BGcx=!uR5M-Lz7Wc#b3rgQ?PYq=#}-B$t#-Yx_~ow0QP^WFM*Xpr_fWL zYEMnka&^H{T|aR?#coJ9?l3XF{5h7YuNpeKCcERR7oKFIg9KDF8tXV@r1*qcn(PGj zKSbHSR2vIodCv8-Vy239gRwv+oGk7GfLQrY`#UQR3hP9OcY@@xaFo1Nm^b(em*Qmj zyKL+L^)JZ>1!5FuaaCmi1CI%{%<*zz{!M@tQ?#tH9uCqpXF)`1wlz({N@*o=Yd~C& z#V|Q+putn~n=%221Wx0EgALM0Pse^&s>UwcikcxVh8NUnSlw(rMUxSg0ihfdGKF6<->iy#`{tt*_w&l@h zm%WcH@*m+je7LK-(g0ckV|FE_!1~#uyIDYiw@tG2Q?L4`reobgn?SfDIHQ5HR*ahinYxMkY zfRdv8&pv%}&kG*FR~6g+yKm_WCBTIgyZsw@r~_M-E%kqNc5k`ER}`&&!5^a)Y^~fa z@%#A4+L_4i;{nzDEf#|Y!+UPp7MIoi+vH2m1mYi^-r*~m^T->_M^He!(tyW1z*uf*;%e_(o~ z#fAUs(CWiIFVLB?{A&CwgIdF*p-5VwnfPb}eB@|U)l8P`29?NUetHnX)$NSJI8TD& zL_!dP;DyTA%72c$vGi|?>F*GLEwt&Y)LWoh$fw8I!18kl&i4*$s04erz(a^PhaH8By^Vq5-Y2k5hC)~R(8B4zUV7MWA zF)*gft}GAvdIuV(niYt=dl-JaWv>wKz-ix9J>H6UdHCAQv>ZmUk7nvom8Y#4MFYS8 zRqMrRuBwj!r^wqYYk`f&pzG0oOt?t@&?Tvhsjs(=Shq06+#b|o{|JL!=#~|5H6=zj zR`Anj$?L9B6D(bp$&Ny{H2Vn?>U_f5_+H0oU2L&5qz~HNkt6;Tdqaz3!|>!?VFO2b zo$J;8rqL^cfiE|xpDX)bl*^Ac6FEEQNjmy@iH4dBa_N{~4%$;$$-Ob`CW5a%v2`k- zelk~CwM~#!i-b|}QRRwl3-YwQ z;MPQb{7&q?ZwjMk8J__+R(fiNbL?GnHy$K z13)v8ZbL)xlC;J`bwR2`F-ZNTCQ_%M_jwT)J$-Z2DnVhqn_xjL?+aM^qNLSB)69={n6E9#Q~iI?+-qcaxHhl!ELwDhH8 zQok4(C9YOgQFfvs(@uEM04WL-^zno1mJYFHSN64R&7FR|r*}-kBMt-^+ijke=_WPw zlf!m}ND3Dq(ettvPDfSoSQ_VD&Ub?vAD^U=T{&vkMSmc*7y+4l+8PtBIDb@DfY2W; zE*s`0eq;Alw73Ab@c2}^Qa*XcKsnL3Xe)4@*8bbs&m-p5Z?r+13<-ME+~U`P1>6yV zlGGE{nK6XRUAQ(Cu{tMJ`Z;M6)ompC-&{maA|B46Uf_8F3^m+O=U?I0xk1A9{qE)z z_njizA6#hwbQ7GB$rTvIs~c$NTdFOEIcPQeo2?^|FRF^NEkDGiwBp8XvxX2E!Pv>T zW>v}t;>9;nuh3kNPwr54Kd?rY0>)?%Xvy{i1G|K6+-r@>JnP_aR2u`~MgY?vWu4qaIvS7jwvDtkMF6@B5JDGNvP7$Cq-$iH4z|!J5uRjR zn?EAJv)kDuvlkVzVyIn*c(o1^mt)CT3|_^&lfrkSS~dI{-2Ae{R;82k`<_RW|D;0w z{KL*Uc$btRxO)BtiUd&_peLG}>z22#R9aW=M2`+2s}c4JDb|hO5)Xe|o|Q|C0b`Nn zzV}zu$VhvjY&gPqY&N;i^~AIqgZ2qWrNa^kRu}QAJ?f8UWn4yed#JVwg6>(S9KnKY z{LcVR`{(3$gTw1ava2mGXXkVm=+mLcGGE^I2>YRNw;mI!g^BOKOSgfTTE>1>t&Fo% zLmuEVE7ezr4Tk@)*;9@dBNQ)SYDX4;hN;CWI-vK|E4Xju@JcYCK;a~082L=y$W5!* z>{jM-V|ZRGNuzi!dRY*BXINPO_Mml)cvhCVr%`Le?(0ZIjju5^Y4)33(+aoo1iyEv z;j)%apvytKtFoc(8YheJWj4H2zBNr(NfvBj9IqZU&V0%m3+}O|&A8}2fr;u`C}$hA zcbu-L4_OztrvXmbwmf7Q2t~9-1O^4E?C{7(D+%*s+_X2AbfY@6zW`kpoJxanJPD>$ zRd(w6%NwEYWB>p@U3%)b@Lx|GWvs7-CW zm4{)|aY?Jn!rm&N4U&`^<3KofVFOyqym2MZ@C2fSS^ijDxo6eXB?P*~R;ODkeM)0C z7#+zY9Hz;xuJI%FW6(}fHnDJ{fv8@_g$1dUCA)k&(!7D?rc5P_d$M}D+-?7QUC}sS zqb5eS6N2Rpg{G2zK(cF^eBO2^0LCez%@n*jMmZcfm^WpGNcRa`^{%Q2j zNXa2@4DPW&77>;+$N0+dLoF?H_a5iSQWFQ-WXl;GqK3mOHN3(m6%!2?g(qzfZi5Te zNc0~sbG<#n#uXWn>*xKu2>-Ml&l-TzNKJfvf)A8`Y5>{vz)jv`!EU6S*!CN{l}4)w>`slAGH>0T!Ckg()W2Kh(q4p(N*VCnf%%3{`8>HpJ>X{QhO1$ zKQTi4sp5_&3*<5aj`{v%J73>~t?Wf|G7E=NaBNPMF_M z&Enl}>o^Jj9CWXp!B0@x3l^ss^0q#uhzF#bp^w z>R5a-rUfm>mN=k|IwCZqk?;k+s^yxKM(`!PIw@Pc0D#qXq}|h1M&>3vGiI)|X0#sX zCCD63wm*f=kt@LV0H*e%#dT{x@4y)T8OBZmIsnRr56WDc==W|VGq`772(mU$ z-n6*Zlq-`)1zHx>T55R`W8V9q#NUwGTeBnzgk9uzss}EW5k&Ui6>ag8lS;hA@3shc z>B=k0^X+d*IVcww!#K<(#}2p@wkDiAFx8nTVnn7$+E=vCq?qc|>6B!BtqI_(D>AVz zx>h6N;>t?Cz%gFO0&{!RW#zT2o4g#@N$B6TJBSVO4+^67fu0`v(kx*c8`a{KCB0W3 zh4e~x7Y;KVmCGI}x9w9Y2U19=SLvtJAt9JT*1nIe3o9dj@;w(Y0jA?gpnN&HY%3*_ zdHu1lbG>I1izDC`W%Bs0IHzgy%$^R_b^cw76d~h-sqha0?eweIj>*P^0wL95TCIu( zjraBqC=J~PlYIL8LgwiZq%B@x%10D(Eul2u@`mFU3xnK5_-67&V7AI^2s$6Qm;6*~ zkKtsE`W`{dUmP@!V{0Uz3lyajoTRyla4?7Gd&$@CZ6kiwB#iElT4Lv{Nb1H zFZ6F<>K-{^i8)pfckui?i6I)yBy5Mystj!+PbNq$AoxH<3`aiVUhyi#6Nh>n17ou4 zPSr>fVtH;;>Qd+2sshVoOF8r?a zE9|Xb_OvISf2bEY0T(>hTYK5+9Nj;yBux=tL`UBhA<1SUev&=j3gY0)TT-(O#CX(& zV!^cPZ}lE1M_=kAK2*khz!Q;m*hJx@ywlEUY5xhDC0^AXRWMQ9h*^wYJu7r!dw<;D zBQj=7t9#pizH3nZM@T_S3>fic6jZzgKm-PEywRn??n-hFk-2bd#JFekNf>i>#`#=r zp2`WP`sGJEyR3R~GI-eBh%Qe~Wgb;O*Oj6Pe}Za7mm(D7r|3<(?MZU`=fScm5@|;{ zpM-lCj+|4M{0ya4xO-Kd*+Z--f8TW?zG^1!tmN!x57K0Ys+wP^^Fjp=>s?OP+L#>t zwjHc7f5Wh=tQ(f*1w^Fj?VlxiopQNMR8W$C2uzZ!9+Gq}`@Q<2PzpCduI=4^n7*Kb zmr}jF${udlbFQzyUmNoH?NG20|5NxYeBbB;Vfsy69gu8jhC4W*%hf%@@{9Ll-u_*S zk*Y}3r@J22%lf72tvjodEO^oypHwDITFz@FNK(|A<^rk+FNe% zAU};f%Bw-p{V5x@wWM@$J7D?cv=%&#H)*<1O0Dl6_WW7hfZ$4{G;#`C$E0iZsmM0@ zTB=z_dmbZrvv)q8z?@Bz$BX5%s#9Jz!21kN%fD4x+3TkU$2NqDw{)Rm?H=j>otQE9H3f;58#bIQx)n$U-RiytJ9HWTPezL=l zA)4o77+3p?y@s$(jji@a&{|^lfbjipxT+FrP?QW!7Qh`@BF$4r6XEV0)Q-|qAcEN` zMXln3&UDMU2u{hJ_TB0l=PnnPmkwypb1efB1Wpn-nBWDoaRzmPS3AR2nlg!7Kp7RgBQICTZ&DN!jZN$*{WH_jsa- zJIpc;C`-K9hU8kzFbxkE7mt`l^~sx0n!PfSr~~2cOr07z=ClV8Q)s!PbIbZC%q>5g zL79$1^Q2c#b6hDWIG0{(?k74!^x;AuRgl&J|G@8fuX?>!l7B73Cj-bz(^#xRp=y~Q z!gV_(xtVvA_&Y%=!d~05`Uq0t_=N~|QeCahK?`#=j!clWqwBSL%MX+8o5^AoyL5Bc zbJM=D{X|Nwqf{$et-1>=!+g7s(DX6ch|y(Byozo|JsWHcF3!Ue?C%VN^}MIqW6BAa zt`c?YJ35nq2FD!AThR_#RHy~uWgDhWg~GDs3P*`;ENsM2YV^zNlsYUKPb%J=JDzqb z)R9h|gya5(mDM=W1Wr%klnCI$w^$H>b6M8bOQ01(kcR;Q?FP0%)enj+Ia6+UiE69sczt_u~8 zcm73lYxko^<4VR=j4qZiz_RYRt>wYzvKx-G|K`A7nYYm*sRU$Gyur2X{k;)1-j5=u@I= zM87V@;b!Z{Z+9khJ(0Odsa^O^c1}t1w?a_rRQ6VO^MeJ_!hH zP{d8x3a zWbED~^)V}rsA{KGej5E=bF(H{onhrk?QM>yKF0xFO7sO~~cfovv(l zFmt!yqYlK)Dt9{Ss)g0YV->6?OZ5`{3HBNp-P~;u71;8n`N$Jo$O~)VJ6+btXt7bt z-{TwCp1aVb4ueWbIuv1B>Dh27KIMx7wZAS4m3V`Nc{BNT&&~VWvZJ6a0nD%42@*?fYhm;mbn|lo%=aBs-oqvsJ`lrc^e;xVlU8GFighuJN<9phXalzcNvQC=$E(hpbHfZR1 z6f95UQ_u8qe#{ z6Sk@1wCr8`6E-QIcO|!Bq5nM(^NYEZ^1!EG@y_34M-u5M2JA%@Vb@*gQ{7skqm3!@ zGIq-+D{8st4r>$3`LYg45wEKKT{2C?f1|#bLi7=Gxo%8HNLjDxzJNBS0v(&is0rzu z)$;mqLJCvP+lENluUVI6+@wx)GR%Oc24)m-kE*4|g(SZQIuMZ(3$1(I7R-rdl^1%K z5Ueo8J^Q*I%S$6k_X*nPKRbHy<#gwkH9WyMPZIL~^v-&DYBk69*Hy$wcRAH>D;VP4 zN8V)SjMtZ|{7M!QElA^;{`@n^KTocuO|%|BM`-+nv83kYZ}*xO&~g_X@@AfugxhrJ zD{ppR((;RRHR_dqw5jtbe?i5oDH4(b{SjBg@5M0Xs|ni z6@5VcgI-l^uwCv^TlQfgLL)UwtXp+zGAlAfbRLo8m&ri**n2BM9mX%+geTUiiI zrDV6R>NQ-`JEH{ZA(32yug+d+AfjXGIw=^h%z{pBRm%~$4}FcexW0m8-0;E9*=N^P zaa{Bh##cB>{-mp>f9_O8$Zp@Q7Kp``Z{9W@Hj_CP&OnCI3j`JUqM;4*eaH7p{DXLQ zcrrTya50d^yIl0FIM)T*V+~RiY0R&~4bh&=4y`B)_4d-;dJ_lhvT8FTDIdr)I!;xu zwsS>T8|Rcjk(M8^b8a>oYL_b}7ozaw1^YVZr{~TsX)}h3m9o9)f+Kk0BxiZO`FNg| z0sMpPjJ%&N=pY2OX>&^xr4Hk=A6{vys2l)*hVTu$8aSv`H{{4~SL#%=lCXmtI?x*) z6gz0Ng~Ne|trHGZIOHP*6ATm$vtn|Z~q5tvD&{2tJ;zc+`{Irx5U5+vLao3ZX+^0KV zzcjyFO&Py4d>l5lfAKw@hNn;U3PswvQJG-YYzCOfwKpMfMI-k0!E%@LJk0;to%ik) zZ2NXnwQjrxK(Ya?(wJJ6{_E9LSC>HGpwn<29PO%bbP;4$_}fKD+kzo#`C|Vmj_~Eg z;tR+OVN;P`X|t*sx(fSZeB;Lhg5+E;29>G_`vV6&qCnnt4Lq3x4z23*LmV4zpIF(v zZ%eh*_V2!!T&~(H&R-F@(P0KqFg!>Dvj_|PIdxwEmoQ`j!9}`18u0lY$s^0Kxk$ok-rFJ| zscx0&CDAd}H`jR$`~xz% z@)SMcX$OWz0M~SCthU1lMc1sq0zE&<|9}X9l-Cy)Js_w2-SPIuzb*3WoqPH9RV|P> zFSui@I(QS!ErK`7{^X=t6{*{J&i_KQF8|7MXi~YU`e8Q2`XCDDbr&W-2K>Ct&-Z0% zgs1NDgMX9u+2Ru$XXE#iPPzvAL8qDBG$;6Fw~u2Ea(7& zrNjSn6}W48RL|zl5H!GcsqW*Y9!QRDBVjw}7mNRZrY7hCv*vwm*6mk(MMo^chPH|CrOZHMGA4L{;~;&+JFH=?*=hshe!b_eNZnx40-PU$ zdReuDS2NL%4pY+k93YG)4GWKYzy6}`|1tH|QBk#Tw1a>k5+WeYNHnUrfQ*W)ckG?~;R zHhEb|GTRfkqF^+}_Um3JbnQVi0}(?okwRPU!--i2KEqBaUjVP!>1DjbCH+N_X0`*x zUKgc}(X1!_T_c0rN!MNakQ~D$NYt3NwExAYy30M`-UV*cm2-YuLfaklr#zoR-T@-; zr%v&;Fb9M~lwz;r%Gjr)r@BZwWi7WzN77P%0j^aJ`^v>GP1~MEVH#70a~pGgsLh-| zcEA=IV>mw_LPUlXEud*vT|8Lut8IKN^xLAaqL&;XNl8%dR9c%*J$e)$#o}r4+>Kb{ zIHtn6uddQyn8hnWDOHE9$g_YpV?vf|kBFSFN}%0S!|RV*507Yxl5KH{u=mGPTyOI- z&g3tt{ci+xWV^_jvf*s4`yMBQnT%iwMsn=M73iY$BeQt+A za0Rc%g~lS;QB70Tn&@v=k7qbXJe>FT$U}lcrf(Ob!?vs{e<*rX;J@9a+)9HpH`64D zR?MRpIcI8zaht^UlDEm@t9+Ft!VtiSRh`is6toRXNY&JEUG92+O$D^x8aK6M z;@Sl@^{ZuHp15{bhNrN+5U_Q;7D-Icam~qRs&Ae^K9-fF{p9+Oaf8?^B#L~Rqo;>o znSN?PY}y{k(re;O2fMn!DC4(3htsf}ifWL{7CR~w&^c>T5X{#z$D!6Yxp&jEfk5tb zi9&)735h9r%SELP&V~_CE-%y|E4T5qVd)3`vXv))XojjX}*v)DxBN+Q1$f9LR9Y#LcJu0hc%}B;MF%ZQK)l{lKNf(He$&*SUzUWiz zEEI&OFzq^chlAoHRi{OtC2FpkYTcT|8AffLp;)fd%mmL@=3$JXotaoZH?{Zk@?K1z zTS!iR!~4wJYBxlby@iL#5vC@iaASJzH~e$7v=8mc8~HD&_G8uyTk1p-VO<_GW4Q<) zi;J~>=VgM0#wxvG+J-VG3f#wjR!#z-rBHpL6HdL(Ec{QR={)GHV!SZNG@#4LB1dDo=D%MRG;TpPz18xS)uLn)`RVtb86*XmUMzys+>Lu_MZhW9 zN}S$Z?>%=8VEGWxIvv_>+`EZoHgtvBrh~XnL8v1QAM8_H!^rZ3&`{hfk5;zo2GiQb zxyZjVXd{}6eH1rG4M=<4Q-kyLm4#cv-j9Kp(ATnh>Ca1}H$5Awi+K{=X~$v(^Ot&& z25b^K7f_FrEQcpWy)fDnjduY0u40LERDWCt+CbMT09A|sgtsT6>D>-SEKU$3-RvBPHuhG$-L zlM#b9zR50GU%Qb2)^E&}6HtLa(H|rEdftLd{YMphYW}d=gIUD|hxCKksc9_EyiE;3 z`CM79D=KqPl9O@ApEa=s(NoVRmI-Wxx-#An)69%H=>8;%3Lt_gki=My)V!At z^5Li8fpzp=0Gp^^eRPZUWn-kv7C^-UtiqKZP9;L^cz2>a4}Byd?4h8MLjBx$Fl7q# zs+Y92#uWigS6?M02I0}V?wf>vK@s^BSkq~V7iMX`)Mx;*7Y%QLUqi<1D2J};0bigv zt*3*A9&C+#VUM6o%9{mn{e%qXo}>am5#a8>j!Mou!Xf)sMsO7S3!u*v^Ww$s>fn7N z;08#;DRuAQcM<1q;73-HkgwqLXiL+e?H|x{B4C{w4Cf1h0xw;ATRSfD-iQ4cnbF^?v| zjn!g$UqSY{iGcxh0EX3)yB>1aWNEV-!-e~D<05eims5PWw{v<{^)Owifg1UsrZD?>jzjhW6wn^ia^6Ht#j6din1> z03Sg{#IpU@&2vO8`EGKSRU)-1?uRbrGhVfon7;Y6NxUNxXW~(siIZwgNkM$~P236Z zteMiokFq(3VVHN%ZBq8`!}tdT0#4E~nq3Q7?}8~V`65=kUba}o5BV8G)*7dius}xV|4@9`@FBYB`2eH; zZ1BhETB!?0^oF~rp)G^fC!0dO38a-+FS5lXeT9aFDrOgz)cq45lZr!UP6;OpmV=Q* z_jg-|`iYwfQ>VQXs=Apsw>8o)9%d@0Q5mQ~+a*Ver%>)~HoAQsdjyxpQL(7gTir2^Y^(pXi zT1fz|7HJcOOvKSPx9ll-o?*B$fsbX+I)_CP7Y2u3F~OL%*2pE%$8gVXkGe-;%$``B{->1N%Z3 zARRGl(`as`enLIiuj}iC2FJk1Ou_D4==$yRnS_Xi;UFz-5hTMXvF3(@=Tc z?a2D@<7fydXlcq>lzSmJzJ@P7&7D!XaA1esC+cvyrXXB~)FzT*etMQRQ1IKW42Q5U zlNok@Pnpu#{*`>HEdzJJ9NEl%e7rwZQ(fSpBbQ10W6VHl6iGL9F9=+=5bEXfe%Mh! z;&oEokcP_YjFl_OuQzF1HnvI+f*#q(j`u&Rd!l#epOhA*>RYtAS{dTr-uql~TvD7& zis{~64sJan7q0N}&fr{^Xu+UMX!nb}bGtJQd98%x$61Rf4I{}IB6pb3MEg1C4+(vy zv1ZD;PEk{mztUxBNSaXx&zm1e{BjE06HdWgAK(>-f2@-nXPTF*YuveU4dMe=s@|4MdAuH=l;Sm<>T~-(1iNi{#;pt9_#U!-bT^Itr=T6Bj56fGY z=Cn(s(r^=AAzO%c)Da%X-KAik%byccad?@bZi^~Lrq_NDh#jniE4!ZTW zHs&p;0H8zrGv8SRv(Sn77;t75qUUO#0Wys{ytAHY-HLe3kldYF;A54GDi$LWhINK+6 zLHWgre!Y!c-rP~-mr!YHY$88y&XMX$Ws%IAmjqExP^L_szXU7I zCv!Q8K9U)S|L!g>Yz*JR7~)`}efh@|n|FDS}+ja<{5!pd0>dj9PgdbJDv?~s2dbRG=rD0`DgSY*IS+pfR1+6 zDZm#uN{hI-tFT4uCe%!;xDVa%{WGIRSI&Z zdy+`A_0{6VD{^u-2vJvLCeb4h?_kq_0f+`RnFu}N(deRREZF>$dE~+doJwF34$FEx zfeys{|H~y5Gk3as@NqBJ3;yn6Z)Cks8@w5t9}zgLyN%jehyh~?+%R@&(v>8F!9~nry=(6o<;X5@1{UunG)3DcOv*OvJ)gxhQZ`*_( zL}m86;u}l(p9I_X@>el3Q|~UbaZ-GY>=rIofIjbieoB4g#G8JnQoduu*^5~@9Qy+6 z=_-bCTl%S}(R-6lfeQzI{xb#Cymow5Bxh;Adf|$w`RiOkd7UCB#|9b}sN8W~Rd6Qd zoS$dk8(gnd8D8iHHKdYp>A4SAd>5=(_ee#Wh7gw{hLcE>ENHR;DsbBglXk)F8GK!p zos103YUlgV{;bATW~-dlr{~x1QXb`hviS_-gHEYH&U&V(O%b?IfWi)+9cTxh1=!Ti zBVhJIdV>HoK_6~nfS;Y0MU)Qo3`j^vy@OLBBLau~epbPz9aB%XpxCiUf$xgaVvZF= zaL!j;{Y{s*LT}19U=q&2ED#rvH+}gp0}LU9T1zQEc~`+^kR=eWsxS_oq;TqI0ZdfS z>slv9qgq1nvOz08QefFXyZ~)d1rFQ2z88k{TpafV4G!)-hj}92i+)*;Z zfZ0O#7Qiq(i-!eWn4UeFnsN^=f-AH~EE-xz4bct-Ze@hP&B6}Ks_pAIT0+zn^&rSi z5QUtlWWa-%;b2f?E&qGsY6KS;&E6Dy1voZefkgM`4!rYy zKTA_JVB80&< zPk+;RW3(qByeAtZAF>hXE?w5$G0+~U_U`NU;Mu#$&D@B9CYMLd-BlUow*AZoO_Kn< zP!y<}Za1(7C7cKJ&RxceEe3CE4x~SXa7Lu5QByPeji&G3FGIjX3x;K8W;W)Ag2#y_ zcPbW`+PC2M!ZvKm=z0kg6(W8S2!af7$eY2wH)^!U6XC=w9v}z4-@-E4k}3X(`NlfO zA3JJzd^-mwO$an_!I$3(4XOFJTeSpBSKr;xVx{*17!%H{rCp5b807izh1@vS<%;h> zBrP#?2bhJBuqyt*(}t2XNk&2BhlxMM8M9EK+Vgvv0K@k4d&YzPunv#Tw+7Hn?hm*I z%6+7itOXrq&*j?uhiS%(?nMO+L7u>AeFkSa~BwBcVp8dx6Q9-jGy6ccX=QT zPTgf4zg1-`BPL?Kxh81LhuN(t_SJl{8oa>mdcas77PcwPz^}KUm3z>o>L-yT86;t% ziexJ8dX|x@a3RH9^ueiNeS2Ek`ah{5U~2tL%JLOZ1I65D)37oxlI}#*Y zjh>O2=!+ku$4 zNBG1%!2!4d7KHLGUTWxwSZ0?5sQcG?r^jk!J z_L^-=a!!d>zLOSHMfu1F@?}8Q>!D!E>Pa2dZ;H2(9a#C6_*2{KNzxZ5|0s#1G7W1z z%_)B1hzQ^%ITDB&=rD-mK(Ba*?Ga+|>?HoK!xbr5As#C?zJ?yAMCIm z;;Yo_jj?~qARkXWY-vn?F8k6VM(&ptIS^a;v(**ju%S{m#XN48ppYMSzwu{Di;EV} zP?W?|nYAnb3~p@-%eBwLRQG2kl?3@zKv5PNwcgZJE{01*h323=uZcrT9g!9@jJtry zJfcOKWl)PKZnJdlM6D6|I&s1l$whu>De@jgXY;8gz9pNlTW%t%oH#fzw=Wsz$pj2_ zxE&MugTEbBGXIIF{>&zJzKZcHt?5j%>SOmZptjmfwxJ}^4a}?wTGsxVO5c?KlS_*nn1Z0bgp*?JX zMW+O!x6V)h&ad-so=2NCE^^=w4RxV0x^WBu3SYp1iCp9_!EZ$&zkorsTC@-X(UlUM zegJZSWpV-Edu%8|0>9aRR)l1hCRI|twe<@rMR=$HlgW+~=aN4lpv>;9X+FQ&Yr z{R=Y3l1j+&kK9cw;B@9(>_D;WW+2O|CO)$bqN!ydhs=;vL$>gc0t8B-0N8Nz!l|Z8 zuS$TH{}xoifI6;LR5PmmFVQJY^bd0z#&v@a`w$&P=g#x+9wnum7#PNEXfP{~W{r(F zc`6f$4==E&*DLp_T&#w6%iT{*rR!KdkPb_2f>B^lTAp`sv9<|CbY&5gy|>f@z!=mvLlHeZltQ{&Kk z1L=de6QcZrodz346%I+djTt-kHBAmQSE}^%)PC-t!Btn4%UbWntbAW5TI$itB9Md4 z;OIsZskkG@vC>7WFJJMb>7>3=_DFm8MmTh$Gx#Hx0i^FGo{(EhB(lgSPnO=rvjOFQ zR4`q~v5nsqF=U=2``a{pts*7U{`PCNHr0Wen}{pn1qGdUmgy_eFD@0)&fq?QA1k*E zKXALx`G7%pB@i;r!hBZnnOy-=Lto0?N~TESFRNvZ$~1JDJk-u`ael5Gam6D=xr^w2 zFt!zk_VV)<1=(Q?&jDzK9eIxYo1Wrf`s{+u;(n(N*7>%kfi&c;w3Khxe>xXh_Sj_7 z%Tn`iIN*|1B02AV84KFR-jIJ5DO&z1p0JQvk}xjYNNyA8QT46fkjh;*_AJ^HxTwea(oFwMdXXdBRaCcXpLu4$q8eVPc zDe_|}%>9EhLth-sOY^FyU*xj|e?y%BB11ssE@tXQ0dS0* zwL;Iw(^6Sk1Hduq9^DQ2J@3_+g+t$we>*BYTaGHR7s?>N-uxdxyaTLmY5tiwiV{Q zCT6o*oV@y{@7b&AG23dIieuhl`tjb_bx5pQNt+g5JWY?6REc)eQn2R{zl-jzvr&n% zaYSJT+bg!*1=BYcGMkC;AzJe;YzLl%GsFJPk zm8zYNnpXflz@pqnKso44*S3%Mm0d#|Z3G{7B$3~zI#lOn8ri~}I-FQp2hLgU=7Ryq zw~x=2!+iLkcUlsK&mO?a2IG%vBbOI&noo*D>hEqXU;I@x5&F&M#v5ua|o9e@hbj;3RpEcp);Wi zw_A$(6fs~%3S2xaxG=UTyx(pShAP@p8??{0^}!fL^-}wn-2r;OT=b8M%y{bhyO~zs_jKxQKm}oWG%kGObPWBU zkwcUTuHS{Y2qSBp7bbXew|K_u7M{~|tv|=|xkmN6^Jl?s-;&vWv<&)FD`ciC46sm9 zc)1p)A$L#^o!`DUQ30rCmH&&lJ43xZWdVSVfh_=~vVLWFuqouW4;sbnA+&=KcZ6>8 z{fikEMDWg6oNP_$pWr}%U~&!(Nvp{9!+VdAs#)y5{|ow&PmfqjhFcBxpt#Ia0fx^N zyx{*X3l*k^@a?=b`wJRK^da6#hd03ff*O;7d}5if4^=PXQ#JU}9dN#&Jv83dj==T{ zKyV@D3sGyv%n2kB!#kt6T z-U+Ab01MsY#=yV;0LH?!dh@TI9Uxlbo@{7+=wuJnBmaU{fcWWZ>r)f5I^d&MO2DlG ziiMc7-2wn+7vLdHVG_M#o zC^A59R#U(0>Om*_vhHr1ySEr12k@+X8#y0FJ1Ok!UIeIfO9nf*f>jybHVRXczT{3U z*ZH-w%oTEb=6J91VK<4sk-vOch|rc^QB(4P3L0$Iy%k`(P3nnttl$5NgCq7i`)m>5 zJ+?LC8FYU-t09^-tudwj#v(nn>8H`09bi#9X+FqqK$#*Y^n4go_<{FO|BLQm)=o&> zTl9i8GBzo+)c0O@2jPG0qWc@>s6S%0hS+~B3IPXTKm{y`2ag?CgL|}Nk?IpG=I$(G zCJA>777@tm&f~6`BC{l0tY;_9R(M071m2+eNME5sH(duM88Y$Xq%k=SzSDXvZS{#y z>~7A48yAJI9&q@`7KjuTW&4|Zq%m>MQRFs{zC*Ld>#!3IWS>ij_xn+K^qox8seo8M zC3T=Kw>*4-=i}k6mHo3KSPLgti~of^>3Zqb6~l-zaJKE-}ylvSd07j_P*a zO;9I`&t58(ha_#io`J@yGpX4U9pO}%oVR@FXd3|WkRGQd19HT9sbZ3@158Xq+uzgc zO#ph=9F_0#n3hge3?`J$O51wogE+foIgRa9u_sZ}(=tKit*o<~A-cWy> z#*JskrN$2Kf5)9xV3lB^8nDH)-odZ!CvwN>tis~&FM)AuDfsWJ0zlU*>VD3}+@I!Z@4wg6 z2SA)AOnOyZV);y2#OVI_Mh1mX=hbwlKy+*>sMR!EetWck_JO>hZPj9wqH{F*X3*vV z>nzk&$K`Ri@0(M($e)N`p#XdT7Wpd=Z!uoAq6f1sOrWTRAVAbB_fwGnydV#&ZQfBq zp3sXGv6S7!bRX^-glWF6AJ455am_xrk=L6#vCpO=$t_I^fu>?5ML;%#ca{ zB}C#XdSkt$zjwIL(s?yAu!NaF$h9PXD+up+aowMVwrQavXZ&za z>ZvDYtw{~CdY`lNgMpZAgABG?eQl**Qg*S!$A54n?iZWxPv09dBHii(V(z>_LTuKY zZU?#B#T7jXk?$WW8Fjb0$y#Dc0F`(voQqGX@|p7W>byVS(iVye%VQMqhI7d~jq;S4 z5hK$G9YHEU=5WbbrJ~I!N%z<1^vi?@q~RwH=I*VjcU6>i@gr#It3#hORHj1&vIg2m z)h-5u*BAB|Y;}Jv$fOW!y-N>d@9I}Q7YUhxam>hcNwADNL@F~$I7n|obls=0P32(B z(6?)4*6eyQr=qRHaAksdz@Nw9(!=Dz>W$e>w|f%M%J#$m6ic@3p@g3B#R|~sW+2o$TpzF(x3YYI6 z(FA<{#VKGVoE=39Lh6du(5uSiXVDDE=@f)Yh3?}rLIS1l>Fk)jlEXma zd^lfXe}+W45aFAKgMe#&bz`U4;2#HSS?D7cVaqLY?-`JRnCGiL-j&io(AG!4lhJou z2DJD{<2aZEo2%7eIgj%?8fWJH78VszvPC%6EBjSDvj_Fg^GGQ?>($Yi3KufqjZv5e zXsGFX)?FFT(YOmK>1Z7FD03m9yJ=AP$++3ZApkCB*nX16gXh^e_^}EuX?mON!uh*N z$Z<^v;FKquMHZpf6TZq#r%4LG(XveWYFF~ytanS#M(Dv1{;F0Q|&8@3*_QhGW*)T|^j;h#zh zi)U^G48fV_ZGSA=RKDPAQb;&DzD#&v{0j;o+3_(c@(tBa`m8T?FsUj`6zmA&A-&+P zXVleXub{B}QKqVHJlkElGx?v+#XrF+hDr(5^T;bB!dlC(cCwT!q&AfWXapSLNqaqZ zq-5ivLAF~aw5tQ=;I2Fjn}TSDtteG4b;(VpNF+JSaon$_Kb7(en*KOSfyic%<&>-= zdkg3+a|41IxV~qb18N$K{QubWQ}VdbRUKs)qU&6;Erf4VfcioifR*YY`#^q^H4E{; zO+YZ>{`x7`{{9G<1D~$w#95Yg+`kxik8hjkc8^`|> zP`&Q*&rESjX8?u{IyTEthzvi39_0C%#|Qvs>@ORe1O{C5z*n*Prm-asFJ&$&2? zk|4mdcJ=Lsq5e=Gmrn`3F`dxPtL|@Z%RKxIf|ytuTit7Mv)(y&Aq&6Q#6i@X(7V|ZeD>+E zVqR`DJs*8E*Rj8L4Hw)R@6!t$q|THzl6U}{rd~=;b8Dpy8wmUvZnc|!={mtalbstS zLraa;bY>662cs_;*IyGN&?~5?O5+EUPMfU=_4D!B@wn*^p{P^q#urBBZ!liP6qk9ny z8(X@sv-7P4n#1D!xZaZe{-gZl1HI)!Iy9tgB;?68#;^0ijJ&DD>1)wlwbT;l5?pYLAfaCxXSQIbN}~fA=^M&r7#P#54zX7C=p}*UKlX8Mpy%+Po}9qU~W7g zF(+ZEt6k%)AYeN;>ldFcwgvy?f*$C_pd zMSpg*crT5DbrtbqqK5$kv(ZA-z$MFIu;ye{ALl zJ({BjYDxMwZFHm=dTKaez`54Fb6J-8tW!RUOm7G$ z#T*_q)dvR;?fVP7)KfmOe=%M#A-zoXoaHabO%lTR@Ely=*(13tW3r^~d!x#ap{(4s zt5vwdsdF5xcdB1CK6z0!q9l@|498rg-5wWOw&CO>ip;8$2Ksq=W4b%+jcs%}>LP6< zQt23q)PSP*&Ln;rmb9>(zS18*botWk-rFqun1G%OU_GFj0IJ%dI?gM`!3v`swg`=E4 zy>oHfsxX)Dsgx}?)W0s$ThTX^12U4*!p{~}@?jr7%a@Sdy($^phxSwl^UIrhsz zpFreV=k``mK3Do#KwNxn+Gbox4cOjye@NI#A%ZeZhY)3dlf<+k!4A&@sRy=fNlH6M z7g(^q$_`p6HnL1wEdTs+PyXo|Q4a<9&-Dx{BGps*8O!%)_f|xB@GhHvTYDJ4em^*# zC3l$eDGpUZG*(;8ZnqC3dNg%jb7pLI8CP5PTbdtFqyw5)2O7RV(rf|i=e1vH z?xae9h|&y=E@S)Q9Oi*yUlBsLbKmmu!^YKo=UHh4SK^2}p6CCZ$z%K8TcBK9?}3v8uC%K4ZF8yU?^L^VnVO(Z__f_1E0H0aG4sZ4 z(h8*mq-8-5gm#`<7kHsY;onuYfPzYtw2bA?N+Cu1yOpbg#}B>v(U484yxfey-OPV} zDbRA9_n&Y3pD|bYjM8bDjPUAwy0*gV`wO~SR{m$>RX#uO47~0&AG^S>n2 zORGJJ6qdqe&IuX4w2VPQ?z+Sl09k_!=$B*aDIa=GeE8BXbFo?iDk}2 zip%z4=50&{!@%sINfXgEizxDMUuI%q#ZPr2hQAq^=i02!7tB-6;DShrXmFpELXg&} zDf!^f! zIg7nMpzgqNh9Aei4GKgTx%Qt!d5=OigPWR%IY4)ic*=Bc=DJ!$1q|C3(@I3nx0tem zya;=h3Gkes(%d;oV{v|^q@7i{Jlqi+Ul_1tQy>yAtJg5gSQJ#IgP0k+QCzss{GKm_ zhS#wR$dwdJT(0(cpxm1L@q~+IW3Qo8Wu;EM^nA`MrR`P4Rpl{V%;ERP<-RE!3p1R9 zDR7+`GX(8WnGiIEM!&s*Y31$(@bepcaaq2C3+b~_xLCSj>Z8v|Yz*(&%I<^G@R|7dB1U}B?p_K&~c`ao?st}E9 zonR8)&Uf2S1=9mx0>9Lh%B1fYpaaMj@pVSn!z{R`|J&HXVFH4C_7h;eIRWck`);-6 z?USOg(EBc*MdK_5lHV7yGyePo=hKkOjY~8*&~CH|9W{rKyQHh*tuO1bS+s;u9#aP+ zT#&+j-Vq}|Q65HZ0qK;?KhiUGdVQ&{E!=900tH`wrN0~(UuT)B5uG#TLmX8j#D4${ zSzCnn4s2w8_W;85#-Szy31Rpf@4liI(xwfWnt&{ITZ*2P>G+K?ohkt%2PYajW@glcNFXlWk z>mp`YHPLAsGC7}bZcXjtt`Oy;MbwY?52T>}8q6|t&FHP7iF*jY85iD}O) zVRqLs1RkyEC=l|E^=4dJ@z+m7QC%_@Hf-t33MkUiOS&Z16~T(E*g+T>d?T*V|91tY zt#Ys0;Y=)Bu4<@ohVlsXEayQhwNEH4Kj3>d{aBPgAqSyk>=1%oY|v9ODImAxzat&d7Gl8fP(>Uq{@V?6~*^2(65RR zkI`9Ty2Ux_OvM`HphNl8b$nBD1tu-0Y3xZZ^E7$g9~his`9&X}VNS0HEC7la3K+T! zNbK^GJpSZT42Apt{Hd7>%X*{VPBz6a`MaLwYOr;yf6nyR(jqAe<{Cc9nPn_QYEmtnyTI|a19PH*a3Bz=stsPrEz~hb>mxOyRe!FVS7FNXSK& zqF{T~qr4Zq_qXNyfAp!Ata+zJn`5VgJW#zSp@#9MdLwz&KV=hwk2`qMPT!=A4+wD@^Mz)qaPbb7S3 zqgLF4MS zV;x-C6l6ag(5a5COb+XSi3Y0`SkKwVn!wXv)6|K`SY;2+t7MDh7xWsOfh~kLV1sQ$xFr3r%(31}(tEj=dp@uAUSk#6UwFS~1ot8Z; zHZ+tt6jw*2Jj=#-R!#O1Ek||n$7qSdhS#>*jkAXCpX&Scgd0N4izuhJ+S#PWSF?@zUCv10u!hAUolqrKY)8fmkm{_rs zVis8*+t!8Z`paLs@el&C3t*PCaH z(}(*yG{1N`TDL`-$OS0WuNH#sdTldM47nBxhIx(gmZb6?)Cw;A>T91}2O)qOU9c(- zyKY<30F8n&R%vzA_ar9bXc8qHKH+HTwIbib=~SN2jWT;pRve{SM>{)Y!vo58Phlm` z3JxOb7gY09Gh`8`XqN;*@51W$=t;&A&|{z&FwmIaRQHPOGQ#*mPpBW4ia%be2h&Lg zbbuD8ua_|{N*)rmjb%xhq^NWfF*ML2dhK zrRdBS^OW;xaNjcPE-bof*$Hh<)33Hb&p>y)^tW^Sc)ro`R-7XX#UH_{rfi^1ZQup5 zB1EUbB~D{1R3dgXYj51dvX(7*$CJ{IwH_&PQaNiM?P>^a<%1qm?!kfR(fR(ZU`$3z z!8j7};ecXu!LM|NC(g_-MK6LE_ss)1`3C<1>33t_QwVbdDs4anuO0r0DbNDG)w#)y z6K<<|B@^;!Y=R^>i%4l4**OQ=w~$J{*qL_B=Cx|9;ZKL%KAK`fsH}b8vLq#w7!0qM zw9u{kUG9L3nV_5M)Ww!-o}P?uSe_|VcZ1hSsuE!|8tvC(ablqLIdCn?q=m! ziy!KD4~x_mPQ)dvlG%rY(zV8R`Z)C?0tb(I%gs(s&PwK1WUa5Y)8nleWQe~1gD-$2 zS7N~*Lk^IJZJB%q^RZqoT0YQU)_bMo#d!-3)!naPrR``BSwLN5DJPKhHi*u86Pzbz z@D?@g-xc`kP=#Mle2esmqyX+VOuL$0-~N+N1#ahsbmWaw)vhsXoVh+-*dkc} zVzn+!%56yMy>P5gr~VzcobW?seYFD%3&sgr7KhJgygzwZH!I^>^FpQ;_LM;ij_eV8 zSIW$%(j|9?+N9)I@T$VYPoysI9FE+A^|LCOk$YP{-!h8iIodO31jxizQ3I6ZhBn*e zdKw)pY~0LYucANlzr4r9*iF>}yRIVtwnY97#?dz5$>Yg!Cms0HguX*mzVS^2S%jg1 zFv(0!HJB$iA>jQED06Uj5fbI$;7LO%=0@KjTk@LUqtAXSZqQ_I>bY%y+d}edF-Out zmM<#P0~m30xGD>?OTx=eF^T#IXaUF9zV@qny-M@Qn9 zS0lj0d%M|OoYHhU6sG`WX!7y(`AB@<9*q=cWf7{(Z%MiM@`yOt4Bt)x$d`O`5?6ZL z{$;O^+*1Wov@5u0r(`f^6T!U=!P5b6KQA`r*B=C=HR|2BCh8vCD%jG;KJc1SXGXU} zEQzQKm-n47o4><=H&=ujE-Q$KPluZRMDO+7a13H`%@-!&S8H=Mn$!DEZ9 zPq`c5W5B9(1bguI9(&@fRK^i~n^un%`1}|2P*$BOOO^0BCoYs$FG!Rk?l#TusvoG( zhb!0rtLYitEmd*wN<7XJxBLZJ$5Q0njvC$HhawOdA}clk*X(;BE81TU)z^%G)J9hooTXN4 zR1TC1JZ;Ap(NgzZ_0l^ywa~9{`JFOPeI#=M0HE~7fxl3`D3NN;|B31<$a$Rs9q6#q z;T`X{U)C{^#%fNg_RArQFu5pFYTcTy>C|Gop$&wdSoxdV~wnR96u^{gS)VJFGsr_OeI zhVVR8r(PNS=At&MRSncwgMqb6UA*}waQp^x_XHhilfnY4M2)?(Vj7}<1LFg?QBy*h zzO>L4aUGKU8Znf15gVlCH-V`VpRyk>3uQTL)Y|7CK`Ruv4fw7*f$5fc;1UvYvuBB> zj@B!>Z_>#E9_#s7ugC3K+vgnYEwvfK%vcAWRc|7=Qh&xBq3O*egv{9n0A=MoxHbI+ zc4WJ&yx7fmtz-jjgAlX#u_MRC#9+@BjDfi?r?%ViI(f@soZ?EGevWe=Ie*23UE?ll zSA%cYpaYdF>&u1=Ha0&j&~l`UU9@3A<OX)%3|c7~*IAfiQoPWcZY!YcaLUfs;tR0)~w)~f&LDnlWyi-nHbyX|jfiyi_F?-ZH zZ^~e5m8bb-}%uT0z*!7g*@e0zrRult8{>Vt0LoGwNBvTy>j<&y?aSKp{Vm&HyMn0RWPZTx(zyz=c$14YkeSw6c}}J_XWS z@Zx3Vr}B3lExT! z=6$b+8BBKS=Z~YdLZGGCn94`8e~jhLoCFl-LZkA2p@H=u=F!{6^>k$to{jW}%n$es zU&Jcc#H1b99s)IzqLemAd?TjMH#git+>)&37cNocNjxh;;Tkx;Yb)pFIM})@Z)%Qe zv2`3NPDcb0keQr$b6;=6Hy3z&PyM$lcQHF!^`RTPR&FEDUg7W5JbZjVWt*llM>kgp zezz70KG5&%iwTwbBhr|w7sJPPT;>8K#IjC`Z*IsR9u^C=bt?*5#Iubtn!`c&D3SjM zLqWX0aB1;MVr-6`#d~kW4~9vqG@7=F8pV0b&ulnZeOX6l{(oBW8KIKiXNF`cA~9D+ z7%E3lMF3w(7DdXR!kl@m)RCiXsjIP0BpAjG01klGr-b}NKZX231@vV38QF0d{y5K3 z_3k~zXAzo)M9lzwVQ)NlHt}3U!K0A_qXUpZ83wr@igAbdcc`{GQxOOL+9>|Dhw#V6 zv7ZcoXWg?IY@cErXEB~f<;eO0TK+fHthFx$>b97W7lg8tz{-%rKljZ5eDUTmKPxc$ zF{#%6^+p!%;C&@;@v7i+ijXY;S%%{Fd6GZ0&dld%23F*rJ!|Tl3uU#jw}n>$B31nb ze97U+Jns-#FQn?nj=<#q04nymJWHrI{I|w^0RI3AcLTYiy!Kss_5StTgZfS%~lf<9zI2GmXdA+jE%za7CC)$AZpbtwrrkP!TGv;?anm>t=PUJE6(&=C?vGBx{`SnCYj=3Jh6hSo~+~4bp!cU-K=(|)*{mY?QJBadCQQ>PZ$99 z?0VEqB=jmS=;}|4ubFs`0qzw40F70D6l$CQ0OR3QdI-g3vMe@|v5DP;F*3FsfLM-r zP&po_=uKL!!N<(RRl;nOeWP_fxuyB9HlBW_#_mFd(D)z;oeB-fG@GN+q=Z3YX> zxC)ua%upVH^MmdkJwksF|MbsI5#kFvT zC!2E+qhcH}=g`)boutr)5=&~NDmD$u9ERzP9(v^Z4z+$;WM~m!@{1c-AR7@_?v(Nl z*iKG8!+I0at(l~j{B9Qs=U%g)^`Uk{A7O~c1bY#I_<%6jO28^yK>3-X1~BiPtCGWN zoR6hclSwaX*AiSZD7R~ZKF<9!h2(%R$Gu3`{!O|((hcU-=K-Y*Op}ra25z{=AY^Be z-iaWFS;|A?G=FH0+zqj_5fovZ{E@#?{6L<(gGgsLt=azoXWuocc4tIV`;-l=KqPQZ zah|kjiwE0d`%I=Niw({baZ&4x^Hud5ueRUZToHpTjM(G3_5=A=&xGQ+dx;v(=S*4g zv+URS#NhTDh7Tju8UWGOv>D~FYwb4X9Y)eVU7$ZY4^~6SslFQP_cog1=_Hr5x!v-0 z^4J1$2jR^~!5dXnw}JdU;yC$^Fn`hR5BElRT%Mg&{x!%QZQ}6~>lSwDX(Gt7c}c>C zAA19^Cp>%NfIV}^Pz!Nmt40ZUB^ki&-}+ZQrMl@}F)(C(k5C(w`#8w`Yqh>hU35$#1%1aQNY5Hw(^}#hhl#3;$ z&YN+E37D83a=6DoP(l9yfmI0e2Z`XCNF;5|6KpO0??d>EAI6+2=BsM<(<;ahn-MnB zH}{JD)A+7GDxwW{)0Z?;Jlc`vlSA`Mno3%-1)`HQv;eeHQqVDRNktS0DQPI61*IKn z1r)$_6l77FKrJOLB>)srMF13sttBa-Lg_Y8X%>ImH|hO(8(IeyO6q( zxO$BB6<>9BUMAD!%$FMexf^OBaF%foHJ8y&2vi*O{IgtU)4G5)A4rlYr*m^?-dZGq zQe2r8x|P7^Z}E2+tF56;6qBgAhEFGJ7L6n!qd)S{5T9^&KhB+?U);Hl#wn!p(?4V$ zbc@M6#4zd=Te0G+CD2j|6Q-{o?-s6LWwl1J6~8oQk&Wr`>qKCDt&7ddr$_G42p?|1R8=XhF%+yQ<52X1DXKrd=0A=w7Ju# zEXx@ZMeGkyKb>oMw%p6%TgQ$kJ03U6#@N_<V)cDw^l1!-kmS|Ps%3G&GHPH7!Qo&9ePsDr(fIY zcDj_Xk!N&SVw4a;DsV@r>E3`ghNF)3r&2z(lc?!;x?Qb>&A?A4_AfdYM$SiYeF(_> z>TO#^xzV*7YfFoZcKb|8G;+kmp+-0drh6XL0e|~Xj=DSkw zG;w*znIAY9IR5~FQdoFuOWzr{ha|c%vdbiXcbA{I7=w(Cxb^Qq6x!)-?%{>GSshf2 z_9mU;9Wvif)7EHXD8@j!+)o%jwI+d}z3#Dj46~SJ)8lE#*}HQih1=9)IqO!uWfkGl zBQmrle9?f4bDSS~?V^*RHqpU|l$Iu%PeD8%8T$deizzxv%CaHD09158iTvwY+U+5N z8+MTZOG~6*ok1CLIvI!ZA4Ak-_$E7prOK$t6iw08p2Oa?wW}-JKMLDwFlrNtn(pG& zqZ?HgH)kw5XOcUbEB^oj4#LB?^_q&~q|{)08@R*;N=bUGV zae?d3JME-v`Ig1oWT8_`NWuN!1)f3F?E|^?J&CF__-ffcA|{9~WfltRpgf0m(z}>& zG07+Mrs*CZ(}|tDI%H=sC`NPzJ5^ul=VZdD5yjp#%r_j-%yV zpS>XI+dqL7l$w^thTu-P-96b2Amshg)_jxt{{X#Nz8=x+ZuI?jTj>iclJapHN6w-lKq8H?94nS=EJu!=2R*^5@AQci!|c&t-M#ur z_K7Y`&zS;`lw)@Uc0Fq^SdUHnCYG_>T*-Ch7rP5F-R3#@iQSM1!Rgn%T}pF?l2$UM zTAfvRJCZ?nEt^MlvAQ&I&3qKZMhlIocz^&g?o|4(O0lt{j!Q_y$lhJPnulb7ZhX9) z5WIEZ`sR=9Zw_jD)0-18wt-_FL1T_NU`gk{V^r_-%_mIpBV6BENj99|%3y`IfDS+d zka#}yIx|q`=p~4z>U$*hBG+$Q`#qf|ZI`z$6mN5wqr$FpA;|00WOg{Naxl`!vBst3 zYz0stK{5>{{YqAM8JaM9A~C` z9OtOO+=k*EO4QoL=iS@mFQnedzC{3aw~+IYKZNzJGh4U@Xzb&>`(>rD#k9=0ZHxm2 zC$Akb*yeyWz8q@b+1?^+XL$!}~)~)5Zea#L^=6-P93Y zRrZM%WGa4qji;tD(!DmrQG34*X?lws&usqyXO*$&c+dO?6-z)b{5#Ygv}rA*`__`= z1J`49{c~L^zu2{;JOq?^P3gIMekBM$@CxAUCK?xx8WnA}*Jmr9n_rRo95s+)s^#T2- zpq967*AW$#GCG!CMn0n>@vk`4BKtn4G6g8EeAQAgS8+KXg9aakZ-@;>?4*WmlTfVn)m}doG-TW)vzaR6~wsnj7aH#})?rsm43UvJc0I#6WrE1)~cGl}{ z7TDp5GQf0I9R*-%u^Zdjbt{l#iv~EiAG(8wZ*T68_z@jzox8Jitc))k+?^A`uv%J9 z1Kh|_m~hgjH#>j8n2*B(y!TCei>rmVw?>v$=&CYJPvZ@Fyg{$cbcBm^{oD$BAn*9~ z{A(K4`sT@|`#j!Jl{~j$)TtvQJ*f=r(rqtH!p&;Bwxq`%UhKme^yBZJ)84u75$PB3 zxAu+Yy``6)z%8s~BLR+~I)TSuQ(YCk%mU^;Bf>Fx*9Culsmi!-a=9NOk6ypb#VxLg zlF4gtZ*}5LVnBCF8N8KlzsSi1BJGpYfF@#-bap9Iafw1N8&5Bw3d6+hT_qs z238^^4>lHltq4A6M;|d`>s;QcquuD&V&3`@6vadA5-Si7t_jD`(&@L5!6U(PKhfvH zyKo8+avOHmAOq+*pbnL0Cg0A5C6X3^v`P%$JX!tZNB5j6=kemBzOah=*(16#$|8+e zPF0J2nTW)I8A!^U4WMJ!IIQ&4?Y#Z|ZLpNTndUO^lCMV~LHAGhM}D;L?Q1mIAeI&K z!I2d0JT`a6e{q6NPBXv;fH}=?LAcTN3yXXiV~Mf7M<5@&yBWbF-m-Dty#aL#WD2s# zqTS>2dSlIm^uh9ffrl;B;Nr10JrV%c;bdER+;SumZIyW|B8`Iz-Mao10nQ|a4;?DN znMowt0kz@jnlBO9x;8T|(tU`>^{uZS!Y6AzK@{b; zLgcniS03lFtZxrl+|Mn{_V9WC0B5(7M^JE8af069XFOLys9)ZAhegz#Z5^SFp`LjJ zs!Vc^l)l^yhUjs?<1_)osHwowH=mV7#@3;Fdd#sd(FmfB>=Fxt@u-n-PI1U5oa2m81P4_2rZ%Vk)l{27zKg`eL7GUC z?8>nREJ|g7!N?iG$n8zj{6BlB_=-&pC5Ah+c@UQ;X=KhuKt6_mE{#aztv~xn`qo~N zqulEP^jpaqHJ!8ExP1J|xX2hCd8u^mB7H+e)U^m@Tv%)}L_x_6NXYtPfHVfAeQ6s~ z!0S|(N0t06`r=Fsaov5L;@isnx!s>mK&D=3lUsOd!&>u|;k%LJ+6O39k;(VLpb2Kw zvZv;xw9=DOgY6FTWr+i682(jLSH#cMGJ+<|3oK|>c^z%~dO z>zrob z$t3hV4%n%zuXQa)PSiDcghD$Ti0)($aW>{-@_;^L>DM6pFpmdhkcAsvA9pKp4 zR|h4b;ZzJ~E5PgR=~eBoEs_NR;PV#7Nn3G??-pPO-Q@5%CqGKTj_Xr>2{q9iV%pw$ zAm-+6#pL;k1AiFE^v-$DH5K%_nrIffoXHy7UPtyw@jQjLq2!QTp(CeGI0K3R-n@9^ zwYyl%1f(|T56D4g0Fn;e`tzLnlSwtbtKP6*C~wsg+bkj{YIPuaeLkFX$UX5jE8SO2 zj@IJh6^$?aySUU`N^+~hgY%Q=*PlW(q8W zxuLKxTP?8rB+9W6?R9j+5ocn87yems(D96W3XP+Mbnwh$V{c>UACV3oN5X^qvz{^3 z=g^9--)o0a{=r!84xlYXs=%P*a~;pmos47fJ=9f;d1ch~Ta7LVu4I@@t0Y@U3luBJ z$(tQVLVk=XTm$UQ37QD}utUM8$F!jZ&n?J{lj?r({{U*VV3IlRe6S-CPju=Wg~5&y z$ry(KbmVdBD<4nPrM`KtZQ`Cpw32)I{z4U4j4408=O3TfnyYPo=Si002yP^|wX+t@ zCz5uf%Ex_-*;u$=bwXwlg ziXifaP^Zjr8NY>3r(EKnajZu663zB|wzHaeE!IYW>`0>-*bkU~VtL!1+0A9L>U#d8 zcX@ARb#~7oXYyfY+mpvkh@7x5cU1DT+h< zPN=+}bAeuItW3I&r!4T;n@3@ppk9jLeB=(pJma@D-S}SlZ+sOB7awWTr!J#*SjUia z^urPV009&rH2xlHCQUM1H$T0#lW|l1#ytMHu9M9B4ziATM+PS(_goNt$wQy`1#p^l z>!W!7M9v_+=zDFGkbm#4KN{|}7#>?MHB_|mjld3a(d6KJvKABplj7|-o3kWK{{SD6 z@IUFYV6WoJ3jP(vqlZwy@Oc&L8iZ$3@adKho>+jIGCGpH@&54R{smrZdm6=j#vlYU zfjoHhZlmxy71Kgp4qQYu<{AwsrUOm}x{fi_14&Cj3rZ;{par6g(Lf7HMrfb{idsql zS}3A`9Yr>sKnqDlD4+v4q%^dY0GdUVIz^B6&Y-z}`F4blzTUq|z`VPf{_XB=8+49x zOo`_3dUmVV@;F zd6;%l{yive!%F98@asVq_RXzbE*e3$9QI!A`2PT&wXv<=$;5DFu5Me(fk#eGKmBL0 z$?aO#az$%uAdd+QXaNh+RCEAW0j>C!3q4WeiIuN_C|Gi~!~3Jv{ZDR3t#h|_Zxv*8 zvR&zZ8n7Q}y-3bBf<|4ka?iDS%N~6(is$eCD(J$}OIv$8;!5oegk1io`Bx>V&MxC= z8bZ!_C66Y#yZtumD?xf-bhc*LvNr*bx35Z(oqdnQn@u^Scr+;*M;PAsV}bZbP`AX( zl)C#(wv%X&+|2JG{R-CtNyi;)Uc%2!n$2!!mSWJ!i1?;kDJrhSLc8G-{V^A6c#d-xVMN1BikToP&2~aB*Bp7#~cC2dYUOYm*PzRUX+RbSzMLHC4dQ>2h(Bi#cP_VVtE#reyiJ9$}X`NO=%>nze zFUSTL)b;$Ufz|vuccx8nQ66hpm=8E1A1V8!j-VdY0iPAdKvwJPQWI2qb*Ti6jk%x> zr@(bZt^_0+$1UFg{?qbtbZ6O+z*15h>V`t|zI2T1ysIL$!XkR9uvg|05ANFa&j zmCh9rNn(A4O=)AOYC53PZEe}F31Q^13PDgw2P9yO8UWb-(FgdjX+N~PZmhj4O25{w zE+Dc+X<&t>bY{UJagaUvsWhz`^H{OeuI;3R3kbaF5y=e8&UW$J6ajVhE;{}dN_{|_ z{NJrU&qZtR3~D;cT&`@SL}+%BNMZ(a+pp+pl6ZW-gcDtkc9G5DwrB)@cjYad=jq$M z08OD=#i$#jBug&BxZJtMbN&_2>mXR`^G2(+5!8hpxCXmT7fJgqg^ZBNEK=Uvw6hlg zjI6AnD90RnlbrUhPsNsx4!B!~jnKcKTOzzultz{{YPMpx@Ug7WB9I9sRs! z*HE&RRG%(k@}}(Ifx-W8Br+J!r!$@#Ef zs;oKfn0fJ9I zFY~8sT8O{YtR}XA17&RtdzvxJ013uNW06-awFz&0VLqoM0^HmdR8U4h7y#$gg&&=1 zN*>Z`E2))gs+1hxLamkO_Ku}>7=l}aZE$aHM$p8?5^Y{&m4W2+=Z=Kn3ZrWUfhNi>QGpS7te{jiEiCw5yKuAA$I(^ z=Q+&qouPHwt2owiy46Xj1NwSBcaAdD~$dYU89l?Pf^$WYo+l9 zp%$a3#@7$GQiatSvVYQJ!NG3Z*QQP~8o7yE5afO1f%wn|p?oy)8-1|o*HRM%v6Z*U z;aD+jemQT*R=%NOviko3P9q6*8Dt0h!;x6u4>XH^u-)sCKKtt*F(QQHXl;P0J^PVe zb^hI7`#V;)c;gHNhkN61sQmIM0*8PviPIj*&&_Er>>uv2=k?8WsNZDPV>vq{QxkK> zSEu4ogZ}^ku3E)3-5XeGAiZfWZ)7U4;}MO=zZ{JFirv0~`fGN$dHGa1f)n?O;FKit z*KJrAE4O4@+Zin_8J(g6Yh#>{ z>H#T}{pBi0KgNA4kJJ$%)MOEH6o5?_{{UsVBk((i;47yOE{85AA83m-;YFo2Kn8J5$n>Yv zc%TkrG?Y@;DcT^Q(i$iLqKYU1Xr!W;00fW#B%ez5PYUSq_-jE8GXDUjPllJ*C+?v7 ze~od!5A+YW>Ob0dEB=jWK|p#moxd)>m2a-NHBCcM)m~5dmDm#nxX%(vkD0%q_RV8C zbTx!}mNjYSzrBY_w~&cvK5X(2`DYmFf6sgaTnEH`Vmb9#^ouYS&reS*D)cXbpU40{ zxvl>I5Z_Co_-0$Z+jT8fz|TVzJwWvY_wVy#wRvsD$(rHbL%H0RB=scqHIbm$u4cE8 zNd(UngClY=Q-i_eS4p92S1D^AnV`b!sa*ya7d&nQJSrdI804P0`d2VXByrQFO>K2O zpqI#*;xeI*LWdia^#|C{2VJM6HW#aDqgjn-S^hhT7j!V6RqSwoh@5?DroE$G++LX_ z)MM3kshjuK_Hmgu05OtOVgF#FqC3jFA?;a8gB5WFUtAJRfd)igu3;{rI^>7SWqXB)E6+M(Bw1FcjxJ^~WZuM`JqN$24~j7Sc)C)v_>orJG54Zq{JzpbTsWgFqH^xNbEa zD)!@bylrC;jENAs%^RErW4Pe1K3+J*QJ2DY*P0d1p$+sA-9aL*(U6jc&Oil03<&Bt zITc}ak|z=zlZ<1vFZMDEm$=8y+#YxzN&w+yiQ;mSAyyrTq)7_#o-4Us7BlA-P3BBw zvFVODs$;?^@~bS26FFroocm^gGPH|tGj+q0v>XAqIUW1gRjr*M>$cjSlF+rYBy!6d z!~{yi?*OMCFC2_|(yoaT$K|YJZ=vR-T^cb6i_04a8+&4aFnn)oryX*8?G%5Y%ma=v zp^s1prg{qIlN)Q%&X}H9jiOS6jkw~XIt7zVB^HPnat}OE13V#hYoT6TCHl(N_jZqJ zQ2@gd0mtZht2!>JrfJqXzMFFa34L#f)pEg^GC?^!9!E-(`#&GUQMHbHQm_%}+MST_ zwy~nk5RA-Hc(IZ<0zGrj0+|-63GhkMS|VhI^h|}oWhzyHz&?lh(mjVb$0nj{5QRa& zB;W#hG{CWct0m8b^s6+EAvL73f*K_wX~Sd!IL=7p(wnX7(Q203IY^=tTUrQY{oXKC zoDO?q2ai)wy@-i7%mN_l%y0!f>7i7)TqqgIrC={>o+N!k#1^`g7*~m5aug6ZfC&V5 z!N~k6=frUjh+o?3@(VF>lk%MHE3}+_D>mNIE}&VVA>(dA9qAymOP@E(B$%AW!vtZ6 zQA`5ES9I|;{PC&TekF`<9XGaApTsU|$BHek&XT5iqID9Fl@}e4y+vnXja^2^+=W{^ z4i7%P4QgMy>UQe@5@UYsv}JLHZ&6*?f8fm?ZYuu(SfRGx?z4HbL$6CZW;en!>?CK`h13B0ZxR`jP8bZXlXSgzIenb0H!p zDhWCD1d3I4!$xuRMa+ml4by0-Jci z{Ho=7VfkXNX1QUCRV3_TN2jDytc(G{k4zfcxzMemmE}nG zODG$NJ#o{D&A8Ky3R$Eo0RR@`uN~{kJ)=7AmK<5Se(wz#xF8_M~djOBBjW1iq1wbt3*O{iKV z){LzTsAN-+%vb}*OmrQ_YnZ;WisSo2(jk~H?Zwrw{_Aze;793IycelWABQyo5hi;E z7YLoo@>qU2VMq>+EH{W_u)Uf`j(z_CW|THIFi^|49g6Ne=afH6rQ-`Wn#LVSMg*`( zW1Inw`&;nHQa!S1z9gAjO|#bQes8m~Tt-J3LHoq~HklLguAR-Mrw-*JOFdE!FnYG$ zKN7$C4N`orYc!Vf9LWT)XSy~Djh~tQTCZ+KQ`mo92{fN zetl|rtWt@_09b&al1=~>>bhhRcpt)o;&{BxM(Nc=T?~@93m87#{{R}J;rkB{Y7(xm zXQtiTt*hkk`QzP;^vNe3c&!Pbw%2@12B{XSYj?q!QiS$54h^KNEe`DTNbZ}9ipE0yu?wJnoHq*@;(1bLMgfT~w&$M`OD?#8+^ z=IB~=#;>U$`%KIWp=|Cdenbbj&RG2b=M{tFYby)S3)^^#?pA{KR9&cmA2_hc7$>mj zK9vQYW4IE1XqDPoo<}6Rv1TW^CnlCy`Z{$VtsujU(gRCMxMpS38ue`K?qnZmmmk7C zPf`awbj^2Y*4DayEhn2v&>!VVA|L6Ri5*Bk!oK_tefaaeJM4|ETdmL{%+97ynRd8!C)mpAY7^B5ObOU#gh8+??tq+n%X$vvS~cLMmM(Ooca%-r`_G&YE~9A+}cF1 zX>72^9BIi_&NJ7OTIpt!5@R8PoE#kB)X>D8+!$aNKAv(fYe8w3Io=qgSkioOg zbxqB+a(bUiU}9+37k(YSf?F$i<#MeXw26?QgOkU9W0CDvH0#@)CR?~|tzmfYZQ2=L zMJH;XKo9e+i7cYGh|4Q1XgaeT0r=CS)0Mzw8CK{=Lr4w=`$M~VS*@bnhny3G`BG_m zJ=fZgof9Ic$=%=Dy#fm;r-(}vqoL@-kZL$$wzzo~7e_I+*V=Qm`WgVsxVyR3v`Za6 zdsK;R8byfpEUZD#=bzG-QPeIqYb`v_W|2*0ZY{u3%POCj^vB{&Y8b8l(e`cY=WX4y zBRKWNHh7@7mKdaTStcY#r1IGGpbA>fyK{T4TI-8!iFpu>%y`O|P(Au&REy#kgT`Z9 zNPl$Gmoc#Dt@4w{a0x$!7nZQwA(rLDX^=ABr?oO&Ibe;XZ~`dFC$OLe(mY8vo2}el zmE9ciN`*+y(!h~{{_q3nYCRvsQ)%`(wY0yyOSm?!?2;RB81@(}exOkuf=v?2fHFAB zk=#^v_ICF>%q*|5iniXwPz3f``^Dj%M@^G)dFGBt+Z^%tvVY(!`O~hvLFf1~-%Acf z%vWt8VZqyvUtF>Ls;b&WB+@|}Zjvl-Tz%a1rZti!%3GGi&ZU(-K%fgc*1Grl4vT9W zx=m>tq`OHOp!O?yA^Qa6akpUHy)r zbnRx&^H7Oljx~@ChjBSve}!|pJ*wH?`R-K}5ahAI=a1`Jw{l0Q6cNcBo>)29z~eZo zhx@F(f5?iL`s^LLf0i5REp*OEcu?ORWpNetH>UzGXC z05?BQDYk+egD;T4`ETXF%0>vO)5&|oYq%ML?<<4%eQSlDp|sW z_ z5w7ma2dAme=U3&k5kk(u?NO6~nn-Ot=$1rWqYRAkkw6wSTg$8atNY8OM7xr6CRZOS zo&x9C0aUJ~z0$R-o6R?B&n!%bartt~*P-vv;Za*$$8KbED35vLEsTLyqLMq~AxGX& z4a_+oOxLAe31Q-R_-7}KljzK=NpCcZYqf#b7cq$B+%v{~KR?d8ElLq{qFhB8Dz2Nr zQ;tU?`BycqzuDd>2i{^>{Rb7H2B8#|@j@;Txj=z@&U22KqX`(ga=%c_9Q~{udKkBj zdfIAfzGAhC%4R4>&Af~QpG;@-toStPq;s}G8vC{dbhmc?Ol#v#Kd5Z)k(y#!dHx(WDbmLE^E28*(PYVm6jKU)buLDAEyL+il&o5WXkeP?Ies{ z+?Hlzl1b!}Ye&M@?Psq+Cf1S(8_9HE<5u}k9s1_7UP5620lmIaiu4}<+i4%!H@9=F zDX8hrS!I#%p;<7b!zyy!Sk@(joC8e$IjL#*^Fk0VQf?7t#CsTqz`~m!G&xWpJ(<~;k)9#L^Bo1WE zdsIdbP%=(O2e_aPmq@ve(&_Z(a3kD&lh75$?G@Q0Zz|eyV_-P) zpB#P%AAmKltY2Q*Xy;Le3v$6SzF*9C?JT_GjyD00=CoGc+FM&o#hP22EkZFA-fIFe zAR7C0k1)AbIfYa!}CrQ zz-i#q0H;z>K!v3g+FZ~Anp$lxXaMg^NkuRUF+~&rpm9ezpc*qs1qO`sNlS_VT2Az| zVt_euMIfTNPSGf$iU28TDQE#HXrwg2KpB`Sg2eCu9Gdoj3TT7F+8Ako`&`4!m)Q1S z!};d8--q5G7uV-hxLn&?ACM9Er2hcxb^NQdyVtGdw79*EgId7FRfk7lamT371M#eC zOQEb6Q7`V=DCd>i5kVVGaV9?Q0V)T+dHe^hco&$>Htdq@c_j5U>3h$^dWFB$YAH-w+0bXIX{Ie)iwMYfM3F-Wg)viX>MfHt{6uI*~yP5 z2WbBB&tBEg`4MQ^gnE61E30^hL-WYrG;lv~0sG85lfeAN0CG3h6WhAX_EXzIIV}j0 zPb=(58OBF6SYA)2-KEXDx;phL~8c1zM5!m?=JO^5EURnXu!vB{{USa z@BlrA0O`eNzl81V+itC|>Gq9}nkaW%NQcmc7$2PpfoUD)HcxMsNkcuFPS53>efxa8 zpllpu<0tf}47T#7$iB^#V{v8=kP8pviIkT=?gN^{m98vgp3=tgWVZ7|EZ$ZNZ9gjv z@~82wZALkw@+O1Cw^O|8x05VvK#p^r-53DF>5)Jh5z5iEtd>h7;4|8U+{Kjt0IY=U zgk||T=L!uxzSv!%FCT5@v~@1>^wo%EWdc zWCO^nwszXCub^M*aq4p|&8^~2@L)zaFvpl1fDh%ss@6@ZS;-)^pUaAP+BwEDT~BUl z@IiZT9I!`n>1{HBEKAYIAcB6FrC=qWNuKAygHjilO?Pd0(MucL2241~WXD2sGtWHL zOaA}|Y3<=l4O$6AcLm-nge=S*vPdJ-kHVym#${*y^qy1WF=yrDJpQ#LdU=dXg2YHc zBRp_1MSzo7(e&fteG>ZB)){=JhGdLx-0FIscqb&E!l&_K+DUbz>lRW+9FJ=oNU$c& zvZ28~+>C#~YP@=RNZC+e7TiHO=cn|hHHi^Wjkkq?n_ z&lwot4&OjJ;-{YS!%g^?{igzsXqlhANK3a9oD zoB{@Y4H8+y5l=L#?_i@RsXYLu1-&0vj^9GowE5ox>J<@fTxElFQdBu>t*{$qj}v&jdjC*GcxE5=Z9&=Fg*X&!nY63Z4CF(^PM9lP;XCDG%! zf#Q>JM;JR!4R9Wr&mBDqjHYSP>A|1w9+lF?rL1TW0?G#8nCFU?$4a-ih(~OSk)a@k zIl=2d9Mm?@xqm3Dlwz&5fhv6}wZkM=sxyHQ8TRj8YunpLJdi}uiNNz3F~K?STz0aB zW^{A2b8II)v;G+T>!%6)OPsjHdR8vmO>d}N8+DOnAxmH$p8o)?X6tbaNW$#K^NzhM ze@U^kg54&D1ddWRvo3OLE5%XoT&{lZe-MAbwRB=))kxHRPCOMz%ABc3p_`}bk=w=O zl#$_Q&V^-0x{F^C$i0i9ZSjT&t_33!cA;IWyzyO#(xg;zb0kx-a#V=65IYXMXje_Ttj&?#kI>ad#J$D$2XIpYIPw133EEd*N9Y>qoiL z=R}rBGjVU`E>1s)56BVrL7{7LR?3> z)Sduz`IDZ&#^pYUYOjm5^(h{u08jQ^)*$T7Tb1{3*Zit@Sql0GGQ@ z`{@4wg>rKvzmc3}721EowAB9q=knA3`ZR~(uBbX)+8_84{{RX(&~h`3qPs)z+f@Gm zpQ~TY{{V$s(!2`#UZR)!tnf9hxH6ELJg*}>dh_^F=R@RXd+2&LgK22m>fK9saJ!l) zSOF6D&%fi?`ctj^IpMuq38!llLpyxlRHzvJF@ah-w}dsFdik&AniTUeRwiSVUdnjw z{PS8K9MEmNC24u9YIhOtMIbmlDh{~!CyI;RUgcX-YwHRB0O1U6AH%a-2@3gdBgu{r z-fVz*JpOeBuZPS>Ptv@yx?P-pWUko6&zzk7N$1->)y?U*GG583c&_py_ZLiI)1V_b z9Wp;aJx|uPyhC+9iQ$#Ad#Po+cDLRXjM#5#xp}9U?NVgly+ZlO>$hQT#WBuU6GpOJsLz;4!yjSRpCydK<{09G%tj~7eZYBOdv~s$%Gsv1 zj%T-cS;l<1F}Z%YH2X_=0w*pHo5v>ur{h2z-1=nRNfz;=$&rBP0D9BT zl0R0$*!(@DGU+|aK3KSv&{RuvBq)Q zi(46mv}T~t?r5bFfQS;5qc^+QhvxFGkobKJ%rx@u#9Q@iZ z+8}tm$s-NM=Y^r5lETrOfboQV9r%f#w1HEs%IL`@J=8tmL=z zC5y~bzGO|cm)su4fI0hZ6>aU(Ez(F7ed!x>AE`8vXfQ=2vLdi)TXW@!=i4Wb!n$~D z(ijpT2@0V>W+a>pa!(}t)HZrWy@X8_y0W2mav95VPERDB^a0JE4%(ZubR*3BHg4;I zoZ}R)quMmFB=JOK$!NoXPDgQ?=-|=qE$?n`Ba3at&e1Dm{M$wc9lr{5>DIDcMJvM_ zPY^y^mHCt&xIL%?n!VGkp@e<0p-7m8{pJ8Cu;;x^Erb^Eyz^{Gqf*SoU;rz2@+%-A zOWz}F$`&CuK4y+8IMJ zVwz3NNAA;gUV&coPg|HR-+mixa{PpldV5hkf-6OHpTCdNv~-CC_GOe3Ly^zWQ6+pT z^$1yGo|~`o3rkrfwu$G2MI$IJ7;W26rhC(^Ebf^l`&>|~2?#+Olev2nk-@9h4LtUV zCDpOEnCEmw!)^RWT6LpdNpo_S7K;=pz(XR*yUiHuj19QyTqmYy!(nnS=kpdXvXx&a zZg=PSw|4qel2}}e+jouPOJxiuMohCG;lb_Rv^=}Ps4f;Cv1~huC(PfTG20lVzmD;Q zA7W^i_p9f5s!#6u&N2L5F`59+zOZ?cKO*43Rz+qZ18z~(dFh{8=Db4?2)F>}Bl`aU zO6;#-mTNg=?eHa3IM9y?V*+E*rO>7yq{lkB#^ zXL!(_Ne2s@o;j@v=Zi(ybXZKRJmeVp|=t(0?lQ z@lsyO$B~7jYW(QqCEmJ=I5^4NMmm$%^{&TG)$OCOg(a74h`UJIdvyIPmDFSMuYVK% zKi0IgYg4Fdwzhc6yN$y*`9~-828=yRLgU5IRVJc(9GY#d`dZyh60^sNBWB>KBm50P zeWpP?FC4I=#@vv@Bl4}Qn@H~MWVN}3JTflUQ_zZt+D8-#6l3H?3Zpr|73ImEy4c|L z7^0Fr(GbXb5ONK2H+K7^WyS+kon=&8UAV1-v``$17B8;F32wz5iUn_Q2<{Xw6qit- zxVse#UfkW?U5h*P<~!&9xc4VxY%;PllD*zF*PPG9Fnfg)eRo~aSkM;f&V z8vgkE>su+N>p`(3Qm^NdRNKD*bU9$s=!wz3dUnzM-T%`Dky&Nd7N3ROR}95mE&C+gHM8mXHf! zyd@j$E3@((B^94=wVPL&03k7K$y0FYy|ao%P0H!kirDuATG}T>V*id1-E$^>3i8&e zDai(H56Y%B6`g>|gmrQWiXLt7df2m6fvwY~=^R@~>yH|hUvTY+=#n?LoX41a*{DAd zT){qa-SguvOm!v+A3?v@J$uxlw5J8!D$%6+CC&|Hz2W(7(}ht;x%EGQt>UNvzJ=Bk zq{tziGQ+n<#s4(tx=NTVY98{=i0{O4KDxkfd%i;GQ0eVY?LDM^1(3a0UOhF|+oV)1 zYwG}bzIrbJ?Z0V<$-3?c?q*SNw*tV)A_$Dxlj3BfB$e~81eFDF){l1k-6VW;5!=+a zF}}Kj(|>#^&nrc(?t~tU!4c#2B)65*uLOVKtzQ4{mHt;Z|9fR#h6k3mlMJ-Q;a>YO zW&2b+>wjJ?X?$~KVojDl#|33kb1wl*w&AjZp+3^`gXKgzN0u`5n+SWmGoY<+djMv258pRD>jx<=S0L}t-$;C4Ok9yBwAZq5Gz!AhR1g?SvN4z85dy}| z4qCh-;khV2_j#@d4C?r8>L{}ywOin+`ofYl1QkI8IAeB;G&3(iFIaNCA2j1_GezpYcK!%Urf09=l5AQBGNuCL$xzEt6I z{x!h+(Krr1V%Dy!X>7z%_&v;{8%JYO1HV;Q;fc2&t+j9CYENT`f7*lZ#K{MXmJeZ5 zMN3o*gY2XuN;t1S;9IK0To@zl?k%hGPt^N|`$1w6&vAUYq&dEVU8{{CDp3n+E!j(a zgupii89gz#drTkrIBV&#rUXm+{cY53E!h?u*wDu*D2E4F^Q!yR4Kdu+mixXnPVvxI zqX9^S6O`%{h4P=wOG34hV+B8AoxrW0PNM+RaR+O%N&T_&AL&`_{HDn?nJC{hR{O2N z2$^Sco8eB$aUn<-6$Sb%W&P4tv`w(hPzkFBj29W%eMP|~lHB@?9InAD+4sMPA)Ny# zmB2@}x56;BUVC%r_`b--Y9Ii6S6v^pw9=8xwyyH&^Y@3}wvy`kw1I zAfbcoae4^|saRadSLbjOb|LmrYkSr3?g+E|Yk@-Te7a!u& zvNKI%#W;*odR++z9oU*jt-w}hq}}~NRhiDH$5|lrx};=hg}JF-md|@kN@nEcV&5Ne z5C4i2^Q(jON0Hwveoz#GgumMz*xAr9>V}xw*t75GZW@@coO5?n1`OLc{2AQqv4?qO zYHzmNJEePDK#%nGrEnTEf#2qF``ZH6`g5ahL}w6!MZT+bP081T)tkbB9XG`gwhD&| zn&x_QC=rPcIcjCA=GLC>R>)hu9iSG)LoQvYm4>gGXCR<8_Qxbbj~Yj}i9j828~^v!Y@o%f0Ziz*b|Vlg0(mG=9cR zLslex-UZapiEz4vq8|s z74Pk$>gTe#(%b{SJ7Gb;DPZEz^^uDo!<%}5^V^kT+KVWp7iFXKvlKAvJ4dyYZJIs! zzf=lp`Qx2F$&PSg3BFRnJCl_sZ$AC*S%~%g=F!KQby3`Np23SDmFb>vumrve*Kb=6s=G3?2WH zK{Ufi8I)0TR#8a_q?dBA= zALmR$^R10JCsxXj5rT3(bOHJrb` zjsEBi>N9Ut*~#f@e8m1ai%G9F@$5Ir@&?u z|4_@@I3-GD{rFwVys)U5-E--LztVq0`Ul+AdtZqyP~oPfhH>;YL-u^A75DMK;8dlP z?L@sIg4;_@5mvJL3v7mB3Ij#`aBTV?0Eu@$@_%~1HhN^Ho2ZJABFq_io5Iemt$%KK zW=j?4lQW+F7h%eUYeNxm(q;twPb~bOXa*Aq;ymi90LHfwj7Y!o;W%;v*#C}D@G2QJ z)qCyKtmhXHoSi89%o3YI{#?Fw@Za!MSrmK!0DJN8O8)<@|8^jt*E4BY^~_?Z`s!EV z|2OXyzwaCwHe__C7Rq>sY|PG0!%Y!Prm-h6GzLun^5`4&SeS#E*nF0x4e;@KdE>_A ziA!7zo2#I;ctv@me~CP=xG9Dai%psqnNe%R!9tnTeRi`gGI-OAWz&&6v_{(u!Iu4f zUKr-SzV>Z)iSKxYFEdI9i4in?Oths&mVJaDg>&gXd1nTE!x%~qhbbU_sIEt$p#1dVU(8%BruNNl3!75bzpx01ED{u#Qt-1YOa?;u!sWoO=)UZ$S{)<*) z|4_!=dxNZBr7?)XElo!PD6vCTOSVL~hwrT&bD33{2WbMYIMf`AmW3x!43b@Ja9|nv zGIN4*cBnI(`#0A5?bF%M%=wRy@3O-Y#+?0Y%pC16-ufgx?vlKaoKWJ&nF)~0WeQRf zGT7de^2Hl4kfpH9mAI+OOZO)=ocKG#V2~Kv3Lp2V3tHd%K|l)eKFtJL^ODdnxxnWV zRax`Z*scJMoTodak&;M*LYh{u1VbX}m&i<<8iqiS<7I{8^AwiBIwt5@5}8GZ8V3Ci zrq*<`!*-$6Nk9f9_>a|MYEG!dER$nRKdOXT#ve&z8N@TKOu4ut9S!?o0`L=Z8K|se zF-xLz)eI#e{Tci~AuU}L=xcBJ#MXo4!>Bh6#=+ulC`N%f!rwn1Kc$^+$ZrmUVI||7 z>t1=$6t|~Z`;U~sE8z~mzu&-Zu1?a9kKZTilZIWjm;~a;cWy{!X($RaoXkD#Po--* zZ+%DX(Gwam9PzOpZn7~*c=|mJ!A_)clCaffRdCGpLY=$rtl>xu0OQH2@$pGV*0*q6 zBt0Iq!d7>BXTkXweO!!P#@~7vt&J_ZBxI@{sszh5G&E;!@tV@^Dy5~zIdX7d|MyWj zx!O88mrv%Tmn^C9gZ~IkSF*9O3B#H^^YDPt=oiT%fV;}@>tVjOnB9%=N_B<&s66N3 z1FL3RMG2DTRL0=O&s-d&>DNdi$^cUXJ-YhVgyxL+5{sq$bZpa6QS>*dYXb2KWyPjV za>9?nQw^0$+OVmW5rtm7WM>2*z$_gNQY+)+ZCKWm#=AV|l$9Eo!e*PdHMz_eQjA@*(nVz%^>A^r9(b2Ls|xrheO%{MElEg39o0Ytv~y^G%GTt_5dk5uK~}n`tb# z^Dx5grn@r|tI5fY=BsT6tASqYN4=c2mTwDbSbsJiXD${(Lex{T0GOvU+f8>BZ({FE zC_MXYSV(crEy>%L7#bH)uPjZ*R_>@U9(5276Yc8Kd`Qh20#U>L4lLMWTxPC5gCGTU zHEEt-!*?N+4f;;<7fLbrkZ-e9wg9gMS2l~O`s&K%(l2*doKHC(U2)d(7 z9Kf@(^M@7my9q>85uuCt=Q0r2F4RIRZ}e@HHLv`s&S1z-589}WX*Zdl3(Lbogsj;x z8Nr(uOv^se<U&_dGHlDF`O2l+iEaPnJ&mpzz$8WbJ4XL7Fy8C;=*vAh#gkPDQ;42=P!zNFPs8Nbrg}x^ z1|rHoSGqx8jYJLnaqQ0h6*S>aqdR7vgo*=)achA#y}5%hL;@=elTgu?X1G)Odc4ld zSyp(W4$>Gl&>bs7yrX^kO!OWk2pYfjid~J%c5Dwk)~Y;x9`=ahrZ(@>3=&P;&kWoL zwf*jV@U!117#Ssb*(&bFPA4;idxIttZV+3drIeG_7Gx}voP$YsI>9#|n@B^fEY>&^ zso-UYdKIZYL`_k+tW*jC&YmR8<3Lm{?`w+s`Fo8^mLHeo)egQS;jwqRFVi=e5qo)_ zn+=>%5H)d!Q8Px|1HEXBNmHkpc8RY z_Z zpOK@28r3Mmfy1&{U*Bn-#_Jiw6_SXA&vR5=m1PdM))GKO*In+vad}r|_ky2d%KvU6 z*wwpnl3o08$l%8|Tu#2qK``!h51Z~R(=Wj_tR#0Dk^@pbUBuqMtNf;ueUucxVq|E| zg;TxWe_JLa*2%o>Nohp-iafi27EM|Mr2ZKvabjB&1@G?W-Ly7PS1GheXK_L3E?_L& zk8nH`56Oil1>k>RVsa6GgRd?QfSZ*C0|=Axm(;8P`31QFI8*Rk6B6(~LGQH00Q;Vt z;h8pd{spsg%hTl#fWTb4!wN~LkOlvo%sgc1ni)zlCR%h5Fcm#Q9)9Li-z|} zH~t>>1#Ivae}4`C4&P@f?6TWi&QxW3$$Ra8+rZdKnD}C~sAEko8&WXGJ8DSnD|wN{)lgq6U%(mpP6HxPow?Ao}ex_ybYzwZxc3m>T3@M zARFLk^&6;a8Ra-ZTB8*O7S#R0!A+`Kh#<^OEcOOJMfM#Wj&#W^dW|7&!Wn<8=gvX9 z6b~kbqPnnF|6Od-Ndi2^Vd~FVpr%vEca#wlUMwHx>VdIIU#|zz&Y*}*@6ykaI4RZT z&_B`D$~HD$@iinkE~0gtaCNg#{z{a@bwmMm#~|AcRG0giu2;)bOB|qVflrJY6u}dvxWKR zF|K}s#YG7+90y3rhbX8gz&jPtR;27ecf5qz=Q$yS`2#?ae*Mg%?GsYNH)N8jDV)o> zE2B&AAKnHyvu?JPaza!_&kySkm5THK&}8mw?d9eIabWa@sAJOHDT@09;RR zZLR4q&41-4U2YkUtaW(s3X?$B1SsgkQzSV5aHX6$^-0q7efe!o`lL+uAd4!;MJwp{TdKMt!?yQ#wBK6+uG-xpw9q zz!iW9w%wID&U(SQTxe#}?nv2QN;m>|d_+bt-Stq@K$d^e{E0t_osW`nFe3+kwl>DC ze0BB@P!HE3R2QD3;mgdG4F5hU-_7Bew`Nu5El=c$niO|kDdlKf_Lo=s4YDkWzvAz# zF}s$eZ(-4AlChk*8pZm55NNkjtR37)S9nK<&OIIF zTF~~JKO8SIEz%KM{=K79@l;?*1$)S6o8(ZVlYFD4*?K?ZbTN70b5y8Aj0c~Jvu_CB z*4m}AbtiT{071IYKVRDVQQaoWbh%2)8y4^%d1OkJyW0+X+aizi|}qhcQNp< zHX&~WuiOmt$AHp21o4A6QkZpw@m}ud{U7YvV7%~oE}{QhDxlDfg=l7HI?3(H%qjc> z`=+YYt8bfaL|t_fOJhcrMH~vC47u}kQKIrQ+Vg6hn+3W5ear(Ly=kh|U4Rh;KIjHd+!4SNB5tsH zC=aXbFa5o*{n_NIQ?s;y4rzx2E8G2y+RfgEwln-=RE zKWwe0r+F!H*-JK>&XXJo95HplKhVbM*I{QD?6li}tmfnBmi9LInR}P_*A+z%^3_}k zo0?7LqN4zvHae#9Ov4vobPdTw=T}l3s7hH5l}TBD1)(qQU@l z2(L6yQT4ULCNI1>ouE&A=8_s*%N{Tw$!Qh{0M6ks*?GYHE`((8u2JQN@4V% z8r%O_sDv(A?^Q?Wr#aM&4WM_o^1)q?osV;G#+N~g?RByr`l_Cw(a_eo2mOYc8^vt-QB!_Ov>-EPo!42d-I^D0pDGGzx$5eLCHtH%HpRt@ zwovPeiZic2zJb;(^kkJY);sA=$tTGqi`q0`E%Rpj-a*w@OfhCn54omlEslM4J>-)W zoHlgpVr({#)IGQ*f0`>LvlXmCX4 z+?1lVJ^9&wx+49Jp8FPcY;z-0Y=taun6JEpbnj3+(N9x6zr&`nt@gFM>+*VDffs#c z7*UN8YCvN=vUz9UhCpYfkb3YQ@7l4q8R$E1{?i41kk(SKpXqdgvtWIbj6EaL&*Ts) z91f>@%GXAu3*I*ywjTBEOJeSuy0Kd*nQQ5_O%?J-Rn!{0IID74W>*pQ-m6>PcpLq%YT9?R$Kw1LvWI zrn+=ggdq`JncF!pm~L^*#)te%UL?dv7BI)v*=B#$F}Tu& zp;*Lkstzi&7%Z1;ZaN-M8_oc3UnG zoBZ(>Wo=8)Bfox_yZCl6biJSOe04w99|%$u;QfScL}g6Zdax~aH6{VgTi}!3hL@&i z$+S-xr?pWib+5 zg{BT?E(4g9>DT~ptTJOZiiWzP_#3_q#UwO-Mz#x!-V2d8$Q;2I|bWzPe9SGsxFd{31-`(kFZQ zJZ`gFS$W2*c$X<@mgzB$BtUyjIe?aIVYno#ys5{V;h`-DdffqaUyXH1!Jii%7Zv`* zMt|xnr8m(@&^~`rELO<69HSmk9lrTkStbQ%R&_eB3=vcgtaLwJ@vjSTq(9ohwILt6g?l)vb(+s}&(13kLj9ZX{J6xH(T1d@90R-)ppN*Su+q{9j#41N zN83Cm4bZATP5CG@&dSLUGUgPMSizoV>$~Gy_=$TU-XaQ5hRjvi?O6Q1o}Rv*#IC*s zK4)-7bup4?J&(KlJVrKg85 zMjE3Cg@)>8N0ZgHg^jloG)2i)S!lf{6wbO|vj5-;Kj*dtkt^AVsy*pO4&o7txd`+L zy8Q=HDGyT%?VI8pSBRJ!Tk2aisS9GHQaX*HLn~X^z!IFY`Jk0l{G06r(LBgJlS3XL zcn!b5i3?3bP%r$gmmfDX#q}Mho6B|LBjEETO)9cZbmPf$zLk{*`~i~CRBbCjAgLz? z51gdmHG&MYYl3Gi>qV!=&`ISWY~^Mfq|673{ZyDhbrPS6$eia6h})`Ostms zsijeJDD6{b5H&&FBO@e{iiL42MnAFzC%q`JIpw2MM z1OpJnar52B-DtzAd5)0nH!wTg(0uO3L=Nc`tr;Q&J}Yz3ZR>OjW8iVW-l-q|Re}Ak ztAl#L8X|}?o(C1E-Ym~Nrhe#~{X2D2vBfVJLI}xo)La(*30SVGsc2za43oTc_D|yc*GR!GTfOLD?|a%jA2*I#7lOl)ns)GnOV&J zjt)YxzJXZ!o?MU+Syhrtkhi7i&B6QSWzxnoBgWSInNqng_JA9}O|MsrE!X&N*OJ?a z#E$e8IjVXx#q4Tu1M8VrN>D(KHuKnse9?*(pE#?$*Ofz?Ks*J%XVw-?|A%U_dvFgf>p+@^WdUJvbUt4t7C9VtOgmH3cC%m_S;dfdM*SGIX4 zy&#Q-10Pj)c3ulxL_YSO3X2f59m$5!h1myKit*d+Kk679GssJj#pTZGaK~Jb3FV9C zsEAmc1ugO#J;7*G&Gfn-lc}7&5pF7VN+uGcl)viR0)tnEs%d^pTL6bCW(STY zf>a6C4Viz9J-;EBKVXTO#S{35*E4kSd#ENoNFU4rMJjFR zp^Oq<(8BBC@#BVe^i;^N_i_2B4)FG}L>b2Cd%AjIZg!Mf|HngwHEUW!YaK^7Gjtb9 z(e(f3ud;0*=yKFvjdJZXdjrC=ZAhHIabJlizZx2wkyPSfsOp_6$~Euws12oDQ+-;3 zIp=Ep96zc4O=mWivC?|ECp&zH{8Fas_6KHuBnU-mUw>h7&}vTT5ykkSSx?FiF;fhI z6C#D-I3a(ePZO#8!ZaQ)v0Gn4B{A$kOKRR6!blI>uaA{wUAJ9pzToa@(MgPP)c-24 zoqfCSIpBJ=Uw|ObEX}Mizv&jLC(da`$1A=VYxd)Yy_gokfG4!W`f;Z;z>C}OmerfW zKhsvT!+8+wQ+n@y4j%FsPl05K^}V*u}Or@9#tzw4^1(M-LN4y8`4JW5qlURQO0&H?`)+VoGqI=XF&n$G-1|8&fgvW$AU8b&JeRHffph`o4^yBiH0 zwKBRv{B>{@{hisqKI}X2ysWFVsou{Oh1ZktQWAjfZ6*C{evPO3xFIZn)dxu^`mboF zD&)~TKXrI;^8^XCQ#dY2Z@*!iFkYl z$3{UQ@_4a|SFehF$BRBC=A}FFdcU2__l>f{SNqA>5hRWXhW;TlT2pyiggzDDQuJpc zrE{04C++(B7P?k#^&Y>euPYNt>-&EVLe<{lmvRcw!#lCDqN@W@Dw$W)&G@!;K5d7e zfpJ@1sEj#jF%-X3G0VKvfw!e>3k$llW03VJ5lna(r%zlmI+Y;MJ*VoA12s?qK zRGWN?K}i2yoQhWcnnkcPtCY4CD`WQDhdeYEQ9NgbsH^=|})Nevp~g zc9462xzmnzu{kg3fsNe1oB&r^ucCqkou&d97Y^mY7D>mf({INA!ds8!1$L(N59S<= z#=YY{Em?LzRphBK5Kiy4+mkQ1$xGW}(%xnugszV)jTxlSS<+^48IFZ`Ni8t0k`ug%hWdzZRaizK&E*)f9+4;3@Ew!PWU?^`Q z5^^Hn@A0ofA5tH0rexOr+GFmA~;hJb+26b zP5i83TztUr45g8E!@7fZ{S$`!S)mC##)!1<68G7Gxo zMh%w;-x>EboYgRecSM$HQ7GfXQFmjUf8`#{TT}Bv2_$}#_z*k<7D(su|0Vv@ zFsY#=Z^RkuzO>^}4WkJ$+{%Yk00mNe6_}D)p>rn$0FGSLKt}pDgifnVLv%svO=KPf zb|I(|eL{OVL2`7k=u;#9fZ~P8xG%AG@P}piCzF}Y8Hk3^_e&|slM60H_p7>e%OkPk za&oRQ7R5O5nj+#mOSa{edG(h9OBXjcbNrz@!u$6!2oD|@5!=^KiuX6bOvqwzn__wHV|q z9}~&mWP8se!L9rlmd@f))?~&xy9k;9dNhtPdAqBuLj#mz#NN004xi^qM~w8shQ5_s z3M@~HUN`U&&TDkCPO=QzKW%*#km=(R6NJpBHxOw<3s%m{vGnpJ`G!#8q;HAzsUt!T z8*L4c!H>&)Vh6UN%%+VPD}-d&#L9B3rc8~@s#c#wrI>*_59{p+Dawxdj+u_#0pc5@ z0C4Jl!4za8cCbE>It=f#Rik=BLjSh%yLA4L6O6|-(?o4Wi#O-|1kd;TsmHu2TY6iy zadPGvx+M$l7g0ezl;>s5ki`1vz6r3rY#d!0&psfx1z` z@E}&GWvWo|C#Qa0&I)3&jMujCeBt4o|KgHlw@t)UDHI8YB-R9&^DQW6@A5qFpuplB zwK?RUI0D(}sP*$$Et1kl<&~fy{dv+=qrBPp|$t2*KJ3Q=*%R5Y@H<1=sM zXwOl zh5z`X+xPiO>p>|~woxcdmhW$0oK$psNAr(*N<3f9wKv6uz^aupaw16qg3+S)zCpGc z{Ib+|3{SKk&(cD@eCs3gsOy!ek2NE{?HT zswy$1*Th8|B9KK|rK;sSi`p61Kc0?@+Jgvikw^q?>zF3L5qrC~)YD^RJymg2P3|ZF zyn9+Na5%0Zcj&yZAuO_shXe8Ib}FBJyR*-n&dVC_G8r$Oo>IItMC2UB{x;{33RcYDj(=z4JrxPeoMAih+>XNicyZbi zYtwZ>rfx_FYp@+5vf=*+sJVY_ANeqI&gvoPRi}%y=t!>7u3L4*gi}mFpszp@hF-J0ZN;mCh8Dj)_Pq z4HwFoa^p1q7cI@?@*kaP;=eu)IOl*duO1&^WKx=7#63LIW-qx&we(0$Ph8ZR6nPu& z^?uOeoabFW7!qdNw5~4^e{wsxJSF%c?(-rRd4N)(=>9>6$#YpPgf94VHI?212AMy8 z#=B<$N)4O!?iZv}ezB!HGz<>Dg)jdA_?hhzuiiRrg@<>7b0q}%0$zpwDQW3gC;pm7 zkz2kBVi=y@m^6yY^9k6spxjG&VIr{@f59=;MBPc7GgBKPvGYXFZl8=L`Y@&FL!R~* zmq+cr9~jLcBh4ApICp7K_B8{fzrU}?(Zo1s<~|F4T`EWprB3`Jo0g%nL$P5V<6Fad z?=!bo&L6$5kcziyq!u~)fZkX_>VZom4z@tS>p!b!i9v+$d3o5_ih z=aXo3@XbFlxLmj;XrUQ@Gonu4*A!25GBiZO9`{`?&?q1}cvdd0r8;}bAnxpSXYYAe=16UUSSFLl9Goal;16#y4v_8IyMmt zyYe8EIFM=2b$^fHF*dw!0n@oSY73)3)^aU+B} zoDetx`6BV3&Z357(gbVbiuBt039p&Pg_rUO2FLtZ%1hR$X_%?FeqhJ7Ka=87cVopj z%PM5n_ffQ!U|8IU_{2LByPIuz;$7XZ`B(Fe#?x=~;yx$%D5EuVBP2r6rGI>=q&*4t z31N#$#{w{v5J2QywMn`$qM|4VrYStZnLs1Co*K)qgrsTYj)LhL2CMpu`XZw<7oBJr zbx;m1;}T&sK(NZpd-WJg`03YY%~o22&uV|xw+wDH7bfO=Y>tawpgX|`X{Xd;t^$3d z>uY~w73%RzgymUPsz?KdhMZAFP>WgXNtHjZpvxy2*N&L{tdfocD7=#314b40j;2P2 zEx+E?o~cpm5dayWicW#rNBK+e4%u)OPY{RfYvKl0jO zCcme~4vJr+pz!AbsB%==Pri9#8u)Rg_U|_6wEjq4du8@ZH(rhe6=%CIZeWQvl~KV)GBGvaKGr&z@=NYq z@AKT{pD|KIvCXlwisKkYgsTOw$B>HkrL(+Cg8l@uUopxn=JWT}%kXZI>C+p161&QV zUuJ!$F>2=$M*^qnbvpfedc9ld2w2^a-EX~DcMZP4-VX&8v%4t~V=v_etVLtG-Ejzm z@TE_jsQMB-@wLQy$viXO4Cc-e2ANF>LR6)NdI{g~T4lw(FefFNxULEcNqM=rYl{78 z@}1(77tZR(2Sl6OG(>w+h1(lS^5g(4kg^#nSt5x(%7($o&J1Gb)P_#eTd`V6{{W-u zgCAKfxS2Quu+`cS?%=+VOi>ZOQS<26aU553ljXNEsJ!bz_Y5x{!s$apu76+btXBnM zM#m}Hg?wgXu?^lCIW+;7A|5JA<4s8&@mA25?zXhyU{<2|f&b&R zW=q%b{PPd3f|wsg4;gfAyXDi04g@`_!oVxA_M89002;$3AkezL-YAD+WW|~Sj-PKH zLskLT+8SyhRChC)Hkkrk3NR+;@|lGekCYD;B%eXy>AejR4K`Wz`l%DT)>aE$8bH$* zRyb7wKwlIi4dso;(h8v3#^+|P)D1v!c2bV9DvUM@pPdZVg11&3VFEON&uD%Ll?OL8 zeW#5k(GQC<+qfY)!UliYPs!4SMWC5sEn5X{-Go;%guu8L>Kp*Tqct^ueO)B3Bu)KCdMxz4cE?89-ag4@e^ zee%f`)xODBMKB3N?DS2AP+Hgtgudk$ef2Y#Nvi6hVEN-JbP8LhJh@=%{%r9CFu&{S*m|Rmm&ZK_7)4t^zHn+ZQ z3F#a7){)i(_r_r{8zf1@htlMn8tm(7dv^CoVO#_oxSgfW-3AdQDTb=arZBL2ZS&6R zwml~mJ;|WvG-7q*G?}wxqCT^bs)wFdt~4ava#I2uTdcl8z zd&J$`M)F9=Mq9#vUWw--dI0H_H)s3bp7ngYSHan z@D}5;nP9pxxQXQ%dm+ma-i1ye^S68Ys2N$z0!sbS&?KCcLYF2uOX~0#q@9YPcEEKA z%2-dUF?B2hbVedUn@G;&f&ILatTywI!uw^JStSb~yUxiK_@$5<-W~5Y=Ko<~j*T7C zs$OtR7+?F4y=?g1C~}7Lmh4qBJJm)mU>i?6Nf=563@ zSzg%+!jJ$(#WjBZF(i3Sd4u3@RsNoo5A5Fb;Y9!w= z_<~U3&cWLEGfvixI@I36 zvTR^;zq?4*zlN;S*jwB&G?i&`#1Ih zr{w)abU@R7fGqG36hMZs7QixWVmSk;!kirnBM1nj#BHJ>F^x?lZz?(x^qR4wt$)%Q zt$g;ool}OgqY9IeSrR{Lx;8p&*1Rh*=y!6}OUY!sWkf#Dw#+88Y!jgV^E&U9dMetv z6QbxuIYK+msxO)jhMST&&`lj%oc-!`6sOy3SqbM)b#%<->1|8+Tg>(o4wn%#{4q~1 zx?no$%UmNBG;rJ?l>qZwPliGtjJqj@+M!wXq|*9ILa zQL|ynB+`T^fai8>7j%tucgDUT^TMp&F$fh|LP__j2j;x^%ozblJzFsZDchSTec~k% z9!Rq-l;J9>CXc48L!6sqaq}YoDjt~cJmSa+Rn`2fwywXf%9~Tyrf;?VQ~1af%iQ=3 z5q{!-tZCRU3`>x;!%7j}DqGZF zm*AaVT}S_!q&)Gl3rF(TrVCW}2_8EqFFu5G#4YBm>E(u5-eZLF0R{SGfxyl(S|=@g zw!gG9Z1kZ|L-n!#Sq{5z|1-+j?K*mGSA0n4_xSMb_oC5D%x=J<*iYKUal@iuarB~v z?!rY`YlQf`SRmJc85pX{>Lr|N_rbgkR^;Iq&6IkmZtMchW(0N|2xcZ)@R~;xth4|S zzH;b3UTCqhot;9RyuR5l?pexke!rZ!RuSBuxwJyCzh1UoPSX!>9p{=I?uE&y5l1=0 zIn(p&Gt+-7sAgC#Y8x>oMncF~2xuua4c zJH7SJaMEyt=D2EhS(J+4E3d2~thsg?iaxy8)~KPVGWneiD!1Xt0fckXSfT|d9oDrt zv0-dYKSoyk_FSS|j}4@+2W~Ik?4)dNzb>)46S+5V8mz7HK93_UpDJpU;&CAiBSr1} z1EgQX;Q73x;ybb5b7cS60r@2+_{eTM(Pg|ia#=m+c1ZvDTD+Dr$D$NJ+wp>FFp*)F z`n4_SAAno$4z_o!qNQiVz4vw{z%pk$4i0Xt04-V93PaD(?=Jd{#Tg_20nGg8)u6`4 zDv!(8g8FQtb8~w~N2n2_u3CkVo--;FM-`M!4ducmgY_k2MG}6(me%AInbmHT07uW8 zQW&4cvf-Km@5wY>Hw){h=-(SAA&;|ZkxcCD6>wwS1zQUzr;NCsGiT^cKj>=wi|N5iqyj~l;h zrdBA=+4P$;A?6wZGbziqa4FIj_+2g30_~k}Lc;vY?7Qoh&olJxas>7TQ8Jep&mFF} zW!i-FJu3-bE{^oShLHcZ43D2z<;Ha7HcpQ${nS~vYf}G!&v(>4^zDx3|L}BHVQsWs z+YYWpTC{k9Lb2iwMT(@jySuv=mjcC|;O_43?gR}|iWYa5=b!i6`1i9h$0T#i%DS)f zycWD?QG`5l*9OL~^YU?7!OE1$ zmb!_MkPsNOrdoZ^*6)RmvCidjHuTmjp)J{}X&YA&fw4*MGv1)TTttos_z+>4+$}?1 zm4|HXH$kFh@zQ}HNk()DO6tIIK4Rez;L^+-rUNL7cvjtPDopx?X%+ch)-JaE@c+5D zC~g`^Qk-q-gn#}I|h*54ZG_r0g(Y-^TbW^Q$Bu?|-0?9yV3#{AHF5 z*~{km3Qir$*4VKO2g6D6;J4#A|1Gt}Bis@4G7{;wVC8VwOw4p{^0)AHj+^Qq5C4Js zWwzK{d%fmzlVcHxA5CA~x&hvMEp>+7^ zp`W#IM>|3OSUHM|7Ju)8>}$R?mB5bN1c& zdXF@LG{QNdLCvq9e0F(<400Q@1WQLfJ}Bor3yHBKT$x$%g>L4|wey@a-`^V=l)AtrmDrr zFr}DGMI;Um-Ig4B18#TrHZ^p%Sw~*7nH_BcCwoIS)p*1Nd!^8=ueGGu^UbzYyNbxe zk+W0Oh4PhiI5jaN^X)ob+d)^b#blUF&>D9cB@!`B_P~qHw;#>Y1^u4_Mx0=5iN|^b znHReDSF|zWBzV42SW9H0H=JN^_qv>@N+--%12mJWBO>vl2h_uc`AWw%6{h1|PGqW#E zi-BzrYQcNsKNHSFiDWu~!KVt@Bqd$Vmesh-sZJ0Ma&39mT+$1UnJoq#tL`~FyiL`3 zuSk-KWXG}i*_c69f)>I=1APgh*m%1S^eq`vm=>dtF?08ho(EMR;kPB33F4~!cF5wc zUcRSOmvB0w>g=#_D76*2SUFzD4s+nbPM3O@o?Lb1TmM~|!~O?Xb9IZ=7Bnis4>G(N~v3OQBUouI-4W+Hzg8?Rr&dE z%mjlNFofhcpU$pe_-R~)L43s9X3B#W=+Xmz*$06S^G9F3$a4g&E+v>( z#Eii@)`@5SGk@jmw8ywY=4JmJ&Y)!(!~FK0GItQ-thn^VpE(o~PPFy(lBn;w>mC!h zrAfc;uf9)8*Jf zC>JyLAJrC3mY*}srdn*IQRxiM?4rcv3(>EIZgJw;(Hx_@MxB3nzNM`DaYCx9_BL{o z&HQZ5HVY>|VL4(`B8+gtxh3m!tHT8nQQmNA|1U7P%3MVyZ5U-_5@m>9m!Ls;t@Wgy z*{+_Q612a6U}dtuKGwBHldZ5Lf*sdS>xLu<4cg#%SpGmzfVQZ^gn94l|-@4aCbg?}PVKTo(&f z35=flW67O|vT3eDwXM4pHGny&k$)%?QeYLNayJ+|WqC(V$P2__w~M=bY$&Mhil#=g z*oU4&HX6PSZbk|~wuF?Pl04>D+O42NNPUbEv~sw4Y^H;~&-6^QfjE^)n2u=%p{!eTtG^nXEH;oC`T4RZGuN4Rko zT;IB7pb-u-)amh2ZBluPlVQ})$BSE9_}5bBnLzQi3X=>snD5nJNw1Ze&Lx<2DfP>` zr@Mp+Cmjlr8%5q*a($}$l>3qlr}-X^^lTVOP-4_hHHWT$nEmpz)2C}VE8J9)E@b~A zcVkq7ol|(u5BMtv6x6n{#%@ISydu;_vB^`1VK9tA#TovE-|a4 zTsHW;sY?6SgZyoFWPe1Af9M4jr-s0AF_K%jhp0aN(S!;FIUU-#6<1x#_$M~ zTM>kweOya(WMlO<^K?-crdwhaXe~UcLRSc|q0S%71Jh3E|RXKIEU-!7^KyEoFa;F`d3C42?wxJZk_Xuty zxulF8PE}F8qzmj`?2D76LqXV^8KZn5b$F4`oco+Jw29DOn`wT8h+dfebM(pLPw2~0 zh%@UbZG^5XB}LH>hOCO0-|>Nzn<#nHM1KC0YJK`4WQ#NWGAVM{c=?bo{iT6cqQ!Sb zKq*gIVUx>mbfv3R+vwbl6Zs(#YE&a_R_8_YZ z&;7+)^$qyJYAkV!_|Kkdj0bAuk*!_sT);Q8s6I&bMc9_umzBYr8udjB#FnB^C@WYG zUHJWaZK=ZM13o{J&L@O=(i8CtS9$Nj+3;h;V5^FX(~dw-|H3xGaw6;-Kr>AHllLUM zEO`eme0Auw`PpFd6ZG+PxsVOZ(I3nI)eWhs z@ncF8ejzT!i5(v3LoUQVGAHNu#D)<<=&FNOSt*)yw&0*;mf2(MY@(1$>`wfTZ8mbO ztNm?x;X47xmBHHMI5-8^eQ=m z@%^PWv%MX?iPpNfT!UUXSi{1`2y;Db^)(kvsiixL_dRPZTVYm1EH8z6uk>pS953Rl zC5V8wiTC{7;_yOLZp*vy2)c9J^}B;WK%w%}J3EItGhynzOu!Vvi7i5=#q18s%7VAW z+H?-uLJCqRWjX=;4=hgv;gu4GBPner)0U5x!EmfU2R?fzLP7rgpw4o5B;sD8V@O%a zp*lpfl_0*}H{U#4Z+cQ|4X~H}<1J8a?rw)}k_kU(>2h;V8^5tdO0USp>CARo z3SbbkqD4=b$^LkITlOCp}dW!(<*|)Z-kg-{F4?03E39W1AQ)JI1jS3#o4wi3# zOtA<)A69Q#!4yqFs0%j|2)Q8avaxfpQ;Bbha%0!C-nzdzb~tq+uC%5JOY39ZTJ}4T z9tbPz3$B_dItVeb_k1(Ar{T9!ZT7VD_LsPV6XOz;;Gi#e&2w5XaU1yLFrp>ig*skE zR%8XbKoM-LsFU(>Ex!wt_}kLzugq1lV%yvFQPb4n(tRFn{|bZ@nk1}>wN}+2B#W}v zx9G{h!pZNFZ-Ffg*+%9BS7*VOPd7&MC1x7Rl?Y#mD5HYD#1F?y#t)ar=c1PvfZ%4~ z4n^>pZ+#f6l+WeE#Fo{KWG8C>dSKS@_Kg-OE$l$MC%QNHO1loEP`4fE5O$k}o*9tF2>%VWY^Jj*kU28u*5-xdRhZGIxVJiAttVszpj@CaW*rAd8ncwfU^!Oz`+o?}q z-JMNux_OSWMdidkIt2INUT1RZzMP{ZW ziq*^iK-RB0r=5>E7AO-(PEprTd}}R4#m-Qzpr94e1gC!jkg}p93K+yzBOkWC0#4l1 z{k*LEo{#u$W=8~nsym-6-NI*ODo_H={?h=Xhd{&38c)vHUBRxCd4qwVpm&Uw8n4Q0uN*MkbR7rT{YC#eRk5y-pLCtO@-< zjXsBbOsiEGZPV}K>6jV$NM?DTOU`}pqH2M(tWC?D55@Jdx`XS4oJ1AmNN69X#A(1r zqU$P1?*B0luQZ<72kD_dzk6h8yZv7F!4-NuLEDWki&itl<@_uN3}4 zcA33q0fa8nOe4Ba10ZOym6Wt$Yb!dmP31I-!>r*2Al1s1LoJwmj&Kg<<+}9;eTU>M zZACZ{1$4F*MWn`-pf5$)yaiyhk+h>+!Vv_z?k~HHhH+@5!G~J&hZ0TUw_lq#ibp5? zEwGq&5vb+0JRe%_P4YBQ6a9ZK8JDW-$qO;Ht@LzCuO>=ywnpL=PyAygE`WaPi zJcK4xd4wi_-@mt_Wf?5T7f*6lLu{--#yC@wI@TqoAy5cIy%qX~Nl-n>*kD1xE;#mc zx}onr^tM<9@m~$byZO(vUMPU&#$5vvU7Tfo&(lDI^93&J0f7#IYiO+}nZ|{xkH}EM zJ)x426)%A^g_tne5!L9Xd_-(s`OG9mT_re3z2RkoDo}5g=y-%nN^a5C?YBqvxC7UF zaT2nkAGJrQl(-tWwIGB@-Kd?YWwgWen$q0Go`&eo=SgA5REx9GX||5%4c;5BjOul+ zs+`Q`#C5V>yigBr?4Rm;gSCCcUWJ-aN_&^U1V?1QCgnYzF8~)xq7uAEhd(7~eU%mq zFWLYo3dH<=pVcnB3y7Ed7n#4@V|dJXkOZ&DHW`|z+n?uyT$|oPfPXcc&vbz)(R_}(8KN< z5U*>!xRHF?d|DWvI1mrO+d60f3V^bl$O+pr6uPKZ->y=%I!8OOhKn1k;-#CbVO}VGvt~p*(J@SF; z`+!2fQia(?0}Q>EuooTQB6$E=jqbFFYHtSWwz`wfUdn}(FHLjAFR8W#(xQttzlGfJ zjqCu^B(&3p1op=&n^FQP_)A($Xk4iOq}{iRk9l}M4T`fE2Q_{Zy-rXx54;_d^1fX8 zqgRoHiAcB$vj?)c3J4j~zHdrAP3-=cg8(SwKCT8H0 z7u8xx07trj#Y;Kz2b%~s-jNxvBK-V*+(&vi&jQY*MpO>T|FsQSPEq9t0QJoQeC_mw z)h3OHKQYYge72>hCg?R4N5e-*R&Zk{_+A(dhV=0+kxMG3Jj?LM*#?bhK;?Htz%+fk zdtZ%FdQjxnjrv<ufPkUtlx%%mdVzZ-5PA4^s*G>BehiT)y$0q_ zmFmadtYs>2pYidrjogsdk=4aGGsMJOl@(VCDwV&cQzsB6>#Nfl{&i_tM)XCtF&Mmu z+tpExdRH=;nz=WMa6@qrx%1OX=&jAnI()oA=Ziwp={3$NukfRi$h3#XvVrR5yQ!DZ zEVA(5f<`DHlS9?*mK^m3<;@LoJ`_+KKW28%kL&|Ec%tz*S~a+?qophpq^3CjOgU1I z5Y!sH#65BqfMW+tJVfwp}l6gA!$yj^YOFnnf5ZkY_HU8102`clcxo z*p66gapO$G#qHFTzDVfwK=$;^+N9o~dR6Z>+TQJVAi_dokQYw)%7ZAQ;>ytxX79g$>b&Al75mE3t8#1cXpSH@?*w z4G*pY5gYN{r~a$@vQM0(Ewxjw+S=oHj$@q2#9E@369|n@rs}?#cN3n>h^6*F9IpBf z9AsY^wYQ&^WgBcN4(CzvqB@46o4ddR=Rp5!>FY@!aqP20plLkAfoZh5BQw5N#aEt zLkE#ip7lpDFWpgu1xmzwO5FT$PCuSo7NdSFK_ARMJDE30Xu%3LY;{KZF-k$ zR#1ZPFOlQ+_#`dPm{dTOJN%A$Zk7X^{|V*j}z zOsB%gPJrGb1l(hEv(CSr*R^PC%VNiTR{fr@hUThj_R7@30h;4i_X|UF)oif^m4K$3lUWHxT$>ghnn1c3 zs>#{Q>v?XO?boU%Mxq+q-D|sjz0ob)R$pu`QvRys=`y$CAzqsfHFXFp_9#j60nj?| zK@ZHNo(M)1{y82pLa^1bf<;JI>}{TI#yq*i3ihyPJ|ji|qx$|uJ8gAzI##mQZpuz- z-oJ8S(v@w#{8@Mw-;RZ{RF#5`CWHi1X=&|BRql-Rp?X)SBN*{AJNz>?V~?~NoAkE$ zh==Dw# z|49yK#vkfaa!oORj}ChmXcb7aBgN8oF9Aj&>?URs-n?-dgY08^U+Vhk@EMw$@P;3B z8b@p*xn91}3mC47tzknzYRuv5E}K}929?Zva4!hUdUH#IZwk0p$m=aeWA-Nf3DjbB z7ds^}HiNnu8*l1|o#dCwq3BKy$*b+%vCs4ITUW?@-wxI}WS1&$(~1*@#SSs2FcL!j zoR*1?m#b)=rV9B7KdN-RmTz;%<4H@II>i zuBpzNBFm%k8+hc_lFoS@Tl3bC%#ZRJT(?Vq5gFSesZ5s1P?idt+GDOZ8N)rioO9in ziol4bj$U|hsXk7nLj*OngNjY%5*bRkpCuoK4L2VTBmbsqK(4ko(KsKs)YIkfl~GWH zdT**>J6g@%jSJhMW*atiiBz8BLF=w`rT>A1lPA{46LeP@T+)HwC`qn=MrWmR>sOa@ zf^xh~WzKhJGIF2jB4ILNEV-42yYEV};VOiQx*=y;Fd492WZZ_g}h(BNg7IxKAWxKksm znp#taW;+zS+S%~+Ng-25*uXdK?Q4~&QMr^?ss2j11(@m1-b0uAjQCN(J5gy-MV6pw zD_hBlH-sqBz2BR|`)iliLAhQ#4~1#QNf3uq?W4ZM#zqWBj1wegbR&az>S~asIhOT1 zSZ;Im0H3KIpii2m6~Vv>uQ#0PO_j2cj%?%|JzXHpG<6ntYaey|gCZMn;zwcI`K;LT z45YU<^-mv0rg{Y34kLdlzCk%)B*;xy9{+&~E63NGFYi&$m#aPacZUTrcig4c(9*f%PFm@0l4 zH}2g@%nXb?yk)#BUXgLT)A?QVm7=X#?h4qEW4+oi8C+@=8@wRaG>x6T&Dzls*nM12 zTlqeJU}@`==@PY_uyzVRkL$7bS}=Yz(gGc|g)KhDTWgO$#F0j*8irjCwb};>XM`GHW9VxY z6pf5!v|+q3Ul(l+{$SAx?UmQC!==Ak-LnyCI}99Qz{m0z&A69TWX=k)*?Z0pwBLN;%yutto1zHh=8*SWJxxcNh52Xc;yNqkFCdoG z?XRS@iB-SQ_#X&|CVyIs+4&MoO@%t@oi!4ZtD*GQaC>h%5WZqiBe4Gl=5#yc{4^8Z zlvb_2QLH&PMk>i(H5-)~Khp(rBd3_Rm=7znaoGbK9ehhF-%HPT3PS>s^JO#`hJ_AS_}l!I zCP;D<%&ZQ^gQ8?_2YM%mmO*vlc#y2Y|c(m7vxlX|G5(rw72V> z#5dpLnVN_cvuH2j6}by+#;1XkdBw{QcY zksTzyDFSIrpXR>9b=M{bP*0#EI0)Bs7)dBa3Z>Kz#B7>m9xwrpL*^dfuyh`G1i!_h zWW+ODbzGla)DUgI6gCoo%;*9R+S+`KX1#*nl4x|hodUVS-0Jh`F#;H!`{zka9X=E7 zU=6Jq2e!p3`yNxDAm7dQTR{Fep-cwe)%Hzuoan=7fVm7R? zZb8kZAydb1pM#&*-qwC~{d}CxGrCH1wehqAydS66Z}%$kLKiRC6+T}Ch2u|a@ z2U3@%iQxL*TB+)q{?MXuvH4V!D}+qAOe`rQ<#pKFCZbM;XE83I)Cwp0KR+EXbERc- zXg$f-SyipP){l-FZH^M}n2xCg2S~{?JPxw~l_8^)vq;pXqg=7IzL7f?@dv&o4rdJj zA#mTZGoMkhZjGy%GJm?Aec&CC(7m`8pO{nZ|Mbcr+0#V$$LM_IB0(Gkfld*hm6s=g1O4++*Bn89%FVptR5OuxvxZ#nH_9BmEty?NL(b z*Q1c!$t9$q$ohjp(SV#0S6-xh#P_tgUn z?o-a%Dd{w@=mC=FBuTq|PFpxVy<=-Sjb_cZ=UB9$NWL7f5z*< zq(6hNYso5F5bWJ^Or|H>x)Sy__g=+6Xs^QoPv|E@p{phtiTO&-SM$w%)F18L2*gCU zTeret)k6$mE4$AZeRI;(-4cdY_fV2FqM{M3&;}B?1&hQXt59&+Q2LJUxxCd{&z85V zgeOUuzcx#C)k)Rn_O@vx9r%HY|^iW2K3?*iT5VB)u_FJZa` zETnFvfk2&V7=2#or)Yd?3G~PUI4MIU@Kx{{9RyV1QZ|NMXJv9nyeSasY_DoY4Ga%A zQy&|bFRh@$shI4WaLyw7{Yc%bVgG^T>z8eF38klS+_Jbw zN5!!+%TT%;VL#Wls0GWaXT)2tU1!tBqLSVU9+&00(V!|)IVp?Qjb&g+mj((X5;ng% zz5&Q}Vo+5COrpg~$Hsce_bU$L_4_QTdpcywf=Q+8Y-xQ=5u%=>e7_(i{jTV`=xn2( z4ey@RxfeMQ2pHKsgvSTw%xBY{y{w}YDH-ZH8G?w9x*nRQb?-7i0yk=k+{{hzz;@bU$3 zPbxs~lEydTlGiLFJhnup6L_&Mh1{14xhlGapH!3`>BS3;TlIy5d!6-;8bbYVY*)^Cek!6c( z$>43xv=T^;X&XWS*0-mFs|r8%1Rac5j=|d4EKTBCR*WxKyA+Zn{&4c!UmhCd?WhMm z!h>;Bo^|yzh+cLs_`ZdzN@3>4gmox<93i_4G^-N%o@45$31BL8BM<*u>($0G%WBP} zxCfs`#X|9+VtQD*-~Hw+RRW8#lA0ErV~dLCXW@etkkjSy0+eK=-!Ze|8Ar{5MM4XK zwgvPbDB4J@Kx@?(xG9ytNqwBorHBQ{pqniy{gew?$E^y#zvNAC3J!?s@c`=^_`{o3TjdY5OXM;5M{;f5wu;)!pUgleq%r~xdaZa=oK`y2X?f!E+#=T-=!GW0Ubn?ah zr>?WAD$l63%?So6P~w;)Dtb{2>MP28hfWymo#DnP2oR1CGucxmj#1`F>TWH|SXVe$ z#}8{i4OUNt6LZkWDiWJUyF`@|Vfri(On*F|)QQKOi@x~T_Vu&m;>(P;PIQCb3}yov zk1}77) zF+ssasWaB`t{pq)gyy5`7D<~qsvGMcyoV!E;_`na#Wx$su%n`oaMhfKtPMjT!Q zLAWvDMXXf+*RtXPZ{}*|6h-OCzufInJMn8mej#d|QQN7M*w&!J_K>M6;cO-rL@+41 zdUQ}CqF2NxyYR_mGpk&8Q`>5O%E;*MI4?To%`(=5k|GVT&-tS_AYQEZH;6LGeDGb4 z4n|ljE%t3+bWk5%|IV^1*oS=CStGY{9P16ra#pk_;yoZ^h{=9RO4!JFu-lH3m8gxF z_(1eeXFW5ULFf5dk7ZbAZ8e3&Q^TdhonrY=p{YIWZl0vV{SW3`WqdR0czm3rZ!}1~ zM^5eB)~}Db(mh|y{$$jLO-(I)D-YFb z>|U&CT){{`arYXm#v?=w!1hBqqF=lfFVc}4r_vN=ht15Wd)3Oo}f z1Fwa%8B=Ykqli*Dw%2L|WU|Ne>q5H*tKHI?r-S}H>Dihs(Abf+IE;H%aW@B=55x6C zl(2t03fWYe#=a}a-E(uA=hPve{z)@1bGpS9?w?? zxkqI}K*mEKrLR6QbY=o9hW&c>i)uRAl!X<{3JN=n-k2I|O)nPynbFw^C_ta+Z;Gw? zg}RG;jobt#$;T#!%c#_7qJH+ejXZ9}i+l`;GQBC?N#Iiyw6Bh0Czcm2wLi`4ZcJI) zb7og;#A8eMii6$$kL@fM^bOa;pu`-~BByItPjDF#xJ_ z%b_tXM1$QStz~lMS$s$E4(J!R6Q29J`DnMT(}qVai(_xd5AS`4e~=2hBDS}ipZ>cl zlSjqQkszSqj*+@4d(DBwz4iCi){T(fG|bHwXB?0l$dSl5wk+nQ2v`;vqORjuA9R#Qo1EJ)%OoXf(y$yZ9qk2^x z9p{g$#9d(dbtn}^{j4On%{<_~zQcQyiwI_VugokOMgnuky-R@0QB~RNeE8dET?|9SM;ApADX!MdA0` zcuoFzRD-d3y-(zf-^P1<8o9eG@qvn$mfr_A`7L>Vrb6e)d2_9w=9-!2YL_YPU`XgoXe8l-72!eylPL4~!jwggcIQEvgb={-puW;xt)yfjjDcA;t)k%k z7H{&JZguC-the!QFIW%UwJg*Sle7B%~?Y%__6o2AKeK&CkA6!9;|D)Mm;!F`0>^)J_A+1A$yKS0&r z@Tf1X_d4{dP}Y=jt~^Me19%G zs@g7KJYh(v%V}{*L=jP;&t0!@npTqw5-%62F1$--TfU&astDdoFqLzWC?Fz*hHA7V z$)NYh#z^Jelnr@gJH7w|S20!p|4eiUq4dQnp_BwE34o+dRDzie2`?!>0CNrupbxG| zh4UI;U`*22vhhGTW>igSAyGfeJ-9a;8MBqg;vLn=Joz8dSD|B$zncLK>)Z{lIqe~* z0l14DEq`Bq%Z1Dz1#PzHOo`ro_~F34uX{<2^+%rVafu^U+>)i(J=@-Oia<{OueP1P z_RsIAkBewKw+C1Fo0j~l+Cou^3EbLdMNTg+@z*@9O1&=~>I6|(Wu;TwpLOYhYR&>I zcF#YtBJBS1i%r!Vw8@R$wwRuZrhEs>InG{O>E>8PeC_Qi#;imaLP&;s*AQr18iT-x z{-8-;&@N=CJrlLUah4a zV4N^AoNZOGDT`7D%cp9E-Mkk2vy-Xg=nJH^aqu$WI`t~%l4n_hq++->5L?J)5x$TX zz}XXlhNN;4YIFl-tkbDukTl}Rj&Y5L*!3cwr~NLU4q|)NjyWGgLDo9G#E#>r07m3} z)R>{U6-ph$C7~Z#0Mg(xF`l<(TNgav%a5zWLRN4&))QY<@G_xoB>ZZ91rpq)V2`?v z{pkb&Z8SB8@kJe@qiKQ+9B8ltAhSLKKBY^1e`8cJiI^gZ;ITvx<}0+tj9Ow?r`PaU z4*2NE#%@av+g(#U2wf(8ot&3hh-fOg2Mh8`$-Y&AtODhNHZd$aTR%w`jM>GPDkV6} zqm*$eC_)Q+AY)5U`>V_)@9Ra@zOVeN^zS$lcx&=XYG<#&qro9^BY&BN+Z}{5?Q>nL z{rJUrjdU|p#1AA~I7q|mCD-wt;{5WKYTg_>6?M>}`b`hF5j~}DC@+ZZ%ReFWU zH*x`a6+0ZSZ)VruT(VaGv^;M#9EuQ1eksFqB3S+Sd4GLPgP5-EzP!CU=e4W^*xz(i zC~#18H~Id5hW2C2N7S9~Na1Se7;H2<3)zhzPN&B3lgP<**pMjWjZm2;;}>N(M8jZJ z&Qn^~=Zv*rA0Ov?<;M_RSv_Oo=Td$KAS;`R&h?JTnvh$$>2w#v=4-}YAInfuOyI*9 z`6~HiF2*=~sUiqu2nWk(5+^{16OtygO#V5V#Zzyu+>u&-(0X6)ZJy29CCtdx*4Bo5 zaNnZrl>mq^vH?Hr4#+7E3ro`1lIy!wWINQ_-=>3U*6W)E``fNd)|%6OhlS7=$S|aR zIDp~}Z>Wux0vv=D{+w#I!;)OYX zSUW-*8Nxco*pZ*(q~6Kp0F++o+m=5Enb`U`0Vt%-@js?YBd=Z5qHy4zGAxJHoSyHt z*?4(`pkpI?Kh3K@RlK$T>bl)4&bh#f_9O<8QL} zb5*VnooU1qC+kyVPl+Og69H?^?2=B|PD*m0@;L;Ml*VYb)JU=j`hAVb)bc;wA<-vP z#9w7zh-}>oSuRwbHZgv&J==NTM-Mv!6Tg%q2NUNB#4O6RaWYQBM)D$^q{0H*cw;)CzxCAZRe*kkj?zlxPAJ!xG zgf_%xV$Z}L>uDMygZpYYS}vJ069?mIh9wQl;bY`I&yV$^JGn)P5l!$t?=thDd{?E@ zxJjm!3P7IW{TSYF8e8`2UzD%!;I}_G8otjtzxY3Sp~$506(MFDis-g!|=tCserX&fV-T@)6P z8_H(eJ5fK2>h1%%md1o_8BcZYRu`H=i+u;}y|1(9Mk09ikz>@@@!KRL_p4a&*wrSV zYs4AB?2S>Fp^_Khev!gG!f8pG2eTA>{oo**O-M~VQth78Ukuf;B0d%&>jr3PJ;{xR zP-EQgUy)M}!6jZA8koO>TXoCGUwDqtN~>59&PdNBVJa5v}XM=u7adOafBumvu>lmdURnK{zPP59_@J@VAxs(*%mvsx;$ae|Y zL+Cjb8q{0QJB6MJpb612aw6gP4UP5Z?s4Y`oBp-+p;JZOE*(J zEVO8>@)$>}Si~gNQ1}R|cLtg1DI`elkW1EalWBElKQA53kJi>NZeSnd8jf^`;p+)#M z*u0EL-NC8&-~7=s>b#BjNm{7XrYao*g>LYpdUcUw_WO(4=8)J%=fHv^Xzk;Q4<(gU z+a2IFjK1A(bF0*cbqY&T)rQ8sbei}HfyQ2(R@6MJNK}_i+Pj(|%mNA|z3GnA8?8cD zV7fNWNWSA0^SWP>7kiBrcn$d3hxN$h;xYakO4{VST}|_!>Sk|hvD4|YgejbalHU6Q zUvRgL#?VvFuYjh-gGQYQJ2I_@f#h{$)EQo&NS4%RIrT_8>gjcAxQ5BBWh|=N-#yon z?QnFawGa`uP(+OzQ|QHRsXX7`AVN54{`*&$U*_ndRp zcv;unct~TrZ}_vEgX=VRsCHaZBySTm*3@aEV!6=@q>LXDMerOJ#_fz+8C^bb8+MFJ z+IY6Wcc92-Ze@e!@H|@!$7*5aGWWdwr`eCdZGArRgoM8N(Q+aZv z76Ag9t$myG)r#K=<-Cdg#hmJKM;35jrStIB47wXD*Cu0=(hJt(2|Y-RIUp|O%;@kH z8)ocKw+NFxF;`}X8xfzePUd3giZ6bRJlX%sx&G+iM!I8v@_KF!f<|Z=NqDgIi7-c* zJ}v5y@tkzxw5()sPfSJd3h!%_Z$l&b$+C`7Irg_`gAx1; zdq~+*^=@m*f>j5e&iBYoqi=)L3J942$o@l5U7^E8#X?0*FH0;ZZP~cjp@{EM@~ETk zaxu7k`hw7aUctNUIW4QXf~O70 zX8KCVV945S^PvA`6ERigQ(W1F_l{chRne%Ot5QEuY?JX!?`QnxE(AgV0K4j{4-in1 z6+u2E^rpqbNyd)4X4P1_Ic)*U*(bq2wHv{WnXhJZF7$M&wk11dr^Z zWN8aia|czXG?_y%)P&93X(!AkK$ao6Hd+`U+Fid%7am*PbmEELz`?(QDkrMLul*FfJ~_w)XMe91V+ z-fOQp=P`>2IEJx<|Mr)Nh8IiJO2+o%8Ey2f%<2|2hw!I+Z8Ay^-TybFQOx1|QQJsRD8S7TCv7j8D3Rrl0h- zYx27h-l(ykP81+|9z7E0W@tD7FbZ-hq~eag!Qy7NhB#E7qjTk->3ltg&kpS{U*y}{ z=N)Myv_Ko2{{Y7e@?Zq90TF-Zd@Oq6Ir%_s0T*ZB<)v%Nomp##lH@sw_M8)F{weYr zAIR^1-nD#(SEH;EJY<&>a`D34U#n==(soUy$&BilFboMk(YsHfux*TXVv`$>Bry*~ zZ#|VYGjd-jm^qO&m{E+An=6>T-E9Qj?_8Fe?N7S?rOmWj<<42=wJXokp?Wci7-rLf z{BPorx9})Y@$UcR-!t|VE+J>faCi~Uv1_pIJ78= zJp=5!i&rtdmEW!AX)!uC()n2GZI#*@NnaU%oQ350OVts>mW`f7_20T-hv9KiWxjb2N8} z_@87gu-2dq+HV>f7@fGS3@JLVo~>z@<8VEq6T2r2az1h4z#W1?3<#6#xa9}a3mLj! zI8r>H#3#NlHnci85(|ja)W=3_)LYcHG&eW2WVzY#dVUrdW9&uV?4FJWv>KBuIxVxL$Oye(t$q{i`3LA>K+x{tV=Q~LG$g+~U#YgD7peK0Gv*9Ma%IO&c76I7SQ)&s zp>~c%v6SPY=Slq?9V*!}7k?Uk!Hf?H+rT`8c_oo|Y#(Cm6L?yjOc5o@BnkNn%8r_t}FXd}*@TG|>o%+3kUj#9OKUMp} zD{)(lIBmt1P{ip$66=Jvss^sI3!S#B(WQ!X!5L8ziFT-W^hJRNuXgEi@`);Q_CGl6 zrECc<_BZ$sj{{ZUDDvDa+lP3mU{waDP z?a1`6(ly7jty@?Ip(h6Wd%vzhuNe|^oA8>~A7WwN{*O5iqac4x|Kqo2TKxFcqvUQD z{NZJ)N$S`=A(n&O5dnx~F^*WB8yYq~aBs7&Gm zV5Bcq18(`wKREt~Y#3;3?y61Q+1Oiph^KBkFm4^)P0YL&f7Zgi-c3-hGa*&)z8bkk zI23G#^iW7zBdF;pad;S(cuT(>2M37(0F^@KqDfh{T+wp`*!qN8is#7^#7sbt%55%& z1J2@(K%w8SP^S8TGx*>dU#m{{I5Rij`#chGQ#9ijP$YPQfucXVe`&G))EE`6cf#Q@ z;EqSg$3np_Qj?aWI)}XP@r@1^mFpz_k?EplBj|K*nBNcEycGGM$Iy*utkT19FeHG?flNck0*i;hO#1$?SiIK<0&hU3 z*H%EIcL>xo#0GI5JbU>|%iCvLSzl8;AzZ1@x+)^&Z(#b~7y^vGWYlHsa zeP#CdtQx1~%(E#2t4xi`9M&eY08xY63DucD^A5Me-?Z9d_g@lO64>T$KhxZp=s zq~*L=?{vm|T^f^cZB+^Kt+`s=C49a)yW|v`QhB^grry&9{L%Jo6$Y8G_tujJ9ru+rI3-mQbWOTBhtE$SaZA?Di9&r9rBu@(5f*aXMUc4q*)v0pGlt(WkBlUV0#7N?= zXy-cl5cQgAibhrwX)fwxx*muX=;*VWtZAc>&?|D1C%B$*;%Y;cbCxjh$zsK&nbHF) z?aX(z(UtE}H*)_}fd`C4K)*XN3Wr-BzP{n#;1GBe#jVl+9l1niPM>(FVgnVc7+9E2DomDz}?|oiVi|t_B#l9_4(kEUYSQ zIy`o8luzr3qa~+-5KUcq6dmI~XD%(WTLhAIb~q}HJK#f@?g94~Pj9$zzF*`&ARLs@%#JUSekmBylSM9}g$ zo!p*vW{?b#Z)`wb`7vkxes(>KX}{0Fud-k5P1 zT>AE*J2+gp$G>eFnX2U2tJ$|Hc6wfu?Sao}aAdgaJ- z@!=r_9>VPUa_{g`4DcwHE<#Gz0v+wfY`QW4;X~&H_JjCY%@jc^Rx!P6LW@ihazVz2 zw3CZq7;^&eWT{Owt7Ir|yQ;3dnMr&?i=1Qz>8Gcw-rAZpX(dw{9iWsF9*!&)85geC zX7o=UjpITZfz1Udu&>RJ#OD?ZbNyIbEvc?x2dnHcJQ6}SXS2^lgaQL1E);D>#B)=mBGP!(+ zPLMM9Pd~&AD1QurTvixrQSd2*8~m6aX~>4~H0Od}>$gShq)pO7{EPkuHi+6|4PgHR zz~`a}Th@&gSiez)bC;7Q{pgJ| z(dibGRT0WXL z@ylJM1KIQW<|%WDojgt?Jke}hpHr;CgW$%=AQ1jxs)jTGL&3tmZNJ-Z=j1w|-xzfj z`EY8LLS;UEVa7oJC?$YuJ}nRQ$Q7ECF61&F=eaFAPodYFk-?{!?irmoU11%`TH%V| zEP9*zKy%b1axz}k=ntvvK5hUI#5fR=tpT9+ zyhs@#;83MS(i;=e!X-Yd!_juvEmBf&7-N3L(FnbWF7$H$EH1n#z1}v+o?$ykGVNZr z|FjzQj$|>2t}USk1@Rpb;zNmjDjj%*q(X}M?H}Os%`gx(+(*wa&D67M;hu>8De-AO z`AJCib~2FSCK}LfpEe|z-B^XDuh-B=pA@kk^G<=-GOI{|)9L-!>Tj`3TW#UUsHX&^ z@V=_=?$bWn%Xpv;AOJ(7H)hxhI$+0ag;fXxA+-WS&+i8&5s{budhP-A@}7gmws!ve zTtrm_9<-x|-KGyZDxNpvwWd^k2n(sV062YsX}+RabS9iQ(aNVnmoi9kZK&+v zK%Zp-a>KRXVF=e9Ch8$CF62^bZEc^cJZC$d$h@YsYPLc*6a5*TBOL2Uyuh)=UjDWYNHGyBEBaxv2BROO zi6##YsyODlY`6J|dbvZaft4Q;6w44e&CL-qaYXpVl6ZY~n!*axzr=DAS$P8B&XoXG zhYxKrXBi5mNBJrl<5VU$Khu;45_&GcjjRi2P~X9<3PGopDPeH6N6hCLbYVH~C!I(Z@@GME>E$Y1zUSBbUZ-Hy5BOnp1wVpI08r!Nm z=)y_@Dmy2(v`Vj-aH3i1ROyuWQEv+O3P;>K^)vl31AJGxXen+JjZ$;ChF_R|KGo20 zd&1QBo9Hg^9)F2NM^pGdiO;7f%M4KsiykYm0p?@z1a&{j7!9nq(~UzI4(9t#X?^in ziU5h&F0LtGXI%|>eS)L&eb@@jW=7OmS+PwHNAup{j|Y_@lVCkAK1A^-XislY3k?s;>Fn)`EJJ^msNqh zvE#15OR0_LhZHEnpLz$K;|FTQ~Q0L@LQlT)QTY@+SRq6+3{ljVm|3ht_f@6cFW`C%gq zq;&t}<%>St0pBtd6u98Ip0jgT{?gB2VPCq7Jm}BM-t}92YwMfLMWv}tp{oAHA zb|*pq0aDT$tRJV=*ND#c3!Q5A%Z<#uHvO6iX-^uLu3pPQ-Y2-abt9X)t0C90TD zS1gWn(R`*8?(-g|hm`L!r8sPL7lS|fyZ#{`+p;l7HRnxm`% z=V5ZkcQgdIe`*7vvZISQNy*7BF z3l7JGZo!WsVq2P$tdBbzX2mvb(A2tV7vBXWV#9PR|@InFvbk|C@oT zNxts({r;w1$ged-1OCd`&;U4Qgy9_AzGBcZa0lrzaw#Yx!JOd1NVw{%$Q*iI6iwaT z3nuk7**ZotW5V__3uN-(+=^W0g&!pO7--@tnl0kZ--@=|AHUT=ecv>}eCA$*hOt-4 zP23{9LPESr7yHyCfg4Rb>wM%s;F~gbp9)Ft34G>*6y4NN;mXF4*e66Y1mtU;DQk6+ z`|`k@b#?W{MT_LW6g#ed{#;M#>$AV5Y}_h0>**%*h?+5LR@wNl&%M>|kQZAgMm*L7 zZWR5jZ(mv+KeZ&$_=LZ7t=Lha3$ zc+#L!J~$O>wF=%~X-Z?WWf>$JZ_t@#7YB`nDWRCrKfv~*Dl&VCEUb$JW5D*RrWZp8 z&B>`)Vs|y91cjeoIDMnTe!sQ-=>5nPH{j4DL?}@3c>Wi2)KA#ewod-uipq!ftjK6$ zR~MT>;lw{rr-~+ULz*V0wj$=Z?B^M&Wl@8u*I54ehW#+>e!VAAnx|7zUBEH4h3qX! zDSNq!CjEU;WYJ0cFSEB&WtR_XN29wh(+IkVN@Q)Bkso9NH;y+Sublev0_Nd0OzSDh zxJD}NOeodORCO@nL=F*L`&GgfTB_11=cv!LZ{M}8+L?nmV}ldI7ZJ^|4K^cY4^F>2 zDH;XHGk@q&`|G!OSlih$e_BP;ZS7#ZW*+?Q)rK-Sc}gNX^&j8_;Qm1-;Y)2EOyGx; z0pM8xN)V0A6*Hp4)j5k3E)-{OOSm0)Nk}}CAiwB;RJNvq_BQn62W2sPr(ar8inavV1vuQ@Pw z+_GvEJicEX{^D3g9WfCvO_93&Ka7?9ZRsI`fI}n2*+ZM%)oaGR3$fn&@E_y5t&W}i z;O_lbeHG%W44#Cx)`7FCxM}rMMr&uHV;mKO1F zP?o%6n3bLHf%Ht1LCm6XgJ{t9+jg zVl$A!=qsDTk;CpU@jyn$lpu#JCdDFI9rJoMYv1Fn9%DE-Iqn@qefTIwh?Y3*F-4K0 z*UCN_<|&z^F(ZX#Qw57M1z#2YM!EaddfsjjDB2`?W96Z;1~H(7MXhpbhATWq&F1HAQ* zDY_p$d|Qqyu3Rwm>WjlylCdLp_Q3(1VT=w*%C4`^R^3ix8&%TWZeKtH+Yo0WU1bU6 zPL2A7$_pOmRl=X)`XV7(jMsbN;>g`Fd}t6+nN7YL@AwkI=htkDR3EHnABw&;*RF+x zD!F)J7BCUU<87tCDXddwTHdaB#Glc*OP${U^MHP~_J@K6-8}vvEjDNE2xEH)a?5QM zkfzbx)odr5T>GsNjY!L1RK0aaF(9PQ@%(MfpOU$Ky#Ee-8T`sD^`)NoUfb@Vqt!y} zGXj}EQ+9DtzlSfmF-*nlQLW>QMVXQmDK8^Gr_21NmW=Y<>5*RTk7E6iY70V0e|2l6 z2SUm1nZZN&S$>3a@(L~$;!lW+i1@jk!j~DE8TY-q#v4667VUA<0rSLHyV$ly`R}cV zCgxd$jeqMr(7tr(e`<|1IeBWL=WU2B^%xxgYUh2z)%~Xa@g~BYCo{6+~?62!9(T8Aka$9z2}@4B_PG z$$|my7E681@4pQtzwl1>@21d*F#Gd-qOkxGbx6_to!Rc_yc!VT=X#Xkfjf z1~H$Ultyj~x?>LyS>Qxrig~TY1>|hmalVZdeQ$l%SR&^RP7Rw=K)=*;I*QKwp(|Wx z;lP^Yf30#;hHcd^XgK)$`w?f9#d<%Jea|U}A?neohmOUApSAbl@qiJrR?@ySXy7UOjJd>t)$IZjT7 zwOw@dgr%$EKd64Yhm-0l%plkzi4xbCKGEo?hy|lG~|-e zNh7~x7XNgKjSFHtaCI#{mQmR=#4OAT?5$4?;?o*!zC1gqQotIQ6Jr{>yyxjg-#oI< zp8%~X5NBuG2k!8~w9hxVZk@hfnj1T+u%!0EPXNer$eV)(O;Wh#iv;rn9l7b7i0lFM zcDAnM(*|p!riZ%GsezeAQ4T$GDTqXlI5aA%3ES z`~Qcjp4n(cpehD{m7$<8S3+JvJQp!9S`T0q0u}XGH&GnP;QxG`bK%za#?yL*rknGv zv*EJp_oH75xm#>>*FQihROG}}o>drWYab~%$HY?v4VLQX#~ZRXvP{V{d@NS)x7CXq zv#*3Q`5MDg0aQlrSySpvL%;O&HjGvtO{X4wHG^)P=#F}JcVFTT&NP4M`iNFn=si02 z*ry-m->Atx7a;7amflzDyAXtRaPSNst$Q&2%BVa@aZ4n%x*8FaI#Ianmrj@P z*m00$_woggS)DXwtLy|ONl1(M>RUTbW}yb#*$}VhVGrS=A6!ki5Ih?w(66wN_EO)3 z2?yY{LWb$*g!NtZMHLSwVmjSmIAXP?XaOik$+6Ez*gAE7lQo4*_~{$dVPKZe1>FdEk!h>@#ru7w9qE<1h11fz`+c3 z2%ⓈgrYiiGe2RwWTT+<`_xQMGM;n!pUNK{oR_pF-%)>p$z>c+;E#V!-SXuRiJfV z2J)oQqvtP6Im=5F_ASjim=Cd^dVXK^`}uiQ4VsNY2qyq4gu^>IogW<^G-N`F?NR8OB~?KJK{t4?wG7GpGB7<@{Xl*yY1#>6R~8 z+HTVfWuV7$sb&h^KPVKZKQ>3pDM+k!cMfw@*2Q2-t~eRFcSR?SYR9}oQSyyqa!H9QQu0K@U zOs;Ke5#Hv1{sTy8c5hqQo_aUdQD_FfF$IZ8cUf3Wq7cHg$%dnbPBv!w3(L+VS3RF7 zmVwL%dh(-kraIqzu_k+mSo%e-dJ1yAUj_)nvf!K!Dn$$(QP(PADO9{#t{dWFabbC<*^{#R*5TV)C~Ce=dS zDhofdO(?A=(?xovQ z^W0s<#LS9VwCv?F`zsXog3+|P5}AV5HwOp&iMy-%^8E~>B^%ipw)9=hpu2=I=t3#H zU$73X5sFd2FhV$x-0wuG+amatK!Q^YwyjdgPd zJyr|&#_#&adyQ)(S6h((AWn>t#qDq0Rk^%turdNKU>E%#fN3v7ZHSA0oir4fWx(^| zE&eK>AL9Ji)6WY`ae!A@XxCKyWAyk(ZS#j@=ki;MDO~ik%2^5cr$NQkr>0mgt*s`z zD0qg0CvEoP$7EKSBUbLm!nUMI&hkcW*wHxIi8DE`FJ9*3$~h5R3}t}3Uz}O#qX8Ow z(9b{5xWP|3Ue&zxL}#jFCy0|X`JTwD#M5#^s}opuPLB~S%=#DT>B z0fL0E`jY)Trn@K&^t-f1p-F4Sgz^H2{+xjq=_xunXZYk4SAsBra#QQWkT(niS{8_> z$9fRKQf(?!SnpJiPYNn{7gPTfxG9tRi=3;`#(4HF?c2dqMYZ=x{Dab6jk(#1Ie?;=3hThg8#n-FBvFWCQ#(8Xi@pXj zEdncAMgVs2uw`Es0g$6Z%WMW%PG6uuV!Y)BbjVnILc#1@1_+z=MqkQ4$D z9z_+~o_ZC8{sDZZ9s|E_-+DUG%e7yLT>k?M^sCabYCfNdz*M%ko~0~$Pu~PB?t*XFBZ!)se$su}dTinadPy>_>eZl?^ z@RL;u3kX&J3u^*O4yciZ{ae$>Tm{~?`V+(tTCG;GD{ysqsBYZFx#az&JZ}9)SdP6H#%5{wj4dt?auqUa3(#xC^HM|p&=DCY?rT^EZLe(j=O z7!f<#f>e)Y2Kw8QQ>wPn!sm7a5^lBKBC9h@Cn^XeS!d=0Ul_xQC(NWNi+m*f0Q| zvxiMwC&|wP3H3&+LuQdFLaL+(Xqi?ZF0E=-m^~+Z)>)BjXl59$mq`YTrubb8Le=-( z&=Ou*RRb4A!NKj-Ea^9=_9)+1283xA`?H2s2KzG_owHo=grf5xe6t)LDWV9UGci- zJ`ErLScJgXDEDOSO3e#Zjn;Y6oo%RfV;!JgaR8<>GD5L|TG?M6J6=|+AEm7AHI_=d z=AjAG&(SwFjm+D#&$}+*iwvk88$@^EgG;8R2;LE)Xd&}gW^9$@bA*I028rOGD1~3~8t6+4nt#SAvB#di`BL*A zVb1KPnkymx)+B^${jTRpONBu#N_{D^{S^pWoI)Te*HvhBc`#WZDvJZ@e_oZ9mByt0) z(xmbr&%7`q5f!}MD`1#_fLTvD2ZTO5)8AIcH&lOh%mr_tX5e}-hfPLR*KG;8QE7ij z^d@d#DRpS9XHw!K;f=>sq}3qS7eYgGG6C?VWw&vF?*~LPES={8%EaK5ey_^ysDB(s zu>Ro|r}zfn!UMa}TU7YZrcSiXKy=4B49BhHs}=Wmb0#)?ocvrkwNiSBzsF;!PF;uFyP2hPv_Oy)Hk;+i9(zu_W^ z9>4OZnWW$1S;d6(tnRXvN%Rf@)&@dPnL8rBhRiA8dtR|Pmu*p=-QDqgN-L&IcQhxr zAk{TVjJ#B+ed%#?r1x6h3ZB?)5%~aJl|F{o6eV*4& z06G!cdx514EOy~66XxSlFu?X#Ipdb8vB|x#OZuuS-#q_A`L7lke#V8Me}E=?$Yqhy zYIQ^awf*E648pz6#Rxv%-Nn8Yd&Xdovf?_*Cc9E+JEEfAIK+Gd|Ap>UK2}Y=NcAOa z&tzRMi!F~mFvrX!-Vwr5RHeag;1BisHf`HL9F)2agd$gQF~xA`psQA>xh3@~(8}>b z?eCjT)pfsBR0j_a5Xkp^<*7`?W}1QZ@$IZzaEsDvz==A^?WI&Uzq+~$4jSelqm=}- z1E{MAlhEqAScj^jExXY?3rCH!i`PE=$ z(dPUPqt3EYdPVy?$5;)9qqA#}TEnRO3H^GrFyxw^Tny`v{Dby- z^62V=q#&k_;`asD;FS`cTuQC1g3pCJ2Hdt5YK=O;cm{;B8u9X$TZBZt0P^{*Mf;fb zy5X89VDu~-tQ$0CUeiH90U$T&r*+pBrV1EhfbYD|_ptISUe!BFG<+>GtovGQD;`?T z@g~*j022cJ#rl5zYWE|tY-!JCpfqpHny`Ru4?WR6tSg;sr9{t8i*KdyJj;m@v@^_}4Nq30 z59=xLJ`*SA$tpNpOy@L2bK*%q-afbR(Rbr&Hu4AbAgrY5&eP2{q+L+fwsa+b=G9-V zG901A>d#g&NpE(dP1KjBg@x|SksvIXeX=yLHs!S3cLvLPM%=6(PPjuTh_$d{L9+BS8_`-LlU{=)^Lw;Gi0%pH_^O{#=(9RmL%fcw0Lh| zkJj!f4&!NBPjIVB(9RCm4iYDOxdr8V&^~MMJ~$h$%DOmlDxinD3i3)}soJEN&K}R| z+r@*Vn0~uE{v>~2Mz1;JerVQ2&;+{?{-}%bXdsaS-ubE`>@Kms>uCFYgR$JqNBT+Q z(^*H3Th7>#$~;>^!(5f)pJu-(>X`t3>q=-~ekNW?AsOTA0rqw7?1M*z3;C#q3vYO21KVX=-k@vnc?UDdy9m zoHO2g&g%V@aALVuz8Wf-?bfCQ=)9!wsQmJf*WS}HoAUU6^(oIkP~GBnZyyotvy6czNXQBSnwY_t?Ah!&g>>qyfbhEe8@{+@(*I;~Roj*0 z(;phF=Tnutvf^*`$X==Ao9F2)Bd#!yRgP_KGf;+&bw<@e1BVS4GYB>EM9|jRQ9?Aj zBCyb>cCm8lyrTFTk7%j89S*Ah4^XK*o?}OTkT1W3MzM|4+@dO$R^~i2xDMz%}6Pl5R4AVqPS=q@PXI5nR?*xkG*6YmFnb)JI&kGhW%qLG4$u27h zo-{aZIY)x&1}4B)9Mr903kn8;PZ31lcOGsR?q8IqR2 zID8x@y}d`-u+b$%zi|z4-s5VA>UYgYWtNF<)iMnJZX4}aS~|2UDT$f3PDbQ*1u6?X(d~{lgJD+u-b&J3BTHW`lTH5nr~u%ourF~&V?QrruBN8 zE(~khU}%z0Ld#a*Kn{+p7E=>%{bl6qq)a&hh(Jhd%PHiSd?cdN<55_}1Pay>2T zDbS4*xJ9hsNl?b>?-L@39YjYnM}40V00|FCh#aWPMiCTkypQs@B=81cxn8KPwly2Q>V zHy_<;OAU%k?ue>fuDF~MBwRVtK{CmE3&mEy%YLe#Dld=$?s2ic<>zQ6Z)~ib2bi`D zhlLYGl9I!%iE!Hb^9}O;q9VzrLkrt@ZzSZBnA6u9SLmTnP6vNwomx4XBXRyEeQMg>n%hCdI7()R6Fk4z z2w<~CE79`vk}=pNPLBp$RjN;&-mK}@j61}O6@Hsxf0wlLi#f!F6o?o1vPJ>*Mm_mq zXjXUGLh-}0#X*v^$2aEZ2Y;BY_ayoc8B(h#$(8?J9lA^+T58Y*5s|Uj7G0RE7rZsa z2V$I6d#8~I*M9(4#WR{iWiiz6*hWO|fmq&u-sy2twjp#0hMqlu_p~}JiZiCr_0|Uz z#?1c#EZGE;h7L2XnI9VgdRL9@BbZ5*Z8814Ua6#3A^~X_Ptki08hzyJsmWnYR`Z@> z$;=(K)==$j0n_32QazvYoUIl`=72vcTXs|1o*;gDN78*FjeC!`&Oj=?>7+t4;;a2A zXZ1O)EW_gWdq)a#n2dcvsEV`G|JSFI7etCdR5V+fi#+R<7cGg($Z)2JmJU;ah##k3 z1kz$N%r`9hF=Jvk=Wfau%d)Ain2pBp-79HO5EW*24*{pHE>Bo`g+;Qog8plI((`<( z%C6Tv?M2_qKv>5rWQ_Dnw`Uan-OK3)6>Kz!-Kk-;oa982qM<<|;6fkZU37ZJ6hwu% zH@D}d(%6l4E!x`>;_{4+L=om&c(>3LoKMgrM=4&Ldy5cku+$%j8ABuOAi2lk<9E~K zTXs)TWyidO*+!S;{;1DLxCXrw38UoNx)SN?c2DPRE%vVxSW7ixL7|$mfA)LvD*kRm zPBLA|&b=C=pxP9BN#l?{--;eV8Lrk4s~iAhn@6<4p3!nkj^b2Nv82zK#m^do?ah(G zlF7AIhy4zYFlu4eQ0Z24qM}XV0$a>aJL0^)U|Q7GE@SYYsjpM*89hq`oNN9$2H$8> zt|1@F*p!`-O$@^x`pR`He~(U}FNeH7jtI$qDyqHeN-8Wbj0jVwgrF-ycx87Q6Ul$WpK-tk z>Uq!MDGS%PA1O*NcUU+vjt3CT4*5PE!#*oinXAGX1k2DofM8%=VjR@BR3u(iP7&Z2 z`g|qc^er|h^O{4>GSvHIK;8Ju{oZ-QY{Vi&*ETL4%ov- z`KAvY)bl_DizxoqLDbjm+4Td)GQvo0YD1WQz5(tt?z!mQB2j=hcW_5AfFuRc`2N*T zl{v2`3O754;XoL+cU>&i;uZ~^-gSFkpg3c=L~SOEG?l=kxbJWzv2%pk62y{(INWFy z#*8}QAcRNHb3|~6VPlwbcX*PE=R2?tEM3^cj^A*P8d$r6$rU7WoNmkR=7Cf|2(l@} z9)d$=Q3gP-7JnfNvX9o1meOPObzvdTLHA2Xuc{9I233#Hn%~?JQ9x8}`M8cA`0!H_ z2=@{8e}*RU4?{#DmttYWpbZ;W{nyf_j`%1VCa(zK0TE@wY9T(RJEw(Crg3=8lNPdY zV9aNi2|<0I6shp1=*Et^4<$djhL(lN`L_^YY#Rk3c{W(5Zvy=k>{L>hM<03JUR|tW z1M|oU2>ls7Sj;9QFUlwwB>&@jf8D(t@q2<4=-Z5pXjKH0z#mI)n`7=2Tmsr1&`c#s z4-h|KDT9$Oi^n51vL0C86{7nyq2<#R6$^hJBk3mv2KVkI@{9IBuFK!(?LJocv~kb8 zrd#0D-CeIGCJ`P2z+@$D6!kZhw9nWo$pU|3Xp?!r1h$NSCMi}i%D*XXe0folQk;p& z|J?=afb&Qi_RmEU5fG*r_f;P$(;wL?xosuNQB?@J8mT{L9P+uyPQ54pU8P-bIE*h~ zw4v}*a(YPIi!^LXF?+exo~6ozH_hSW_~#)D4`f7!lRGFQw~{&<8HG+wyF49VEs_l2 zLj|8PvgC(I$(XyDT`;W-b=XxeuNZvCAy`n~*Z;_no?cv%>U41d{%5m<~m;V7DXaA@SE zSf91NICSRzl=^mf*0A8D(@;ACm7<{=0tx_0-#1Kf*G+t0yqg#?IczOMO3e*C(N zV`oB$r>=;8we6eHfsy3PJY%W1jaa6IUmOi?!rS6g}U z_Mz3zmV4p4hTFq>%ea8Tl(4X(0wUQw}Vm;Q6fXph-c~B6_Ahl-XZW z_<}-K((VhH$>Ykdh2lp#RqeDgMO?~a{v0`l4|<-EspPPFo;qd zm>bYVimY*YUi*jKocW-q`wY`r3=f9hDOc&MXj_aD`B^|A_|bl27JMTE6L;MI0U-a6 ztG5h`qkEzU2MCa$3Bf(M69{etN$}wAt`ppKAV5fP_YCe9bZ|oO;O_1kT!+cO-{0;& z&+dMh4?WX;=jq#h>r~yUI;UaGj%01Yn4_Tu%qCBZd*v2#|CT2C^Af$cUqAVe0y}ys zpT^U9nSzaORLq}UrU4}=9T@EbsX8|tZ)cCW%}u2K41l>LimL35iBi>OxUDA@h6pcx zax72<)*I#jW}S)qX^ED)m#e(YES->8aucu!Q{MSj=V7syn1v_NFta~tcz}E{wWJcH z0?fVHtIxzMU!D3Bl|-@Tgem^w9cGyOB}^CO6u*vfqxU0feyFsiI4fF;&KdCI4stGc$ZK~!DXA3Q#iu!t3D?` zEXtQN1-Kj}e9c8uB`9`MBZ7Q6<8Q9i)yGlfrI~EeY>ZM&i0>-h&0Wmwe=B|wWjVQ< zs+{G1>HWPL3;*~BJ2nAcg3vE5>SiHC`;n*$jK{_UFV+oxm;^f<;_>tld#n4ke={IV zg&JOD_dw|D5F(=Tl9TSwS3zDu^k%AX;4vv&s%SdqB;Musob8_rSS(vMCHuNXZwHd9 z{R7Qa%eBJRK1__IM8q5PhN}GnVf{X%j`+;iH|-E}?Q=@9cg$>ubi-&ORq9RBxMn~e;)7)p&nDCt$@nuH(0_gu z4VPM;^(=N1=&a;Zg92h50qwSEid_$cUJ;k8ziTVPlRXA1{r;j#k`5NXHAZTN#{#29 zyZcHfEZ9xF$CO5`jsRVf)u#p{nzwA1J-49`hfz0Uc&Dw-K9|qOsQQE+BCaDNZ5{I$ z`0S6C=;N=%rJZ4PXB}|t^m@A-7*`Ql>aIzTM-HB4^DnlozoxGQpj;z&mul&9fbu0O zcn3~1M2k%RUSbSsOynaG@qbnG*i$O}1QBl#2lxr-!%6%9GzlTxB&onKNyC~^-US!f zk8?z?=t)Tg54#_zoBjZp$tnqop^_kj+ml$nmA0J_(li?ePcW4|DW>KAqYvt3CHXU}edK6mFx7fOAonZZ*8ybdH7Z|h+C1Huhn0+TM+Gvwc#K81zk8H?ok&kD zylvLeaXljChU5EbNI3oaW%oclrH}5|n^dwSKjLeDRC}MGqP- zeAv+zqWpW;MwK5#B%5|m)7#Y#pG;cgrgyVw*>K5LL)=&CsH8FFQXF!>TYxbrdM@5w zlMR$C%J}VAc^a5;y(bn;e>V=3aakkO6;7WM$ZKCt=~vI+qYl6K1PbkByVhb)6Y^P4 zt^nU`r@|3-ow&2msZv*l<}8Kb?!7_ zypw)HR|W%BDcaMD<@&=6jFJO?k{_%iG2b2A4|?X9Da3B7I%7_jDY{Su7 zGuO@S7h;Ar81{>ml&_h6;Jyu$tHAVicwAC~SaNFR{-9fMiH|!L!g+VddclV&6~QHw zlSnYR{bS$N=Oin`zvq##C4oIkqw9^A>H00O8>-KDf1)GVS=&n19N&|2iN2$Y^U`HL z3LtXSXcPBB51X00Nw=$HYP3y9waF^SOY3J7eo%95PdMcxHdXlYJ}L_@DR?2%J}Sc| z+zDLA|0ueYPPXxV^m-8=T>&O~U1F0=qMxuk^S$2S%ehQ94byRu-_>ShINhl(L+P6) z+VzlWa`!wrgU=;uKk-OS*RP7aV@^3W3}6={i$aB6wAJSpiP~+lB}?`{53J{g^-fMg z)oYBKexZ%uiuq19-4h&sJm64cNRT;9u(5di>$6AKU)A)lE=>XNwEyz!p87KvAAsBS zPAt8+G|fT?e3ATP_gGeVlM0q-C_$uzryw`skXN6rPR7R0{`epeZ+S{rB?F%r&u{bf#qKAP5(Ls)-;Vi+R0V?#-VnFBIJ4B zTLTxvnKdGa;wF_tb-v9v(izVz%2x`#Zmr}+=kc%7erl6xb2xh+s~9V@>LYmfd_V~= zMnU`FIHp>Uv6mfn#RmdqMT9j$(s4_XXDAYD?wT5qK&LRytB>DgcZO~Jf?O>fW$E`N z5v)9y@06}zc6|c}NwgsiQSN3e{IO|PEyLD527!1Z3rQr?Z}5l_R&r2IeA~WAzU7G( z?Wiog3LtKNUak-;xeVPwkiw?TcDx@)9(;oVuUp^sT7s{pCYJ zN_H=8yYT$2W~Qx3N71ooyDQ2w1b&gegFVky9QeAc~*lqQO)U zQc8)3#thZpep&zV*!)-2OT_s{=^S@=hUEPU*Un_L=~IVmq06skaN5DN!21(}2gC8W zgw7OQ=TN4Vka3+PhxkHX_5rf*){FCGV1=cr&)3*jiu`f4r=y0JNcW)Yw9|F%Xk%&o zH;dn4x(_I;EtwSDbw$7`)AjS!5!|4`T(tcIca>piqkn>Um=qU!q6SAw1CGh6f)pc8pr zjImFGm>2e|HUZeZI@+`6@@&eRn=5o=Z)!<#pkB|u*rFDPa2Nc9`N?+ARA0=-aq==5qZXnVW9- z=ad^(3S2dF9n4*m*6r$bq=vzKXiCLcAboVy2uV&Bu_-&hDWKej)fSYa7J-h+d3dXS zx7RyiXI4|RfP6SE9Uw(gUNOV>^tCT!s~{tu2S3;qK+*)k4cntcvgY#r2SZL#bzuU-se_@EH7#h%b2_fdK+RughcZTsFE3 zY-LrO-*Z=YcrFWT9)k^Mz$D&H^Y%X(TWyX<8C+UHF^7TmDBVM)0~O~(*>8DpMECe{ z_c8@waBkv99XIL=UO|+s02d?b_6@h{-hZGM_+JNL6xA>TbI%s=xkb&MSfF0T-eiNF zKQ2|yWHoXMFUQihV|YEuvTvhbEJ__MA_L?5?b3kGQ=(dADwv}@>cQC(nB!AanVhyloWSw7E!0+6uqWk_HYr6pHH9Z&CU?@PdlhAh$x~}}et(d}+M<`wDaR#_Lv`K}?5n?8xiUdTdrw5PfO$FIKDPRebp zuO=jS&{NrsM7of!jPvG)AmJRmmQh@p(*U7GBM#!jrPDyk;iCl^Uz@CqqpjHBAjlxa zre`k6kX@188SP_Ec@0g>hUV^FEPzivIxfHQDa?bPKS}YS9JL696UR8Nibkeyx1^1* zk3Poug5CmjUeSuOHM3?BQ~*67-B+z2YM0U7LIYH?%ptwrmaA;%;-|X~%6HEmR}~4- zj^IS89v)C{wJImZtn8M_VFQ})Vyc)EspQGY2_bHN4xoRaqJ*-4pm%y+)I4W1Y1R(r zLy0LDnLf-&w5+*cY%(vRfZW&>OlIhKaEJnjqPw}=<6-$Fes?>_PZQX4YI{fUnrgZ( zPDBLe8`;?^Zhfto|e#Rj14c|FR4zbvr{DqG*jDmDMCaUwv{%7RQ z3GFj_Q7ftFHA7X5P?*3uUr%D7q<=EtjWyX~6mB6brVnzC(;Y|@l38l0| z=8KC=y-s;sD@{2O!1n8F((9!yW&vstzOdxq={OooOpDzGTC zqsTxj`}av%Hu1&ayB^t1ReVgKjFUr~zYknU=T}~#G!HXx$bzMhxt0Q~4TPd4A>1CBop9 z{M##Ab!1mrlufbpZL1cptEE+!g=1Y5*$sb&)90eSdDb%wotbPlEaH1;pP5Z{DjIC4 ztR?cE@wDAOA7r#_Y)3}R`zSL?bb$lf6I;q}!i zlwBVenX*3fMiWzWt`(a%Xcmh|JRUhPYU`kUAceV-<0-6CCs@cFC+#?7SAWJ< zzO;T-fc^|V%68q6VM&Xk62S$rQ3i=@t73fpzA?f2EaK`1g<`}AiG9@8WOF;UmQlmp zf&wX?E!rnFCF7(+kiLSx0%*@)!`zXhZH9)|?M^3spUsWL=>mJJ#M*dZQ_(Zes+}eaw3d^QXOWQh7Xpo*&Mh6+~BfJL?X2zmuGG zf|c?a=02SCKV2H$B>K8TiS?Hg8->%@AI$E+iCFuD|3GGUof-|%4Bn^1UbA_OqYRkw zCvnOupVU!l&{rt;r1Yr;5bPzA{TawVxWq3d63E{WcJffXzsle3b>U7c!yuxd zZPdM8#z!q*8L_ad^r?QPQo20SBJ_IirK9kWV4%;ht)tnNO19Gga94}V&oGe(rfMcEyJFegb|20f>V7Yl&ACBG3DdB9cg<)RbT-bjkk zyrPZiA>Z^j+t|Ol;K!C;LTg;0M+;@nrS88%K+1kVTHmDvf*kK-~D zf{p=AQd^XjQfXdT{d1PW0@`sDX~NYjlu>(q;_950fI?H)oZX*63WCnt@$y+}u6Lg! zdx&dRnVjpwP<4@^rvE_nTJC?z4i{ZRIjp`ptAA*BIT+(FdVq&{Byk2fEsEv@t zXzIuuR`B9t1*(kzSS1YIpwN5An0}F6)%_>?tQtIb`t>_2eA@k};MqCtH(tSsy8rft zEK9f?Ok2P8i`nmc(?)>K$o!>E!P5Z+k1WD8>18!X-}$;MW8~t_cjZvf4uNtU-<0OF zJ(U(t{)}%0;^7J#P6!egYYH}lDZ=MnnFbc%)5_rzJh9&{@ql20`-z6S-03sl&(*GB zD0YmoLtUpliBq$gE(Jr_>$#+5yT1*$Wo(<8_4wfTKZ8w^7q3n);av1;^Q?y|mBhC$ zy+wwFV`;a=xK0e8pIPkgxn3W@qzYpdlXBkRirHyUi`6M_{P~c-B5mVqJ#8vDyQA_T zl%C&p>?(|4E8wkNkrs=w#9B{Fi>pA{cL|A@HX_zQ5V7qOz|Y9JxIVnoOyN{U+D+2b zz8^{YBCuR0{=L+Ly{_ab(_OV|`!}6a9ZQt_mq2T@FU!|Al{_1R%6Q%C__)ggJQRVN zhW;f3iK;&kV7zaCqHSDK?;Yoeb+1*}pWbnp%EX=vmt6&e>xKFN&jkoqKZx z@uGk7r_Bxgdm!nWKZ>S6;;6j5=jdI~&9mE%q4I)j^-F1ISmQMzdi;Pav8;m2w^x%b zAsc6HF>EB00)8{Bq%As!ZbL7r?ED)l&HNfG0#~D4y_kb|f>W+{Je45AVx(qkymq$vsnWn7hDuALw3o zNA~RugU_}E1x!-nLu{d;$_u%Fpsoj<0x7IG2{j!HxFLR$=1NLV{Laz(9P_DG8iLTT z($^HOavH48fhDTWa@pih5dN%~$i<(^F`ojga2jgrS@%B$LF~k3VZ< zBbMf0*{_Y_!rw6DVMiuuCdI?myP!iDa&ucBA1=`2=J zP5kPSJhDCH z>m6*5f*briwGz}?Y>}2-fYnFMP3;!!)jm>e4OjiRV;Ou-_Yb5BB|j7cZz^^*j_JhS z23fd8@jOgNO`T)pQ>DalRO0dG>QE<>e5p4iZcg`gAF&%Nu$w!iF~yxG+PbQYmf&v) zlF1M51=*nl2P+ei3rNecfbt@6LDu%ZjIfeW71EW3a5X~=__`C<`|`}t&ZcUcz_65Re zT1@^#hQ&S?5&uP5S~40h40fMu>j<;Q5K9J!NiI^A0Hx57dkwU1aLuWRgT39PjoP0E zzwZ;AzW0!OO;_8-rdms`b_!_yZm} zgQnuNOmX(MRK-R#)VDmE#Xp0gp<0GR3-qzC;(Q20@f8-D>!q2Avd-OK~}q#wMvZ zJ;m>V7aZWH0(PDA7uoA#k2=*K@_&Jz=F8>t4XA5k|0G(+N5_(oQ&u9FFA9-esbZ`M zpfx=9GX^S_$+6$(fG){n@3iqAy#_=k-u`uhSxsh=P2jgd7N^CJfX>k9{dY+1&q7r`8xOa;<+W2zCh*(nwi0bw61AdA)^6shc-v%Eix-ep4-K)ZQoWgm-m&Z+K6 z?;~Kykm)D33-28@ibuAEw5TdZN)}=Ipa6M^tgW9_6nb;j9+4s9$E_B~XEYv|@Vi+} z{iN|vmDX7Ch>td4RqtN)=w7!44y$u^fFCp(mcY55#@Z4gpZdA@@t222?12$;1nS^M z>#u%LNuS@3Zq&BR?th?H{PJR%!m7k*ju#zf7E7QOSilg0udl{+EP>(S>$caQ9@kyJ zz9C5|+3FDFvDkM*@~eip*1XP$`V?ndR4K~8>a)3<#af@27VchHw422O>Sfth*J%0$ zkSZ3C7H$TkvlJAJfShl&ABw{p(BrTp^#~EMf3gCc-x+abZw;KbHSs@^o+iuDZD0(l zK70{<;?ZjiWSg#}eH8!Q?_ulx_EYZE*;VPXx0BYl<}XUT+Q7<-54@lam=mT6^GOl6 z82^0D`F?Y5WWu9{PpCgJfcmWSjDPQvsR=TMf0UZ>E8<>&;bK=YR5T9%;BLmifkbz5 z?WBeOj}hH_GrQ)qQS(q7W`uq6y0UT<0V(?jOt?`L99 z5PGFa{}0u6m3#m*BWK~WWNJ5nPDPle(%p-kIMe$hO#O?`AD4`Usr8sy6da(}$ukF^ z_#E%YX8SvL--6rPC2FxX@q*}1O61q(gpP)*eUzkf&>xxS^p&nHbKO5kwD1|*tozpg zfe7h$m{)uQb<19DoaYT*q+t2kbZ#k_s{Rr<{s(f7ve}n`l+OfGABo6Yzk138s%|*V z$w+Uhq}_IZ+kV%^jyd$n!OFIYP79)W8t-;RKEs&`wJrYEr}^|0y7hD|Op~l@+tzSD z|BTXqWa+@q%)BOABJ?L9IOI+4%p|Iy3To9u=u*wEeO zRJ7J8HJ*-kwNv%^*z}a-Ja0vL;+(MTLpffjF)JsRMMmGI!2uapob|I;rv!-$nZl$9 zdrpDv{t}MGn0p7(OF=5*8dk^QONIQO65WqX*--3QoJGFW2Rh|0d# zbu_VnHN3ajGir-Cp)?qb0ZYM9uFHMfHxK9Do7oX%`4Qm|-)k~>2;CN%?ph$m37ZTl zT|vLhPBE{F-!nDU!8R$p5@u0}D`JZ(b3Q4g;Q4pnu z!q`70U}F4YycHojmm$(@37WZw&qq-xr+tmCJYTLB+?+30PD}Itc}EfCS$p0^5&fQn zS?rjf%}%59BRH7^@1xGtU&bl!%}#i7&)L(YvaC21Rj6oLq0VH){hT&MhgV=Votc@) z`QUYx^VitpX4$g|my3AA6{V7~z2)Qtqg=07gZ-84Vv{oQZBY~bKfbA8!}d_q`_#BWswCnz0uIUZ1R^lx;+tTSsf?HboCdW zcLjSZ&lkz6+D-B9LMub*IPV-hw!^7s=X#S%K;SaeYM2vNZih=rD^Q!zN1cLSR zCR0V>V=P1!WA}%^tp3r}!9_j{650?@!CpLNLm>-@XPRMuRnyS6DrlC{$6Cn2oRFqs zL5Yzt_9efJCGNiQ@t-!V6>^EVV*ftLHza`W+%j4;wVYPJWai@WbW5gr3vj|M+d+H} z7;4krJd5iM^c)k?de}?s=buU9mpzW9aFaIpA{bryp7x{7U`#g}|M&;Nmj6u-+DJ%#%MkP&+JcdcNl zj_p*P0h8^;fDrXI(z_o`Ou43V^++TAuMIZ&(|p(O;&JVdI+s!+?fGf*UPtk#_?YKq zJ49oaQ)@j+l^>vxf=mOyA9*`^eLy|76IHZ3l2satyIO9+h%xThCQL3-#eCIzYFDAM5m1c6`5c-p>YO-Aw_ z*nRn7vs!WqCLDpr;))F4VsKD7)GAqZy@OVySS<=3+Q@`9YYw^dkh zAEkN0R8GQQ)vu%*yaT7GWl`IEP1P1{=N_=S&qK_i*AxTKg>2vhh&~rXs*_{l*KHZN z$-D9IHViBKPK5`kfL84=XGdR-<5LM5yN#3p0iXKEhHZIlg64&vvLq>m{JOZA(=!!v6!Q@a#3MtQI5{^IB};kJebBZFTxopZ=Ce`O)Hk`%SNv zxA6xOjU=)iHY<%$xUx65v!hNF@6qr}=;=~f+^E-`?F&Z=G;(#MX&>f74+V|iP3$Z{ zOAq7rPMe!uqpxT;f&9bgyX1T1Y6pUA4PkeIopuAs#?ezybfA6I0^fb)G`N$IXxQ#t zL^1%BIsm31(Fc)y;X3Es4xayj3j(mxOaI}u^$_jXUb*&l2Rga(K*vs?o_|C)QOv$2zELg={b zBXCJJa7m-TDs)#A3h)FtA^D!t+^A1m#7n@3a~DLs2aQLQJoh@G`X+aIrxz67*CUdH z?4eROgTf5!UR9%`M%uHzy`z<0e7`qxa2zcc=j~8T-Nt>CRen-8a0!qnk4Zn`n5>xm zNm}S#klishs=^3`HR@R#2836|tCWw>cn(MmNBd47|U1=%$t0aWjJA z`$;ikG(}+@4*39y?~baN{MZ1P?Xr7)?b|a;@1%dAb@#Omwe08qQZ$#mGzh#@1j`OK z?5mo~t@Qi-x86iuu^0$Rv45c7GSD*-le3bYv(#8~8S8TrDHwMlQ1c@EehJ zJ!d!#J_FJ+eHs2*)zyf8ej3CJ=y~2ylgYs0Dd$3682=B>`f#LP=Z>yTFHoKLg!zA+ zk?U_(#d_aR`SBlUX$UB)BEH1FCx==lf)8N@2J+y&L~R=cQ^wd6`t@tT1aKqypucU( z0cHjD|Gft^2s>Rarw_LOK+F7v4rq8Y1HcVhm1eh>*)t=T;CE9Ly>lmXsvTgxOoVOI zm|Ptx?MsN~bPRjX&N=^43^&&xAW&6|uoqQ%xytyv{#J*Z+DGFJcs7pa!&0?EN03AH z%eHgR5P{TMQ6GsJ_+L^&x9ch{rT4O~A7fC!3ZB^68fqr&0ktOghyOr7xR)6Jfne45 z+T1lRM^^5!cYsEG}SzVL;b(fI8Y?7+-vOSP z6-QHX^fT2M(1Q(N>g&<&a;MlUjqo3R6N1F?Y_U1jAawGZO|nkJsIoUFbHFOn;yOjB zL7pYbR~b7*dr`ra0dm=qFj1_%TzQ)?F>Qwt_{c>mSjuozOqX+b?JRB?UAHh5@pjfY2uJ=$yP`X)Y*$7KUG`W!ubYH%nw4T10iv();;0GPu9- zcLk7-l^e^2Zb1y&-6gmZ4Qk~ILbO_=c)#FyDPvw1Y)Y3jZ&>T@5 z99&m%tNP?btYoYzO|hC@pn6eWxcX)!aC-HqkYp_GAk?4%r&%@!qe=`duu`9T6{wGM znQNs7y99oTy0S$5y|f#je(Nj7p<~RNLnu~#+-cu@kIO^+AcF1Vw>KQFqrP>Ni5gh- zQA=zqAI-j7!x^o@dLp)}i58C(7&E$cqFt!-QR}vH;!v`uXp&tW254jQTEqzzOS~0~ zSUc=0U%=+QOz~;`w!pXZxqh{u0DbA)JXizaCkDx1XEOF`M&Zx%BG5VCVgXqlkOyi) zgrtxKKyqK~m4n_3G(P9xVL=SaS^b+g6Nr&VIGQPHN?u;LZLfS1^8i@Q zXU#he^^UL>lE!#>)MB5Cn*8wxc3T1@rh4@&Bpkvc)z_&#WlI!v1EeU` z{zzCX;}Tt-=DKZhvN>@*YRu3+TNgEy=)N*_(b6$Ef5%OJeY*j`)s}3X`L0CNuYA-F zSLEC|_zANCAAyqya1s2!4{kmi?oHI2>WrE!t^!sh=QJ0a=sNqS@q!0dCU*fGR#_B~h- z@GaC7H@K<$3gF*HF`vMSNJ7{9u+i0xK79UY4<@$|L#3V6sLwGB=eXS#05JUnsp)AP z1~LbKbMU;{nmic+(BsE+I>Tm(q0Dx6a(Sc^P^RpA8h+?LXfshP1%zDs)Nm;FvUN8GB8M1}6(Er~B<6=ft)kY8?iTo?|Khz6qaVQvD zb{d%4s!xsTTZ;#7El13zGWI^|KQ{{)QW3aESk0RDH2zZ?_-?{fgoPv9RutFd>%>=~ zDpBNXDy49d%KL}WwXIJQoYN{s@2{S$oz4r*V2KcH92bMx_%rrihI8>tz;r1#k5y-^ zZK*BZMVxb~0X(0Un7h@S;5qm-V$(bB!5}0ckYz) ztfL5YY-$RvI$>&D%chn&=ZQT&L528raODdAqn~f7hsS27oUtDN(n?ut%u+Kx85+=z zM|eyka?f`;XI56L$D7^ypbgA?X!U?yC%nqJMv+_4)w04qY92vpu^+(N;S>?mmLWA) zEiu8)BKv5WN%}enV1hW14s-Jq^}_uvxMPsvV>>V^yI~v~CHeR^a9@rEJ4G8zBL*y{mnx&InLye&Vx<-++PKl*~< zT1@kMrFUHaZby5GG>NreG3ZHnupm`^hC5%gxwExJ(u>{j&nU{ZstTd&_koc|zUuGH z4v|Y}O4|7SQI|gaPsy?&8p7_s}0UEJ0NZsr? zUrS&eDYfzcpehL^dmLCAMa}-G&&5J|-80AsOYYtWuqLISkd8S3dTo-oUEtgCg7yU_ z{ME>h_THtK3SUSr>2XBJ)7-0ioNE>eN0?acz8R`d*-eA;ekkShfdFAg(xR!>akSFs zBZOI#Xu&Di<*W)ygmFURlot2XH!p`g{0QH6?aCb!KKpy;tMk+Nu4784VR7~4boHkA z>e3DZpa1uo(bA$}eG6mqO|0;}<$^0dbqLK{#8EhaTE~tOGzYz5ec60BB#HyJy2;E3 z$Y+`)#2G6^uT>i&wL_4;bQ`~_h>hHOY*tyv@eld%xcjyj&s*=#}RWxW9{4)oQFt(W!|0R6l z%6_u>)QeNyJ@Ny4Es9fT{oD!cl_j^yT~--U%3k{XW#(ZEXCS$5R+C0a==2Bhcr-afG>c^?0>#K5Y71sQ108?reY%X;QWqMs5^HoP__#G|6SwspPBwII59ba{x^o( z|8p#!Nh8Ad`uDBU1lzO(ev>stxQYE>!?c*1mlsi+@65T6Azg?&BEea7&dP?V90G(A z_A^yGamo%e(cN*wco zzN7jdP!4X;P}3!>GKxW`t~xhlS*ji>CJ(d^@m@g$wv@lwV1e0o|8lgMS!9d$yh{ML z`mk1fZ!jT{bbh$LMPM9^UFQvW1;pejy5gbI{K-w2dH4)YcCFmxe)*>VW;X|VvIF?f z`Ty-A`~#(}{^xxFv6pMa-U=qnbxA)pZE_L2b8T7)(W*^RgFwq)#%GzWHjo-Y-6qf6Sdc8wC zSURm}jaQJo+2L!ysONylImoM1#Tdg zdpwM71Ylm=5@4o@CPq6vj`GNl)xWo2(`^oJf;n}K-ObFL^Y0;^3}YW{p?z`30UVOo zC6AX~@S0wZQj_5{^d|3T$iZmE?JE2)~iTX$6*Zr@KNJ5UB zfyJ#8a#uRXUTL_6?AXq+@!`*9F4PfVxT(Tj>kZ0+q=N5A7`0kE&y@;WN0^$uwMbl+ z+_$%Ap~t^}gt@iD2Eq>XY7O2xCXbz*n}rUDeQ^0H%hCM!Ijh1xX8w9pDmJ%dR)q-a z#1!N4*w7po9p$*a2*h*Z&Vfm~T<&%h>@n=dT??eB_&dfv0i}1@D($dQ2gloyuwkdh z(@&O^E?S*%e}KsDfA|Q5`(@kayW)RF*VnBZwlZmT!uDZr=2D)Bx3pUm1lG%!!FO{~ zn~igyw<6^DAp_k}AyiYrhy$T|es)+>6)sLUMh7IjSO2N)EBH>1d%oHT?)nM=xK@g7 z?-u~hyw!rhR2ASI3>)*E-b^`&;KRxCW`DaW=ym4_#ub?a1T8% zR@}sY`AZ@o@E^$QR(dNDvH#QX!~=MBjF(Rvr}F*0&qJ8N-hlvj-=@b4>#wBp-&2Rt zgWX_mgAzprk^1NK{d@A2hp(g;wp(4Yb4FD*loA1;9Os;Qn)%K8C-b}BS%4%{#&<3m zr-g#g@-9p>;({Jv1vnwIHIV@8sVqN-a{*M4W3OD0si4<3o`lV?Yv(spI6KEDN};3v z`zQ8>*>QOfvx**2q&i&N-}Aqa?p}v8ND4D|eNH-$BNa)Ispx23Zy{cD4a$nGHhJ7v zI~(NTA0ZCKfU&jVF+}Tn5eZe*y8vOE+NXGFkxbYH&PEBc)|W9eMEesQ$oqTKp9QZ5``y`}5Xk8V}E z!t9kZdNupe<&uT(5MMt}q1u81Pl#Vzk*+v-;F_q!4xJrumqpK9IObDeHc+O^eb&l# zqOEr5&7U(+eVdwXd~K}wcFp~Z_;VsI#^s7x5r@T7c=Ia-=uQ%#VG9&0&Utdx(G9(3 z-TcUWMPF!`(Z}0X&U&-0K?}PWqkAF$Va6>kFfX^KkY4fAT}YK({y?kMG-o&ldwgQ- zZ41(;5`6~2T9I&^xbGzkVTZ&eoLA`6fzSN{}F{B=T_ zQ8juEizQqwTitdzvUsWe*QbD6wCA1bJr)N>F+a>{G^hAB`=sGfgY=?~t0xy2TaOdn zJiwj~>^gj7Nl=O4WmysA@z;i4OMws@lq||VuwmZYm@!j*nmg{*OV0>O_lv1p#j%nL zz$af)*vp(=6rt;kKJCgNRbfZv8y0`SKhp81FuPGABaMZrq-7h<308k{y0+8u(X)A3 z{a8NuB<;26FCiTzA4R0frobGSHO)SxvCa2QI0thpVyxYtK7d^+mMF4ZzQF*q0ptv$ zO(J%Ld~Jtj%^6h<>n%17b*G4pqrZq{Dr?tGEYxw4e3@ZZN~-aEH;5o5Ati_)k?@d5 z61SJ|SlvA6C7_fCA_P7Pc?BR%HkXJ*4-oFB-Q*Z)K|avBeGhX+g~&{r$T;SQf@}Sw z%06?lDiwKS?UsQUf*|@hH@(}TU45ljG)J$d0HRBVz#OgHL;JP}-U?rKcA6Y|aFH$Q zXw+bdorvo|df0XhiP`iEvjhyFwf9S)c`f(pC;ij!WnZ)nGKGd%(RNrv5f@)8ynSF) zcsB%(`eVap$SYok&OzNk_YSVm$_T}J$A;;m_uY5q)@!7Q!klO4$EaYUG2X4A=4j?m zzC<8o&Kxg$^||+>b?nCDwYuKPBC71;GmHC-%~QwRS_<9!#DAbMelh$~WOA)98Q-a1 zgnJ{M9ff`AQAUWtxpHo$$VV%yFZ|EH39V~uFZ@j#Vh{aB>F7x4hp!KJXe3Z7TgSt> z*a8QgsIUA{=yE8ae8IIgq%i^ghNLRjUz`-%d=6e$iHayBoOr=&RA7NnTH9wkm}Zo| z*gywup;d4C1&B=kJk?E@GJn@rN_u*__NN2`9<@38ivAX62E?f-G+Rdsh5nNDJp-#PKAKZPhLs6_)y0eNqpbZa#LkVcHFAfC?}`d2~hUE7rPYwE)z^raN_(?P}RSZb0llnImS zLG=Y1(xO7^4}5fGG?IR>JXV)q~OHnV9H1z92?*Ts`s&r2C2Xqub@o|o0?wj^F4=^8Ng z4T1SG&tH~`r}#?vJWUh2#r_D24JJ{8R0J$RLNZqT+|Vy*p3lpk-c8pPZb0jQ1w2A%m2*pfsl3yPoBTi!s= zfqp!#r*KoNZr1%juDJRMmO}Lc5iDh|+Bf(w8YrUW^LV*_I57S$l6VXbH7R8Pte9uI zY3E{wc1CZOf%LAzuv_!eHf|S^W#d1Kq~hCic2X{z_r5H`YMNUsiRUm5F?2_!!1^#} zv0l67qx#IS`g5vPh593!$J=x!WIhGhK zWEZ;MzR#3s7=_dcL#7pqd(3t6lHt~ zV%TRFL4J~%$?3<|Z7ImKum^4O4+e848uA|l^zW-JKkOYwA+gO)=^gbb3Nj2Z`?~AW zZGNL@5KoIH=VXC}S_4SNcOt^jO)=IUk((4&zY5-%x)0)c3qnxof{^aBVGV{krKCz|u~mslBB;1|PT3D;ro-o%d_% zFrxz1cY|K{$8i|5!>rJ(hFwNG-{(NzLNcfTGZv&+$u8L$o5)xvsqz^5KPy(XQD;=~ zVeF}E0=f#GY*hKc^keANGH2b3A78@6M|5TpTF{ELO*=BP@9*jGfRL2@&w}{g-vWo4 zJ&L6;>h8I-@|0g6676$6pN_s`0(MMwWk{h5lFy^Yx#T0~%lg>YP+76X@$8i|7-;!b zC?-5h=RKX|K{9P;=al!W$IGVT7>N62_gv8^*E7r;)^L_YW0MhZ>-dgpI7VmMM%8*{ zn8n|5-;HnVB@X|HgqzK4^rNBHtGyX8jpZe?@=W-EPy&i4^~+zo{EkpCzItwWY0yE^ zCeV^cFs}t}@fkNBhbRK8m6Wa%u6u z-6VTeX)IhG*!C5x){0gdW-6Jj+cCLcTz9Dj`TMsJtcl-@R+GgWkC|!~vH+5YgVY+A z5|b&L9X{}Xqs(HE{{RGokIt&grrub{B+QZHq^M6Hi0M}5u^{BG(ds!A=$`h~Pm>{d z{{Xw3gZNaqmCR{a`1@Y5h(UDF>Q=o9Tqt~x_qzUdX*FL9YR$?|qFo;8`^ZW69YtY0 z);9w)Tlq78c~1n?GuT@N^D@{yS$P#UXsf1l(&;ym!{@@#-`juBdpF)c5!6)`Wp0Nx zhZView4QdGcy|x^=OIV@zr!^k*Y3=?zlCRE)tPol{{Vdt>r|(0#NpW5q^dA#)^fHB zyjkrg4nGn90M@MnjkGu!L(zvrS}7)G;?T+{pwkh%;YIRw3H2ixkZJbsaH)^J;9(c) zSd4uuu+ywh_NJGo7A`I0GD^;Kz1!ps{{RAx8IS$6_pCn-T9naYK&$3o-m8Uk)gi%O z&Ss5I*1I1H#ItG_*Q!sF9LEoEV@yW8{{Y)2KlakFo7CD1LZ6N9huR>AszDn}TvCss#`D;G?_93kU(y?_(aT`zv53fiIH#NdvHdxnPtxJ|}YmK`kxu6W$NvImE z$||#Wpa>hSHL2#BXaSU>lNhG~Kn6IbRFu;|45Y<4(oh0XMHB$Elv2u1Sowu@P~bv1pa`5`nxlH2ZLG0lheuz{PCrn! zp(R$8M%~AvGO_vt&*_=~v!k+K=-O(?q{AeU!sK>YVv+{`0LOw>J^jRyYnm3PlCs=c z#6R6Bgg>g2R&))}Xg9I$!`k_T4^tG0DE$?wJX;Y#|9xqXMqxgSNjBfKSn%v|4f&l#TYm2+NhRAJWzJK}V z4-54_)A?4(=w#NVi0&5Agzj(<)qQit7y9Ez8_2>K*J4IE09Ioe?@yT{gpWN>3O=6o zZq%$lHL~L!XOpkt=}_IvO2S)dEC7=2{G~k#n zV9xP$6^JRxA&JC_H*GwRQP7XX5-CYsq;#64m-b$@J+R^@K4e(wvAG|Y zBk-uXtt+`kx8W;2RyN-?newLfE1VPg?Qi%ItmGk-5zyAu<#?R6W6L4JmXeCp%vyJ9 zZ8%d9Qqoe;0@9I9r)Gc_ib2+w859A|nrZ1vNNbqv5{gPF0Sy#VibE2NQqoW$rZh3g za#Uy3aB1|Ttph6?RmjL$2cwK1%v53&w|&qw*513nc%P0r{VL(4q~eEmGy5tF<=hNO zC;aucZOVSD)K+cnh5eYrm7W#oNZdcfR*S(Kwo2iG*@HEtjPWle;cdWuM{mSc%eWcIV-lh6M*#l-PvulqWw()J zQt>$DSxyh&YI#cLFWYPJu>$to`gxIXexx1`>00*4m)zJ)mmlm7AO86~{#Af(frI#hY00KTaN)Gu^%9O&8PAmY_H6Axm_F2ANGzG_%B`iD79b1hRw5*i zZbME~JAioWB$odG_sOoGNr`kX3X;U1E;E)V?`>V7hx@@n{A(xR0E4z>4J%+QQ#icE~SxBK14B(BUws`c$D>lnCG|LDrWi)_^J4pazkeF;2jx+dvFjw*cu-s^+c2xa~k429bk`>JWbH zeJhyKMgXpzPwvOkfFWvvWiK1As*zR?dW`YS072pN9Gdn0q^p?jWI{)@s8PT4IyDA{ z=fhV5dy#H#ZEY@H<>+KZc#8VxF@ui0Rz9Jue`0FyG#F``0DuGcSzjv0@B*^h&vu>Sx&)li^tI3AVT{6MwYezU0i>zvmS zo@$XSS}4UR!K)BaONuc_1*N2=palY)DFMwH#V{}E+MJqW+*@_Fy6U}yV+ZpDinVDk z1~&W2$JVhJd5A`F=zZ%)Ob>MR91wbg zPOh_vQA#N|qci~Q(M`=RXaQ++O{WR~bvA-P87F~55S>jRInrsg6PhcS?FvdLpaP00 zpg~0@Xw3r_nDEB!lA}JOgHNJ>E4{YvyBvBr{-T)_e`h4eESCA|8GOWVt~vcG-)cKl z@}b<1`zjmcET%Po`RQugf%>meS@*UYm6BpiTtnM(?*M*0iqL3dX53Q^{ortE!S2y9 z9m6vJ0CrA)T9*=(j&QBBk(GOP^&dKZT}SIriaYxu=i14>G0Avaa34|I@fCLN-K9I4 z6;|#?0RI3_uxzGD z&-Vet{{Y`Te=6tA(oeaO&D^;4E)Xb2DD6gT5u z5pCiVJZ&F7@bdbSv7-f}%DeO-mAHY|6AH<6tYe$PpOLJu?2!Tt61x7f}9N={C zP+hEOX%Mx}xe~F-iXiTP+H;fqtI^a2Oji})=yy$ba>_w@G6M`9y%+QXyE4OXQI3>= zj!sP~QwhoAy-1@2lRyKUEpxiWpCRVAravjJV_9%UbHN#)4g*+xvsW*0K_#DIi(=iV12o2cDW)^&TK@oIG}p4=ngGezX*Tg!n%^0!?;Z^R zL5eX_6`-y$KoR1T6#P={pa`)`igqZV2*{*0Ar!(W0kmSI+r=)?)_@}0N(D#-7{Q$wP2s*QiCTo`Rj5+rrNVopenM^ln|a66Ge7O#9q zeS2jFlVX)ETb^Q+%vJu zxc5Gu!;i08bb5TE6`6rmkYzV@esFQ^ka_9FQbKG)A(i*d^RO6I94e1aKai{XZjXPh z+@w~~vt-~C!ir=TVNPTjBb~j!8tObVde-{AyKcY?I30(etL5rv%x7Qdr$wEuWa35P zm>y5#*nK}*r~m^106nX=_0tp}fs=03Nu<~dRjmzrULh(lQg-Y1@BH6 zruC%<6aeZmO%3y6oCfMZbBCU3Ge~;TT<2hvl(dwF6j4P028sb14i8TvFGg`>a805SyxDR$6zY$k%t=aO;5L4ySp@H7zJ|S2d(CBns)H!9j`uWSs>;BJPR6?xbVzsn~7vy)2jKy&A zoPV=26mR_uepI@Q*7rUdoKJGFy~VYq!!)1s)fM6^>zu|8I`C^BQ`Lrxs}IiXe=Wz!bTa`=0_jxA5US&*R4K1 zK4pO>kZoB8Q+HPxBOrGf1ZSreNeQu~yuu8>I}QSYg;Dr_O24M*8iu!X95&GxB;aF( z6&<~pPo7V~Yp3wd^IPihIp`Q;*j9=<8S@$U+B0a^2HH#sSB7EK{yv{i)~bL2z!lth z{@5kzTo2<=O>pDy8mR4ZShP}7(*P9eZ784zQi^RTrUU4t6toDrqUw#L+)o31)|X=r zho*7<1dqnA+BO45PIjITsO)PEqY^F;;C&5U(>%+G-Z=S{S9Z@(I^+4&#$1vK$DJD# v>S`XKf(SSu^#+`4tl|n$O{Jy-vp}ZNngD+kQgVAz&;o%@6&`8e&`_ is a flexible and scalable open-source RL infrastructure designed for +Embodied and Agentic AI. This integration enables **reinforcement learning fine-tuning of Vision-Language-Action +(VLA) models** (e.g., GR00T, OpenVLA) on Isaac Lab simulation tasks. + +The typical workflow follows three stages: + +1. **Data collection** — Collect demonstration data from the Isaac Lab environment (e.g., via teleoperation or scripted policy). +2. **Base model training** — Train a VLA base model (e.g., GR00T) on the collected demonstrations using supervised learning. +3. **RL fine-tuning** — Fine-tune the pretrained VLA model on the Isaac Lab task using RLinf with PPO / Actor-Critic / SAC. + +Overview +~~~~~~~~ + +The RLinf integration allows Isaac Lab users to: + +- Fine-tune pretrained VLA models on Isaac Lab tasks using PPO / Actor-Critic / SAC +- Leverage RLinf's FSDP-based distributed training across multiple GPUs/nodes +- Define observation/action mappings from Isaac Lab to GR00T format via a single YAML config +- Register Isaac Lab tasks into RLinf without modifying RLinf source code + +Architecture +~~~~~~~~~~~~ + +.. code-block:: text + + ┌────────────────────────────────────────────────────────────────┐ + │ RLinf Runner │ + │ (EmbodiedRunner / EvalRunner) │ + ├────────────────┬──────────────────────┬────────────────────────┤ + │ Actor Worker │ Rollout Worker │ Env Worker │ + │ (FSDP) │ (HF Inference) │ (IsaacLab Sim) │ + │ │ │ │ + │ Policy │ Multi-step rollout │ IsaacLabGenericEnv │ + │ Update │ with VLA model │ ├─ _make_env_function │ + │ │ │ ├─ _wrap_obs │ + │ │ │ └─ _wrap_action │ + └────────────────┴──────────────────────┴────────────────────────┘ + +**Data flow:** + +1. ``EnvWorker`` runs Isaac Lab simulation and converts observations to RLinf format +2. ``RolloutWorker`` runs VLA model inference (e.g., GR00T) to produce actions +3. Actions are converted back to Isaac Lab format and stepped in the environment +4. ``ActorWorker`` updates the VLA model with PPO/actor-critic loss via FSDP + +Prerequisites +~~~~~~~~~~~~~ + +- **Isaac Lab** installed and configured +- **Isaac-GR00T** repo (for VLA inference and data transforms) +- A **pretrained VLA checkpoint** in HuggingFace format +- Multi-GPU setup recommended (FSDP requires at least 1 GPU) + +Installation +~~~~~~~~~~~~ + +From the Isaac Lab root directory: + +.. code-block:: bash + + # Install isaaclab_contrib with the RLinf extra + pip install -e "source/isaaclab_contrib[rlinf]" --ignore-requires-python + + # Install Isaac-GR00T (pinned version) + git clone https://github.com/NVIDIA/Isaac-GR00T.git + cd Isaac-GR00T + git checkout 4af2b622892f7dcb5aae5a3fb70bcb02dc217b96 + pip install -e .[base] --no-deps + cd ../ + +Quick Start +~~~~~~~~~~~ + +**Training** — RL fine-tuning of a pretrained VLA model: + +.. code-block:: bash + + python scripts/reinforcement_learning/rlinf/train.py \ + --task Isaac-Assemble-Trocar-G129-Dex3-v0 \ + --config_path source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/assemble_trocar/config \ + --config_name isaaclab_ppo_gr00t_assemble_trocar + +**Evaluation** — Evaluate a trained checkpoint with video recording: + +.. code-block:: bash + + python scripts/reinforcement_learning/rlinf/play.py \ + --task Isaac-Assemble-Trocar-G129-Dex3-Eval-v0 \ + --model_path /path/to/checkpoint \ + --config_path source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/assemble_trocar/config \ + --config_name isaaclab_ppo_gr00t_assemble_trocar \ + --video + +Configuration +~~~~~~~~~~~~~ + +All configuration lives in a **single YAML file** loaded by `Hydra `_. +The key configuration block is the ``env.train.isaaclab`` section, which defines how Isaac Lab observations +are converted to GR00T format: + +.. code-block:: yaml + + isaaclab: &isaaclab_config + task_description: "assemble trocar from tray" + + # IsaacLab → RLinf observation mapping + main_images: "front_camera" + extra_view_images: + - "left_wrist_camera" + - "right_wrist_camera" + states: + - key: "robot_joint_state" + slice: [15, 29] + - key: "robot_dex3_joint_state" + + # GR00T → IsaacLab action conversion + action_mapping: + prefix_pad: 15 + suffix_pad: 0 + +Key Files +~~~~~~~~~ + +.. code-block:: text + + scripts/reinforcement_learning/rlinf/ + ├── README.md # Detailed documentation + ├── train.py # Training entry point + ├── play.py # Evaluation entry point + └── cli_args.py # Shared CLI argument definitions + + source/isaaclab_contrib/isaaclab_contrib/rl/rlinf/ + ├── __init__.py + └── extension.py # Task registration, obs/action conversion + +For detailed configuration options, CLI arguments, and how to add new tasks, +see ``scripts/reinforcement_learning/rlinf/README.md``. diff --git a/docs/source/overview/environments.rst b/docs/source/overview/environments.rst index a28d129f7027..39536c32883f 100644 --- a/docs/source/overview/environments.rst +++ b/docs/source/overview/environments.rst @@ -204,6 +204,8 @@ for the lift-cube environment: +-------------------------+------------------------------+-----------------------------------------------------------------------------+------------------------------+ | |cabi_openarm_uni| | |cabi_openarm_uni-link| | Grasp the handle of a cabinet's drawer and open it with the OpenArm robot | | +-------------------------+------------------------------+-----------------------------------------------------------------------------+------------------------------+ + | |g1_assemble_trocar| | |g1_assemble_trocar-link| | Assemble trocar with a Unitree G1 humanoid robot with Dex3 hands | | + +-------------------------+------------------------------+-----------------------------------------------------------------------------+------------------------------+ .. |reach-franka| image:: ../_static/tasks/manipulation/franka_reach.jpg .. |reach-ur10| image:: ../_static/tasks/manipulation/ur10_reach.jpg @@ -228,6 +230,7 @@ for the lift-cube environment: .. |reach_openarm_uni| image:: ../_static/tasks/manipulation/openarm_uni_reach.jpg .. |lift_openarm_uni| image:: ../_static/tasks/manipulation/openarm_uni_lift.jpg .. |cabi_openarm_uni| image:: ../_static/tasks/manipulation/openarm_uni_open_drawer.jpg +.. |g1_assemble_trocar| image:: ../_static/tasks/manipulation/g1_assemble_trocar.jpg .. |reach-franka-link| replace:: `Isaac-Reach-Franka-v0 <../../../source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/franka/joint_pos_env_cfg.py>`__ .. |reach-ur10-link| replace:: `Isaac-Reach-UR10-v0 <../../../source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/ur_10/joint_pos_env_cfg.py>`__ @@ -261,6 +264,7 @@ for the lift-cube environment: .. |reach_openarm_uni-link| replace:: `Isaac-Reach-OpenArm-v0 <../../../source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/openarm/unimanual/joint_pos_env_cfg.py>`__ .. |lift_openarm_uni-link| replace:: `Isaac-Lift-Cube-OpenArm-v0 <../../../source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/lift/config/openarm/joint_pos_env_cfg.py>`__ .. |cabi_openarm_uni-link| replace:: `Isaac-Open-Drawer-OpenArm-v0 <../../../source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/cabinet/config/openarm/joint_pos_env_cfg.py>`__ +.. |g1_assemble_trocar-link| replace:: `Isaac-Assemble-Trocar-G129-Dex3-v0 <../../../source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/assemble_trocar/g129_dex3_env_cfg.py>`__ Contact-rich Manipulation @@ -769,6 +773,11 @@ inferencing, including reading from an already trained checkpoint and disabling - Manager Based - **rsl_rl** (PPO), **rl_games** (PPO), **skrl** (PPO), **sb3** (PPO) - ``newton_mjwarp``, ``physx`` + * - Isaac-Assemble-Trocar-G129-Dex3-v0 + - Isaac-Assemble-Trocar-G129-Dex3-Eval-v0 + - Manager Based + - **rlinf** (PPO) + - * - Isaac-Cart-Double-Pendulum-Direct-v0 - - Direct diff --git a/scripts/reinforcement_learning/rlinf/README.md b/scripts/reinforcement_learning/rlinf/README.md index 4ca96ba4fd2c..725079782f97 100644 --- a/scripts/reinforcement_learning/rlinf/README.md +++ b/scripts/reinforcement_learning/rlinf/README.md @@ -81,7 +81,7 @@ python train.py python train.py --config_name isaaclab_ppo_gr00t_assemble_trocar # Training with task override -python train.py --task Isaac-Assemble-Trocar-G129-Dex3-RLinf-v0 +python train.py --task Isaac-Assemble-Trocar-G129-Dex3-v0 # Training with custom settings python train.py --num_envs 64 --max_epochs 1000 @@ -94,13 +94,13 @@ python train.py --list_tasks ```bash # Evaluate a trained checkpoint -python play.py --model_path /path/to/checkpoint +python play.py --task Isaac-Assemble-Trocar-G129-Dex3-Eval-v0 --model_path /path/to/checkpoint # Evaluate with video recording -python play.py --model_path /path/to/checkpoint --video +python play.py --task Isaac-Assemble-Trocar-G129-Dex3-Eval-v0 --model_path /path/to/checkpoint --video # Evaluate with specific number of environments -python play.py --model_path /path/to/checkpoint --num_envs 8 +python play.py --task Isaac-Assemble-Trocar-G129-Dex3-Eval-v0 --model_path /path/to/checkpoint --num_envs 8 ``` ## Configuration @@ -132,7 +132,7 @@ env: total_num_envs: 4 max_episode_steps: 256 init_params: - id: "Isaac-Assemble-Trocar-G129-Dex3-RLinf-v0" + id: "Isaac-Assemble-Trocar-G129-Dex3-v0" isaaclab: &isaaclab_config # IsaacLab ↔ RLinf mapping (see below) ... eval: diff --git a/source/isaaclab_assets/changelog.d/Adds-Assemble-Trocar-task-Based-RLinf.rst b/source/isaaclab_assets/changelog.d/Adds-Assemble-Trocar-task-Based-RLinf.rst new file mode 100644 index 000000000000..2a79e0a27d50 --- /dev/null +++ b/source/isaaclab_assets/changelog.d/Adds-Assemble-Trocar-task-Based-RLinf.rst @@ -0,0 +1,5 @@ +Added +^^^^^ + +* Added :class:`~isaaclab_assets.robots.unitree.G129_CFG_WITH_DEX3_BASE_FIX` robot configuration + for the Unitree G1 29-DOF with Dex3 hands. diff --git a/source/isaaclab_assets/isaaclab_assets/robots/unitree.py b/source/isaaclab_assets/isaaclab_assets/robots/unitree.py index 7a02c6eff294..8e4f692ca6df 100644 --- a/source/isaaclab_assets/isaaclab_assets/robots/unitree.py +++ b/source/isaaclab_assets/isaaclab_assets/robots/unitree.py @@ -21,10 +21,12 @@ """ import isaaclab.sim as sim_utils -from isaaclab.actuators import ActuatorNetMLPCfg, DCMotorCfg, ImplicitActuatorCfg +from isaaclab.actuators import ActuatorNetMLPCfg, DCMotorCfg, IdealPDActuatorCfg, ImplicitActuatorCfg from isaaclab.assets.articulation import ArticulationCfg from isaaclab.utils.assets import ISAAC_NUCLEUS_DIR, ISAACLAB_NUCLEUS_DIR +HEALTHCARE_S3 = "https://omniverse-content-production.s3-us-west-2.amazonaws.com/Assets/Isaac/Healthcare/0.5.0/132c82d" + ## # Configuration - Actuators. ## @@ -609,3 +611,201 @@ damping=0.2, armature=0.001, ) + + +G129_CFG_WITH_DEX3_BASE_FIX = ArticulationCfg( + spawn=sim_utils.UsdFileCfg( + usd_path=f"{HEALTHCARE_S3}/Robots/UnitreeG1/g1_29dof_with_dex3_base_fix/g1_29dof_with_dex3_base_fix.usd", + activate_contact_sensors=False, + rigid_props=sim_utils.RigidBodyPropertiesCfg( + disable_gravity=False, + retain_accelerations=False, + linear_damping=0.0, + angular_damping=0.0, + max_linear_velocity=1000.0, + max_angular_velocity=1000.0, + max_depenetration_velocity=1.0, + solver_position_iteration_count=4, + solver_velocity_iteration_count=0, + ), + articulation_props=sim_utils.ArticulationRootPropertiesCfg( + enabled_self_collisions=False, solver_position_iteration_count=4, solver_velocity_iteration_count=0 + ), + ), + prim_path="/World/envs/env_.*/Robot", + init_state=ArticulationCfg.InitialStateCfg( + pos=(0.0, 0.0, 0.75), + joint_pos={ + "left_hip_yaw_joint": 0.0, + "left_hip_roll_joint": 0.0, + "left_hip_pitch_joint": -0.05, + "left_knee_joint": 0.2, + "left_ankle_pitch_joint": -0.15, + "left_ankle_roll_joint": 0.0, + "right_hip_yaw_joint": 0.0, + "right_hip_roll_joint": 0.0, + "right_hip_pitch_joint": -0.05, + "right_knee_joint": 0.2, + "right_ankle_pitch_joint": -0.15, + "right_ankle_roll_joint": 0.0, + "waist_yaw_joint": 0.0, + "waist_roll_joint": 0.0, + "waist_pitch_joint": 0.0, + "left_shoulder_pitch_joint": 0.0, + "left_shoulder_roll_joint": 0.0, + "left_shoulder_yaw_joint": 0.0, + "left_elbow_joint": -0.3, + "left_wrist_roll_joint": 0.0, + "left_wrist_pitch_joint": 0.0, + "left_wrist_yaw_joint": 0.0, + "right_shoulder_pitch_joint": 0.0, + "right_shoulder_roll_joint": 0.0, + "right_shoulder_yaw_joint": 0.0, + "right_elbow_joint": -0.3, + "right_wrist_roll_joint": 0.0, + "right_wrist_pitch_joint": 0.0, + "right_wrist_yaw_joint": 0.0, + "left_hand_index_0_joint": 0.0, + "left_hand_middle_0_joint": 0.0, + "left_hand_thumb_0_joint": 0.0, + "left_hand_index_1_joint": 0.0, + "left_hand_middle_1_joint": 0.0, + "left_hand_thumb_1_joint": 0.0, + "left_hand_thumb_2_joint": 0.0, + "right_hand_index_0_joint": 0.0, + "right_hand_middle_0_joint": 0.0, + "right_hand_thumb_0_joint": 0.0, + "right_hand_index_1_joint": 0.0, + "right_hand_middle_1_joint": 0.0, + "right_hand_thumb_1_joint": 0.0, + "right_hand_thumb_2_joint": 0.0, + }, + joint_vel={".*": 0.0}, + ), + soft_joint_pos_limit_factor=0.9, + actuators={ + "legs": IdealPDActuatorCfg( + joint_names_expr=[ + ".*_hip_yaw_joint", + ".*_hip_roll_joint", + ".*_hip_pitch_joint", + ".*_knee_joint", + ], + effort_limit={ + ".*_hip_yaw_joint": 88.0, + ".*_hip_roll_joint": 88.0, + ".*_hip_pitch_joint": 88.0, + ".*_knee_joint": 139.0, + }, + velocity_limit={ + ".*_hip_yaw_joint": 32.0, + ".*_hip_roll_joint": 32.0, + ".*_hip_pitch_joint": 32.0, + ".*_knee_joint": 20.0, + }, + stiffness={ + ".*_hip_yaw_joint": 150.0, + ".*_hip_roll_joint": 150.0, + ".*_hip_pitch_joint": 150.0, + ".*_knee_joint": 300.0, + }, + damping={ + ".*_hip_yaw_joint": 2.0, + ".*_hip_roll_joint": 2.0, + ".*_hip_pitch_joint": 2.0, + ".*_knee_joint": 4.0, + }, + armature={ + ".*_hip_.*": 0.03, + ".*_knee_joint": 0.03, + }, + ), + "feet": IdealPDActuatorCfg( + joint_names_expr=[".*_ankle_pitch_joint", ".*_ankle_roll_joint"], + stiffness={ + ".*_ankle_pitch_joint": 40.0, + ".*_ankle_roll_joint": 40.0, + }, + damping={ + ".*_ankle_pitch_joint": 2, + ".*_ankle_roll_joint": 2, + }, + effort_limit={ + ".*_ankle_pitch_joint": 50.0, + ".*_ankle_roll_joint": 50.0, + }, + velocity_limit={ + ".*_ankle_pitch_joint": 37.0, + ".*_ankle_roll_joint": 37.0, + }, + armature=0.03, + friction=0.03, + ), + "waist": ImplicitActuatorCfg( + joint_names_expr=["waist_yaw_joint", "waist_roll_joint", "waist_pitch_joint"], + effort_limit=1000.0, + velocity_limit=0.0, + stiffness={"waist_yaw_joint": 10000.0, "waist_roll_joint": 10000.0, "waist_pitch_joint": 10000.0}, + damping={"waist_yaw_joint": 10000.0, "waist_roll_joint": 10000.0, "waist_pitch_joint": 10000.0}, + armature=None, + ), + "arms": IdealPDActuatorCfg( + joint_names_expr=[ + ".*_shoulder_pitch_joint", + ".*_shoulder_roll_joint", + ".*_shoulder_yaw_joint", + ".*_elbow_joint", + ".*_wrist_.*_joint", + ], + effort_limit={ + ".*_shoulder_pitch_joint": 25.0, + ".*_shoulder_roll_joint": 25.0, + ".*_shoulder_yaw_joint": 25.0, + ".*_elbow_joint": 25.0, + ".*_wrist_roll_joint": 25.0, + ".*_wrist_pitch_joint": 5.0, + ".*_wrist_yaw_joint": 5.0, + }, + velocity_limit={ + ".*_shoulder_pitch_joint": 37.0, + ".*_shoulder_roll_joint": 37.0, + ".*_shoulder_yaw_joint": 37.0, + ".*_elbow_joint": 37.0, + ".*_wrist_roll_joint": 37.0, + ".*_wrist_pitch_joint": 22.0, + ".*_wrist_yaw_joint": 22.0, + }, + stiffness={ + ".*_shoulder_pitch_joint": 100.0, + ".*_shoulder_roll_joint": 100.0, + ".*_shoulder_yaw_joint": 40.0, + ".*_elbow_joint": 40.0, + ".*_wrist_.*_joint": 20.0, + }, + damping={ + ".*_shoulder_pitch_joint": 15.0, + ".*_shoulder_roll_joint": 15.0, + ".*_shoulder_yaw_joint": 8.0, + ".*_elbow_joint": 8.0, + ".*_wrist_.*_joint": 4.0, + }, + armature={".*_shoulder_.*": 0.03, ".*_elbow_.*": 0.03, ".*_wrist_.*_joint": 0.03}, + friction=0.03, + ), + "hands": IdealPDActuatorCfg( + joint_names_expr=[ + ".*_hand_.*", + ], + effort_limit=5.0, + velocity_limit=10.0, + stiffness=8.0, + damping=1.5, + armature=0.03, + friction=0.5, + ), + }, +) +"""Configuration for the Unitree G1 29DOF robot with Dex3 hands and fixed base. + +This configuration is designed for high-precision manipulation tasks such as trocar assembly. +""" diff --git a/source/isaaclab_contrib/changelog.d/Adds-Assemble-Trocar-task-Based-RLinf.rst b/source/isaaclab_contrib/changelog.d/Adds-Assemble-Trocar-task-Based-RLinf.rst new file mode 100644 index 000000000000..062bce25b772 --- /dev/null +++ b/source/isaaclab_contrib/changelog.d/Adds-Assemble-Trocar-task-Based-RLinf.rst @@ -0,0 +1,5 @@ +Fixed +^^^^^ + +* Removed ``_patched_reset`` monkey-patch in RLinf extension; use + ``num_rerenders_on_reset`` env config instead. diff --git a/source/isaaclab_contrib/isaaclab_contrib/rl/rlinf/extension.py b/source/isaaclab_contrib/isaaclab_contrib/rl/rlinf/extension.py index 89368c532109..1defd1a0d503 100644 --- a/source/isaaclab_contrib/isaaclab_contrib/rl/rlinf/extension.py +++ b/source/isaaclab_contrib/isaaclab_contrib/rl/rlinf/extension.py @@ -440,6 +440,19 @@ def __init__(self, cfg, num_envs: int, seed_offset: int, total_num_processes: in """ super().__init__(cfg, num_envs, seed_offset, total_num_processes, worker_info) + def _record_metrics(self, step_reward, terminations, infos): + """Override to use terminations (task completion) for success_once.""" + + episode_info = {} + self.returns += step_reward + self.success_once = self.success_once | terminations.bool() + episode_info["success_once"] = self.success_once.clone() + episode_info["return"] = self.returns.clone() + episode_info["episode_len"] = self.elapsed_steps.clone() + episode_info["reward"] = episode_info["return"] / episode_info["episode_len"] + infos["episode"] = episode_info + return infos + def _make_env_function(self) -> collections.abc.Callable: """Create the environment factory function. @@ -468,6 +481,7 @@ def make_env_isaaclab() -> tuple: isaac_env_cfg.scene.num_envs = self.cfg.init_params.num_envs env = gym.make(self.isaaclab_env_id, cfg=isaac_env_cfg, render_mode="rgb_array").unwrapped + return env, sim_app return make_env_isaaclab @@ -481,7 +495,6 @@ def _wrap_obs(self, obs: dict) -> dict: - ``"extra_view_images"``: ``(B, N, H, W, C)`` — stacked extra cameras. - ``"states"``: ``(B, D)`` — concatenated state vector. - ``"task_descriptions"``: ``list[str]`` — task descriptions. - Config is read from the YAML file via :func:`_get_isaaclab_cfg`. Args: diff --git a/source/isaaclab_tasks/changelog.d/Adds-Assemble-Trocar-task-Based-RLinf.rst b/source/isaaclab_tasks/changelog.d/Adds-Assemble-Trocar-task-Based-RLinf.rst new file mode 100644 index 000000000000..f5d918d3680f --- /dev/null +++ b/source/isaaclab_tasks/changelog.d/Adds-Assemble-Trocar-task-Based-RLinf.rst @@ -0,0 +1,7 @@ +Added +^^^^^ + +* Added ``Isaac-Assemble-Trocar-G129-Dex3-v0`` and + ``Isaac-Assemble-Trocar-G129-Dex3-Eval-v0`` manipulation tasks: a Unitree G1 + 29-DOF humanoid with Dex3 hands assembles a trocar from a tray, trained via + RL post-training of a VLA model using RLinf. diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/assemble_trocar/__init__.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/assemble_trocar/__init__.py new file mode 100644 index 000000000000..624d02269813 --- /dev/null +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/assemble_trocar/__init__.py @@ -0,0 +1,6 @@ +# Copyright (c) 2022-2026, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md). +# All rights reserved. +# +# SPDX-License-Identifier: BSD-3-Clause + +"""Configurations for the assemble trocar environments.""" diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/assemble_trocar/config/__init__.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/assemble_trocar/config/__init__.py new file mode 100644 index 000000000000..cd8c26c840a5 --- /dev/null +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/assemble_trocar/config/__init__.py @@ -0,0 +1,9 @@ +# Copyright (c) 2022-2026, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md). +# All rights reserved. +# +# SPDX-License-Identifier: BSD-3-Clause + +from .camera_config import CameraBaseCfg, CameraPresets +from .robot_config import G1_29DOF_BODY_JOINT_INDICES, G1_DEX3_JOINT_INDICES, G1RobotPresets + +__all__ = ["G1_29DOF_BODY_JOINT_INDICES", "G1_DEX3_JOINT_INDICES", "G1RobotPresets", "CameraBaseCfg", "CameraPresets"] diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/assemble_trocar/config/camera_config.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/assemble_trocar/config/camera_config.py new file mode 100644 index 000000000000..405948726034 --- /dev/null +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/assemble_trocar/config/camera_config.py @@ -0,0 +1,131 @@ +# Copyright (c) 2022-2026, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md). +# All rights reserved. +# +# SPDX-License-Identifier: BSD-3-Clause + +""" +public camera configuration +include the basic configuration for different types of cameras, support scene-specific parameter customization +""" + +from collections.abc import Sequence + +import isaaclab.sim as sim_utils +from isaaclab.sensors import CameraCfg +from isaaclab.utils import configclass + + +@configclass +class CameraBaseCfg: + """camera base configuration class + + provide the default configuration for different types of cameras, support scene-specific parameter customization + """ + + @classmethod + def get_camera_config( + cls, + prim_path: str = "/World/envs/env_.*/Robot/d435_link/front_cam", + update_period: float = 0.02, + height: int = 480, + width: int = 640, + focal_length: float = 7.6, + focus_distance: float = 400.0, + horizontal_aperture: float = 20.0, + clipping_range: tuple[float, float] = (0.1, 1.0e5), + pos_offset: tuple[float, float, float] = (0.0, 0.0, 0.0), + rot_offset: tuple[float, float, float, float] = (0.5, -0.5, 0.5, -0.5), + data_types: Sequence[str] | None = None, + ) -> CameraCfg: + """Get a pinhole camera configuration. + + Args: + prim_path: the path of the camera in the scene + update_period: update period (seconds) + height: image height (pixels) + width: image width (pixels) + focal_length: focal length + focus_distance: focus distance + horizontal_aperture: horizontal aperture + clipping_range: clipping range (near clipping plane, far clipping plane) + pos_offset: position offset (x, y, z) + rot_offset: rotation offset quaternion + data_types: data type list + + Returns: + CameraCfg: camera configuration + """ + if data_types is None: + data_types = ("rgb",) + + return CameraCfg( + prim_path=prim_path, + update_period=update_period, + height=height, + width=width, + data_types=list(data_types), + spawn=sim_utils.PinholeCameraCfg( + focal_length=focal_length, + focus_distance=focus_distance, + horizontal_aperture=horizontal_aperture, + clipping_range=clipping_range, + ), + offset=CameraCfg.OffsetCfg(pos=pos_offset, rot=rot_offset, convention="ros"), + ) + + +@configclass +class CameraPresets: + """camera preset configuration collection + + include the common camera configuration preset for different scenes + """ + + @classmethod + def g1_front_camera(cls, **overrides) -> CameraCfg: + params = { + "height": 224, + "width": 224, + "focal_length": 10.5, + "horizontal_aperture": 14.25, # Match original vertical FOV after crop + } + params.update(overrides) + return CameraBaseCfg.get_camera_config(**params) + + @classmethod + def left_dex3_wrist_camera(cls, **overrides) -> CameraCfg: + """left wrist camera configuration""" + params = { + "prim_path": "/World/envs/env_.*/Robot/left_hand_camera_base_link/left_wrist_camera", + "height": 224, + "width": 224, + "update_period": 0.02, + "data_types": ["rgb"], + "focal_length": 12.0, + "focus_distance": 400.0, + "horizontal_aperture": 14.25, # Match original vertical FOV after crop + "clipping_range": (0.1, 1.0e5), + "pos_offset": (-0.04012, -0.07441, 0.15711), + "rot_offset": (0.00539, 0.86024, 0.0424, 0.50809), + } + params.update(overrides) + return CameraBaseCfg.get_camera_config(**params) + + @classmethod + def right_dex3_wrist_camera(cls, **overrides) -> CameraCfg: + """right wrist camera configuration""" + params = { + "prim_path": "/World/envs/env_.*/Robot/right_hand_camera_base_link/right_wrist_camera", + "height": 224, + "width": 224, + "update_period": 0.02, + "data_types": ["rgb"], + "focal_length": 12.0, + "focus_distance": 400.0, + "horizontal_aperture": 14.25, # Match original vertical FOV after crop + "clipping_range": (0.1, 1.0e5), + "pos_offset": (-0.04012, 0.07441, 0.15711), + "rot_offset": (0.00539, 0.86024, 0.0424, 0.50809), + } + params.update(overrides) + return CameraBaseCfg.get_camera_config(**params) diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/assemble_trocar/config/gr00t_config.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/assemble_trocar/config/gr00t_config.py new file mode 100644 index 000000000000..540b0edbc3a0 --- /dev/null +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/assemble_trocar/config/gr00t_config.py @@ -0,0 +1,144 @@ +# Copyright (c) 2022-2026, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md). +# All rights reserved. +# +# SPDX-License-Identifier: BSD-3-Clause + +"""GR00T data configuration for IsaacLab tasks. + +This module defines customizable GR00T data configurations for different +embodiments. Users can create their own data config classes by subclassing +BaseDataConfig or copying/modifying the examples here. + +Example usage in run.sh: + export RLINF_DATA_CONFIG="policy.gr00t_config" + export RLINF_DATA_CONFIG_CLASS="policy.gr00t_config:IsaacLabDataConfig" +""" + +from gr00t.data.dataset import ModalityConfig +from gr00t.data.transform.base import ComposedModalityTransform +from gr00t.data.transform.concat import ConcatTransform +from gr00t.data.transform.state_action import StateActionSinCosTransform, StateActionToTensor, StateActionTransform +from gr00t.data.transform.video import VideoColorJitter, VideoToNumpy, VideoToTensor +from gr00t.experiment.data_config import DATA_CONFIG_MAP, BaseDataConfig +from gr00t.model.transforms import GR00TTransform + + +class IsaacLabDataConfig(BaseDataConfig): + """Generic GR00T data config for IsaacLab tasks with G1 + Dex3.""" + + # Video modality keys (from gr00t_mapping.video in RLINF_OBS_MAP_JSON) + video_keys = [ + "video.left_wrist_view", + "video.right_wrist_view", + "video.room_view", + ] + + # State modality keys (from gr00t_mapping.state in RLINF_OBS_MAP_JSON) + state_keys = [ + "state.left_arm", + "state.right_arm", + "state.left_hand", + "state.right_hand", + ] + + # Action modality keys (output from GR00T model) + action_keys = [ + "action.left_arm", + "action.right_arm", + "action.left_hand", + "action.right_hand", + ] + + # Language annotation key + language_keys = ["annotation.human.task_description"] + + # Observation and action indices + observation_indices = [0] + action_indices = list(range(16)) + + def modality_config(self) -> dict[str, ModalityConfig]: + """Define modality configurations for video, state, action, and language.""" + video_modality = ModalityConfig( + delta_indices=self.observation_indices, + modality_keys=self.video_keys, + ) + + state_modality = ModalityConfig( + delta_indices=self.observation_indices, + modality_keys=self.state_keys, + ) + + action_modality = ModalityConfig( + delta_indices=self.action_indices, + modality_keys=self.action_keys, + ) + + language_modality = ModalityConfig( + delta_indices=self.observation_indices, + modality_keys=self.language_keys, + ) + + return { + "video": video_modality, + "state": state_modality, + "action": action_modality, + "language": language_modality, + } + + def transform(self): + """Define the transform pipeline for processing observations and actions.""" + transforms = [ + # Video transforms + VideoToTensor(apply_to=self.video_keys), + # Disabled: camera already outputs 224×224 via TiledCameraCfg. + # To avoid VideoToTensor size-check errors, either: + # 1. Disable input size validation in VideoToTensor, OR + # 2. Set modality meta height/width to 224 to match actual input. + # Re-enable VideoCrop/VideoResize if camera resolution changes. + # VideoCrop(apply_to=self.video_keys, scale=0.95), + # VideoResize( + # apply_to=self.video_keys, + # height=224, + # width=224, + # interpolation="linear", + # ), + VideoColorJitter( + apply_to=self.video_keys, + brightness=0.3, + contrast=0.4, + saturation=0.5, + hue=0.08, + ), + VideoToNumpy(apply_to=self.video_keys), + # State transforms + StateActionToTensor(apply_to=self.state_keys), + StateActionSinCosTransform(apply_to=self.state_keys), + # Action transforms + StateActionToTensor(apply_to=self.action_keys), + StateActionTransform( + apply_to=self.action_keys, + normalization_modes={key: "min_max" for key in self.action_keys}, + ), + # Concat transforms + ConcatTransform( + video_concat_order=self.video_keys, + state_concat_order=self.state_keys, + action_concat_order=self.action_keys, + ), + # Model-specific transform + GR00TTransform( + state_horizon=len(self.observation_indices), + action_horizon=len(self.action_indices), + max_state_dim=64, + max_action_dim=32, + ), + ] + return ComposedModalityTransform(transforms=transforms) + + +# -------------------------------------------------------------------------- +# Register data configs into GR00T's DATA_CONFIG_MAP +# -------------------------------------------------------------------------- + +# This allows load_data_config("policy.gr00t_config:IsaacLabDataConfig") to work +DATA_CONFIG_MAP["isaaclab_g1_dex3"] = IsaacLabDataConfig() diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/assemble_trocar/config/isaaclab_ppo_gr00t_assemble_trocar.yaml b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/assemble_trocar/config/isaaclab_ppo_gr00t_assemble_trocar.yaml new file mode 100644 index 000000000000..b130a12a8a53 --- /dev/null +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/assemble_trocar/config/isaaclab_ppo_gr00t_assemble_trocar.yaml @@ -0,0 +1,298 @@ +# Copyright (c) 2022-2026, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md). +# All rights reserved. +# +# SPDX-License-Identifier: BSD-3-Clause + +defaults: + - override hydra/job_logging: stdout + +hydra: + run: + dir: . + output_subdir: null + +cluster: + num_nodes: 1 + component_placement: + actor,env,rollout: all + +runner: + task_type: embodied + logger: + log_path: "../results" + project_name: rlinf + experiment_name: "test_gr00t" + logger_backends: ["tensorboard"] # wandb, swanlab + + max_epochs: 1000 + max_steps: -1 + + only_eval: False + eval_policy_path: null # Optional: .pt file or None, if None, will use the checkpoint in rollout.model.model_path + val_check_interval: -1 + save_interval: 2 + seq_length: 4096 + max_prompt_length: 30 + + resume_dir: null + +algorithm: + normalize_advantages: True + kl_penalty: kl # how to estimate kl divergence: kl or kl_penalty + group_size: 1 + reward_coef: 1.0 + rollout_epoch: 2 + eval_rollout_epoch: 1 # set eval_rollout_epoch > 0 when enable runner.only_eval or runner.val_check_interval > 0 + + reward_type: chunk_level + logprob_type: chunk_level + entropy_type: chunk_level + + update_epoch: 4 + adv_type: gae + loss_type: actor_critic + loss_agg_func: "token-mean" + kl_beta: 0.0 + entropy_bonus: 0 + clip_ratio_high: 0.2 + clip_ratio_low: 0.2 + clip_ratio_c: 3.0 + value_clip: 0.2 + huber_delta: 10.0 + + gamma: 0.99 + gae_lambda: 0.95 + + filter_rewards: False + rewards_lower_bound: 0.1 + rewards_upper_bound: 0.9 + # params for generation + sampling_params: + do_sample: True + temperature_train: 1.0 + temperature_eval: 0.6 + top_k: 50 + top_p: 1.0 + repetition_penalty: 1.0 + add_BOS: False + + # length argument for autoregressive sampling + # max length means max amount of tokens to generate + length_params: + max_new_token: null + max_length: 1024 + min_length: 1 + +# --------------------------------------------------------------------------- +# Environment +# --------------------------------------------------------------------------- +env: + group_name: "EnvGroup" + channel: + name: "env_buffer_list" + queue_name: "obs_buffer" + queue_size: 0 + enable_offload: False + + train: + env_type: isaaclab + total_num_envs: 4 + auto_reset: False + ignore_terminations: False + use_rel_reward: True + seed: 0 + group_size: 1 + reward_coef: 1.0 + use_fixed_reset_state_ids: True + max_steps_per_rollout_epoch: 256 + max_episode_steps: 256 + video_cfg: + save_video: False + info_on_video: True + video_base_dir: ${runner.logger.log_path}/video/train + init_params: + id: "Isaac-Assemble-Trocar-G129-Dex3-v0" + num_envs: null + max_episode_steps: ${env.train.max_episode_steps} + task_description: "assemble trocar from tray" + + # ======================================================================== + # IsaacLab -> RLinf -> GR00T observation/action mapping configuration + # This section defines how IsaacLab observations are converted to GR00T format + # ======================================================================== + isaaclab: &isaaclab_config # YAML anchor for reuse in eval + # Task description for language conditioning + task_description: "assemble trocar from tray" + + # --- IsaacLab -> RLinf observation mapping --- + # main_images: single camera key for main view + main_images: "front_camera" + # extra_view_images: list of camera keys to stack as (B, N, H, W, C) + extra_view_images: + - "left_wrist_camera" + - "right_wrist_camera" + # states: list of state specs with optional slicing + # Each entry can be a string (use full tensor) or dict with "key" and "slice" + states: + - key: "robot_joint_state" + slice: [15, 29] # G129 shoulder joints + - key: "robot_dex3_joint_state" + # slice: null # Use full tensor + + # --- RLinf -> GR00T format conversion --- + gr00t_mapping: + video: + main_images: "video.room_view" + extra_view_images: + - "video.left_wrist_view" + - "video.right_wrist_view" + state: + # Slice concatenated states into GR00T state keys + # Total states: 14 (shoulder) + 14 (dex3) = 28 dims + - gr00t_key: "state.left_arm" + slice: [0, 7] + - gr00t_key: "state.right_arm" + slice: [7, 14] + - gr00t_key: "state.left_hand" + slice: [14, 21] + - gr00t_key: "state.right_hand" + slice: [21, 28] + + # --- GR00T -> IsaacLab action conversion --- + action_mapping: + prefix_pad: 15 # Pad zeros at front for G129 body joints (not controlled) + suffix_pad: 0 + + # --- GR00T model configuration (single source of truth) --- + # actor.model.embodiment_tag and obs_converter_type reference these values via ${} + obs_converter_type: "dex3" + embodiment_tag: "new_embodiment" + embodiment_tag_id: 31 + data_config_class: "gr00t_config:IsaacLabDataConfig" + + eval: + env_type: isaaclab + total_num_envs: 4 + auto_reset: True + ignore_terminations: True + use_rel_reward: True + seed: 0 + group_size: 1 + reward_coef: 1.0 + use_fixed_reset_state_ids: True + max_steps_per_rollout_epoch: 256 + max_episode_steps: 256 + video_cfg: + save_video: True + info_on_video: True + video_base_dir: ${runner.logger.log_path}/video/eval + init_params: + id: "Isaac-Assemble-Trocar-G129-Dex3-Eval-v0" + num_envs: null + max_episode_steps: ${env.eval.max_episode_steps} + task_description: "install trocar from box" + # Reuse IsaacLab config from train section via YAML anchor + isaaclab: *isaaclab_config + +# --------------------------------------------------------------------------- +# Rollout +# --------------------------------------------------------------------------- +rollout: + group_name: "RolloutGroup" + channel: + name: ${env.channel.name} + queue_name: "action_buffer" + queue_size: 0 + mode: "colocate" + backend: "huggingface" + enable_offload: True + pipeline_stage_num: 1 + + model: + model_path: "/mnt/ckpt/g1_install_trocar_sim_box_v3_60_train_bs32_1_gpus_cos_30k_tune_visual/" + precision: ${actor.model.precision} + obs_converter_type: ${env.train.isaaclab.obs_converter_type} + embodiment_tag: ${env.train.isaaclab.embodiment_tag} + +# --------------------------------------------------------------------------- +# Actor +# --------------------------------------------------------------------------- +actor: + group_name: "ActorGroup" + channel: + name: ${env.channel.name} + queue_name: "replay_buffer" + queue_size: 0 + training_backend: "fsdp" + micro_batch_size: 2 + global_batch_size: 4 + seed: 1234 + enable_offload: False + + model: + model_type: "gr00t" + model_path: "/mnt/ckpt/g1_install_trocar_sim_box_v3_60_train_bs32_1_gpus_cos_30k_tune_visual/" + precision: "bf16" + trust_remote_code: True + is_lora: false + action_dim: 28 + num_action_chunks: 1 + denoising_steps: 4 + policy_setup: "widowx_bridge" + obs_converter_type: ${env.train.isaaclab.obs_converter_type} + embodiment_tag: ${env.train.isaaclab.embodiment_tag} + add_value_head: True + rl_head_config: + joint_logprob: False + noise_method: "flow_sde" + ignore_last: False + safe_get_logprob: False + noise_anneal: False + noise_params: [0.7, 0.3, 400] + noise_level: 0.3 + add_value_head: ${actor.model.add_value_head} + chunk_critic_input: False + detach_critic_input: True + disable_dropout: True + use_vlm_value: False + value_vlm_mode: "mean_token" + padding_value: 850 + + optim: + lr: 5e-6 + value_lr: 1e-4 + adam_beta1: 0.9 + adam_beta2: 0.95 + adam_eps: 1.0e-08 + clip_grad: 1.0 + weight_decay: 0.01 + critic_warmup_steps: 0 + + fsdp_config: + strategy: "fsdp" + sharding_strategy: "full_shard" + gradient_checkpointing: False + cpu_offload: False + offload_pin_memory: False + reshard_after_forward: True + enable_gradient_accumulation: True + forward_prefetch: False + limit_all_gathers: False + backward_prefetch: null + use_orig_params: False + use_liger_kernel: False + fsdp_size: -1 + mixed_precision: + param_dtype: ${actor.model.precision} + reduce_dtype: ${actor.model.precision} + buffer_dtype: ${actor.model.precision} + amp: + enabled: False + precision: "bf16" + use_grad_scaler: False + +reward: + use_reward_model: False + +critic: + use_critic_model: False diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/assemble_trocar/config/robot_config.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/assemble_trocar/config/robot_config.py new file mode 100644 index 000000000000..81c60741b784 --- /dev/null +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/assemble_trocar/config/robot_config.py @@ -0,0 +1,147 @@ +# Copyright (c) 2022-2026, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md). +# All rights reserved. +# +# SPDX-License-Identifier: BSD-3-Clause + +"""Robot configuration for the `install_trocar` task. + +This file is intentionally **minimal**: +- Supported robot: **Unitree G1 (29 DOF body)** +- Supported hands: **Dex3** + +The only public entry point expected by the task is +`G1RobotPresets.g1_29dof_dex3_base_fix(...)`. +""" + +import numpy as np + +from isaaclab.assets import ArticulationCfg +from isaaclab.utils import configclass + +from isaaclab_assets.robots.unitree import G129_CFG_WITH_DEX3_BASE_FIX + +# Joint indices in the full robot joint vector for observation extraction. +# Body joints: 29 DOF (legs, waist, arms, wrists) +G1_29DOF_BODY_JOINT_INDICES: list[int] = [ + 0, + 3, + 6, + 9, + 13, + 17, + 1, + 4, + 7, + 10, + 14, + 18, + 2, + 5, + 8, + 11, + 15, + 19, + 21, + 23, + 25, + 27, + 12, + 16, + 20, + 22, + 24, + 26, + 28, +] + +# Dex3 hand joints: 14 DOF (left + right) +G1_DEX3_JOINT_INDICES: list[int] = [31, 37, 41, 30, 36, 29, 35, 34, 40, 42, 33, 39, 32, 38] + +# Default joint positions for the supported setup (G1 29DOF + Dex3). +DEFAULT_JOINT_POS: dict[str, float] = { + # legs + "left_hip_pitch_joint": 0.0, + "left_hip_roll_joint": 0.0, + "left_hip_yaw_joint": 0.0, + "left_knee_joint": 0.0, + "left_ankle_pitch_joint": 0.0, + "left_ankle_roll_joint": 0.0, + "right_hip_pitch_joint": 0.0, + "right_hip_roll_joint": 0.0, + "right_hip_yaw_joint": 0.0, + "right_knee_joint": 0.0, + "right_ankle_pitch_joint": 0.0, + "right_ankle_roll_joint": 0.0, + # waist + "waist_yaw_joint": 0.0, + "waist_roll_joint": 0.0, + "waist_pitch_joint": 0.0, + # arms + "left_shoulder_pitch_joint": -0.754599, + "left_shoulder_roll_joint": 0.550010, + "left_shoulder_yaw_joint": -0.399298, + "left_elbow_joint": 0.278886, + "left_wrist_roll_joint": 0.320559, + "left_wrist_pitch_joint": -0.203525, + "left_wrist_yaw_joint": -0.387435, + "right_shoulder_pitch_joint": -0.340858, + "right_shoulder_roll_joint": -0.186152, + "right_shoulder_yaw_joint": 0.015023, + "right_elbow_joint": -0.777159, + "right_wrist_roll_joint": 0.019805, + "right_wrist_pitch_joint": 1.182285, + "right_wrist_yaw_joint": -0.022848, + # dex3 hands (left) + "left_hand_index_0_joint": -60.0 * np.pi / 180.0, + "left_hand_middle_0_joint": -60.0 * np.pi / 180.0, + "left_hand_thumb_0_joint": 0.0, + "left_hand_index_1_joint": -40.0 * np.pi / 180.0, + "left_hand_middle_1_joint": -40.0 * np.pi / 180.0, + "left_hand_thumb_1_joint": 0.0, + "left_hand_thumb_2_joint": 0.0, + # dexterous hand joint - right hand + "right_hand_index_0_joint": 60.0 * np.pi / 180.0, + "right_hand_middle_0_joint": 60.0 * np.pi / 180.0, + "right_hand_thumb_0_joint": 0.0, + "right_hand_index_1_joint": 40.0 * np.pi / 180.0, + "right_hand_middle_1_joint": 40.0 * np.pi / 180.0, + "right_hand_thumb_1_joint": 0.0, + "right_hand_thumb_2_joint": 0.0, +} + + +def make_g1_29dof_dex3_cfg( + *, + prim_path: str = "/World/envs/env_.*/Robot", + init_pos: tuple[float, float, float] = (-0.15, 0.0, 0.744), + init_rot: tuple[float, float, float, float] = (0, 0, 0.7071, 0.7071), + custom_joint_pos: dict[str, float] | None = None, + base_config: ArticulationCfg = G129_CFG_WITH_DEX3_BASE_FIX, +) -> ArticulationCfg: + """Create the only supported robot articulation cfg for this task.""" + joint_pos = DEFAULT_JOINT_POS.copy() + if custom_joint_pos: + joint_pos.update(custom_joint_pos) + return base_config.replace( + prim_path=prim_path, + init_state=ArticulationCfg.InitialStateCfg( + pos=init_pos, + rot=init_rot, + joint_pos=joint_pos, + joint_vel={".*": 0.0}, + ), + ) + + +@configclass +class G1RobotPresets: + """G1 robot preset configuration collection""" + + @classmethod + def g1_29dof_dex3_base_fix( + cls, + init_pos: tuple[float, float, float] = (-0.15, 0.0, 0.76), + init_rot: tuple[float, float, float, float] = (0, 0, 0.7071, 0.7071), + ) -> ArticulationCfg: + """pick-place task configuration - dex3 hand""" + return make_g1_29dof_dex3_cfg(init_pos=init_pos, init_rot=init_rot) diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/assemble_trocar/g129_dex3_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/assemble_trocar/g129_dex3_env_cfg.py new file mode 100644 index 000000000000..50e58134f14c --- /dev/null +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/assemble_trocar/g129_dex3_env_cfg.py @@ -0,0 +1,444 @@ +# Copyright (c) 2022-2026, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md). +# All rights reserved. +# +# SPDX-License-Identifier: BSD-3-Clause + +from isaaclab_physx.physics import PhysxCfg + +import isaaclab.envs.mdp as base_mdp +import isaaclab.sim as sim_utils +from isaaclab.assets import ArticulationCfg, AssetBaseCfg, RigidObjectCfg +from isaaclab.envs import ManagerBasedRLEnvCfg, ViewerCfg +from isaaclab.managers import EventTermCfg, SceneEntityCfg +from isaaclab.managers import ObservationGroupCfg as ObsGroup +from isaaclab.managers import ObservationTermCfg as ObsTerm +from isaaclab.managers import RewardTermCfg as RewTerm +from isaaclab.managers import TerminationTermCfg as DoneTerm +from isaaclab.scene import InteractiveSceneCfg +from isaaclab.sim.spawners.from_files.from_files_cfg import UsdFileCfg +from isaaclab.utils import configclass + +from isaaclab_tasks.manager_based.manipulation.assemble_trocar import mdp + +from isaaclab_tasks.manager_based.manipulation.assemble_trocar.config import ( # isort: skip + CameraPresets, + G1RobotPresets, +) + +joint_names = [ + "left_hip_pitch_joint", + "right_hip_pitch_joint", + "left_hip_roll_joint", + "right_hip_roll_joint", + "left_hip_yaw_joint", + "right_hip_yaw_joint", + "left_knee_joint", + "right_knee_joint", + "left_ankle_pitch_joint", + "right_ankle_pitch_joint", + "left_ankle_roll_joint", + "right_ankle_roll_joint", + "waist_yaw_joint", + "waist_roll_joint", + "waist_pitch_joint", + "left_shoulder_pitch_joint", + "left_shoulder_roll_joint", + "left_shoulder_yaw_joint", + "left_elbow_joint", + "left_wrist_roll_joint", + "left_wrist_pitch_joint", + "left_wrist_yaw_joint", + "right_shoulder_pitch_joint", + "right_shoulder_roll_joint", + "right_shoulder_yaw_joint", + "right_elbow_joint", + "right_wrist_roll_joint", + "right_wrist_pitch_joint", + "right_wrist_yaw_joint", + "left_hand_thumb_0_joint", + "left_hand_thumb_1_joint", + "left_hand_thumb_2_joint", + "left_hand_middle_0_joint", + "left_hand_middle_1_joint", + "left_hand_index_0_joint", + "left_hand_index_1_joint", + "right_hand_thumb_0_joint", + "right_hand_thumb_1_joint", + "right_hand_thumb_2_joint", + "right_hand_middle_0_joint", + "right_hand_middle_1_joint", + "right_hand_index_0_joint", + "right_hand_index_1_joint", +] +offset_dict = { + "left_elbow_joint": -0.3, + "right_elbow_joint": -0.3, +} + +HEALTHCARE_S3 = "https://omniverse-content-production.s3-us-west-2.amazonaws.com/Assets/Isaac/Healthcare/0.5.0/132c82d" +USD_ROOT = f"{HEALTHCARE_S3}/Props/LightWheel" + + +@configclass +class AssembleTrocarSceneCfg(InteractiveSceneCfg): + """Scene configuration for the assemble_trocar task (robot + objects + lights).""" + + # humanoid robot configuration + robot: ArticulationCfg = G1RobotPresets.g1_29dof_dex3_base_fix( + init_pos=(-1.84919, 1.94, 0.81168), init_rot=(0.0, 0.0, 0.0, 1.0) + ) + # add camera configuration + front_camera = CameraPresets.g1_front_camera() + left_wrist_camera = CameraPresets.left_dex3_wrist_camera() + right_wrist_camera = CameraPresets.right_dex3_wrist_camera() + + scene = AssetBaseCfg( + prim_path="/World/envs/env_.*/Scene", + spawn=UsdFileCfg( + usd_path=f"{USD_ROOT}/scene03.usd", + ), + ) + + trocar_1 = RigidObjectCfg( + prim_path="/World/envs/env_.*/trocar_1", + spawn=UsdFileCfg( + usd_path=f"{USD_ROOT}/Assets/Trocar002/Trocar002-xform-wo.usd", + collision_props=sim_utils.CollisionPropertiesCfg( + collision_enabled=True, + contact_offset=0.001, + rest_offset=-0.001, + ), + ), + init_state=RigidObjectCfg.InitialStateCfg( + pos=[-1.60202, 1.91362, 0.87183], + rot=[-0.0, 0.70711, 0.70711, 0.0], + ), + ) + + trocar_2 = RigidObjectCfg( + prim_path="/World/envs/env_.*/trocar_2", + spawn=UsdFileCfg( + usd_path=( + f"{USD_ROOT}/Assets/" + "DisposableLaparoscopicPunctureDevice001/" + "DisposableLaparoscopicPunctureDevice005-xform.usd" + ), + rigid_props=sim_utils.RigidBodyPropertiesCfg( + rigid_body_enabled=True, + disable_gravity=False, + ), + ), + init_state=RigidObjectCfg.InitialStateCfg( + rot=[-0.71475, -0.000243, 0.05853, 0.69692], pos=[-1.50635, 1.90997, 0.8631] + ), + ) + tray = ArticulationCfg( + prim_path="/World/envs/env_.*/surgical_tray", + spawn=UsdFileCfg( + usd_path=f"{USD_ROOT}/Assets/SurgicalTray001/SurgicalTray001.usd", + ), + init_state=ArticulationCfg.InitialStateCfg(pos=[-1.54919, 2.03365, 0.84554], rot=[0.0, 0.0, -0.70711, 0.70711]), + actuators={}, # Empty dict for passive articulation (no motors) + ) + + # Lights + light = AssetBaseCfg( + prim_path="/World/light", + spawn=sim_utils.DomeLightCfg( + color=(0.75, 0.75, 0.75), + intensity=1000.0, + ), + ) + + +## +# MDP settings +## +@configclass +class ActionsCfg: + """defines the action configuration related to robot control, using direct joint angle control""" + + joint_pos = mdp.JointPositionActionCfg( + asset_name="robot", + joint_names=joint_names, + scale=1.0, + use_default_offset=False, + offset=offset_dict, + preserve_order=True, + ) + + +@configclass +class ObservationsCfg: + """defines all available observation information""" + + @configclass + class PolicyCfg(ObsGroup): + """policy group observation configuration class + defines all state observation values for policy decision + inherit from ObsGroup base class + """ + + # robot joint state observation + robot_joint_state = ObsTerm(func=mdp.get_robot_body_joint_states) + # dex3 hand joint state observation + robot_dex3_joint_state = ObsTerm(func=mdp.get_robot_dex3_joint_states) + + def __post_init__(self): + """post initialization function + set the basic attributes of the observation group + """ + self.enable_corruption = False # disable observation value corruption + self.concatenate_terms = False # disable observation item connection + + @configclass + class CameraImagesCfg(ObsGroup): + """Observations from the robot's cameras.""" + + front_camera = ObsTerm( + func=base_mdp.image, + params={"sensor_cfg": SceneEntityCfg("front_camera"), "data_type": "rgb", "normalize": False}, + ) + left_wrist_camera = ObsTerm( + func=base_mdp.image, + params={"sensor_cfg": SceneEntityCfg("left_wrist_camera"), "data_type": "rgb", "normalize": False}, + ) + right_wrist_camera = ObsTerm( + func=base_mdp.image, + params={"sensor_cfg": SceneEntityCfg("right_wrist_camera"), "data_type": "rgb", "normalize": False}, + ) + + def __post_init__(self): + self.concatenate_terms = False + + # observation groups + # create policy observation group instance + policy: PolicyCfg = PolicyCfg() + camera_images: CameraImagesCfg = CameraImagesCfg() + + +@configclass +class TerminationsCfg: + """Termination conditions for the environment.""" + + # Time out termination + time_out = DoneTerm(func=mdp.time_out, time_out=True) + + # Task success termination (all stages completed) + task_success = DoneTerm( + func=mdp.task_success_termination, + time_out=False, # This is a success termination, not a failure + params={ + "print_log": False, + "success_stage": 4, + }, + ) + object_drop = DoneTerm( + func=mdp.object_drop_termination, + time_out=True, # Treat as timeout/failure + params={ + "drop_height_threshold": 0.5, # Objects below this Z height are considered dropped + "asset_cfg1": SceneEntityCfg("trocar_1"), + "asset_cfg2": SceneEntityCfg("trocar_2"), + }, + ) + + +@configclass +class RewardsCfg: + """Reward configuration for sparse reward mode. + + Each stage gives 1.0 reward on completion -> Total reward for full task = 4.0 + This ensures clear reward signal for each stage transition. + + ``update_stage`` runs first (weight=0) to advance the task stage before any + reward term reads it, removing implicit ordering dependencies. + """ + + # Stage machine — weight=0, runs before all reward terms to update task stage + update_stage = RewTerm( + func=mdp.update_task_stage, + weight=0.0, + params={ + "asset_cfg1": SceneEntityCfg("trocar_1"), + "asset_cfg2": SceneEntityCfg("trocar_2"), + "table_height": 0.85483, + "lift_threshold": 0.15, + "tip_align_threshold": 0.015, + "insertion_dist_threshold": 0.05, + "insertion_angle_threshold": 0.15, + "placement_x_min": -1.8, + "placement_x_max": -1.4, + "placement_y_min": 1.5, + "placement_y_max": 1.8, + "print_log": False, + }, + ) + + # Stage 0: Lift trocars + lift_trocars = RewTerm( + func=mdp.lift_trocars_reward, + weight=1.0, + params={ + "table_height": 0.85483, + "lift_threshold": 0.15, + "asset_cfg1": SceneEntityCfg("trocar_1"), + "asset_cfg2": SceneEntityCfg("trocar_2"), + "use_sparse_reward": True, + "print_log": False, + }, + ) + + # Stage 1: Tip alignment (find hole) + tip_alignment = RewTerm( + func=mdp.trocar_tip_alignment_reward, + weight=1.0, # Give 1.0 reward when stage 1->2 completes + params={ + "tip_dist_std": 0.02, # Std for tip distance reward shaping + "asset_cfg1": SceneEntityCfg("trocar_1"), + "asset_cfg2": SceneEntityCfg("trocar_2"), + "use_sparse_reward": True, + "print_log": False, + }, + ) + + # Stage 2: Insertion (push in) + insert_trocars = RewTerm( + func=mdp.trocar_insertion_reward, + weight=1.0, # Give 1.0 reward when stage 2->3 completes + params={ + "angle_std": 0.2, # Std for angle alignment reward + "angle_threshold": 0.10, # ~5.7 degrees tolerance for parallelism + "center_dist_std": 0.05, # Std for center distance reward + "asset_cfg1": SceneEntityCfg("trocar_1"), + "asset_cfg2": SceneEntityCfg("trocar_2"), + "use_sparse_reward": True, + "print_log": False, + }, + ) + + # Stage 3: Placement (place in tray) + placement_trocars = RewTerm( + func=mdp.trocar_placement_reward, + weight=1.0, # Give 1.0 reward when stage 3->4 completes + params={ + "x_min": -1.8, + "x_max": -1.4, + "y_min": 1.5, + "y_max": 1.8, + "asset_cfg1": SceneEntityCfg("trocar_1"), + "asset_cfg2": SceneEntityCfg("trocar_2"), + "use_sparse_reward": True, + "print_log": False, + }, + ) + + +@configclass +class EventCfg: + """Event configuration for scene reset.""" + + # Reset scene when episode terminates (timeout or success) + reset_scene = EventTermCfg(func=base_mdp.reset_scene_to_default, mode="reset") + + # Reset task stage tracker when environment resets + reset_task_stage = EventTermCfg(func=mdp.reset_task_stage, mode="reset") + + # Random rotation for tray and trocars + reset_tray_random_rotation = EventTermCfg( + func=mdp.reset_tray_with_random_rotation, + mode="reset", + params={ + "tray_cfg": SceneEntityCfg("tray"), + "trocar_1_cfg": SceneEntityCfg("trocar_1"), + "trocar_2_cfg": SceneEntityCfg("trocar_2"), + "rotation_range": [0, 10], + }, + ) + + +@configclass +class G1AssembleTrocarEnvCfg(ManagerBasedRLEnvCfg): + """Unitree G1 robot assemble trocar environment configuration class + inherits from ManagerBasedRLEnvCfg, defines all configuration parameters for the entire environment + """ + + # scene settings + scene: AssembleTrocarSceneCfg = AssembleTrocarSceneCfg( + num_envs=1, + env_spacing=6.0, + replicate_physics=True, + ) + # viewer settings + viewer: ViewerCfg = ViewerCfg( + eye=(-0.5, 2.4, 1.6), + lookat=(-5.4, 0.2, -1.2), + cam_prim_path="/OmniverseKit_Persp", + ) + # basic settings + observations: ObservationsCfg = ObservationsCfg() + actions: ActionsCfg = ActionsCfg() + # MDP settings + terminations: TerminationsCfg = TerminationsCfg() + events: EventCfg = EventCfg() + commands = None + rewards: RewardsCfg = RewardsCfg() + curriculum = None + + num_rerenders_on_reset: int = 1 + + def __post_init__(self): + """Post initialization.""" + # general settings + self.decimation = 4 + self.episode_length_s = 20.0 + # simulation settings + self.sim.dt = 1 / 200 + self.sim.render_interval = self.decimation + self.sim.physics = PhysxCfg(bounce_threshold_velocity=0.01) + self.sim.render.enable_translucency = True + self.sim.render.carb_settings = { + "rtx.raytracing.fractionalCutoutOpacity": True, + } + self.sim.render.rendering_mode = "quality" + self.sim.render.antialiasing_mode = "DLAA" + + +@configclass +class EventCfgFixTrayRotation(EventCfg): + """Event configuration with a deterministic-but-different yaw per env index. + + This is useful for eval with many parallel envs: + - env 0..N-1 get different yaw angles, + - for a fixed global seed, the set of N angles is reproducible across runs/resets. + + Notes: + - Determinism is tied to torch's global seed (set by env reset seed in IsaacLab). + - Angle unit is degrees. + """ + + reset_tray_random_rotation = EventTermCfg( + func=mdp.reset_tray_with_random_rotation, + mode="reset", + params={ + "tray_cfg": SceneEntityCfg("tray"), + "trocar_1_cfg": SceneEntityCfg("trocar_1"), + "trocar_2_cfg": SceneEntityCfg("trocar_2"), + "rotation_range": [0, 10], + "deterministic_per_env": True, + # Use torch.initial_seed() by default to follow the env reset seed. + "deterministic_seed": None, + }, + ) + + +@configclass +class G1AssembleTrocarEvalEnvCfg(G1AssembleTrocarEnvCfg): + """Eval-friendly env cfg. + + This is currently an alias of `G1AssembleTrocarEnvCfg`, but registered under a + separate Gym id for compatibility with RLinf configs. + """ + + # Override events to enforce deterministic per-env tray yaw on every reset. + events: EventCfgFixTrayRotation = EventCfgFixTrayRotation() diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/assemble_trocar/mdp/__init__.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/assemble_trocar/mdp/__init__.py new file mode 100644 index 000000000000..d428ed46f7b4 --- /dev/null +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/assemble_trocar/mdp/__init__.py @@ -0,0 +1,10 @@ +# Copyright (c) 2022-2026, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md). +# All rights reserved. +# +# SPDX-License-Identifier: BSD-3-Clause + +"""MDP utilities for the assemble_trocar task.""" + +from isaaclab.utils.module import lazy_export + +lazy_export() diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/assemble_trocar/mdp/events.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/assemble_trocar/mdp/events.py new file mode 100644 index 000000000000..92214471ac09 --- /dev/null +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/assemble_trocar/mdp/events.py @@ -0,0 +1,253 @@ +# Copyright (c) 2022-2026, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md). +# All rights reserved. +# +# SPDX-License-Identifier: BSD-3-Clause + +"""Custom event functions for pick place surgical environment.""" + +from __future__ import annotations + +import logging +import math +from typing import TYPE_CHECKING + +import torch + +from isaaclab.managers import SceneEntityCfg +from isaaclab.utils.math import quat_apply, quat_mul + +if TYPE_CHECKING: + from isaaclab.envs import ManagerBasedRLEnv + +logger = logging.getLogger(__name__) + +__all__ = [ + "reset_tray_with_random_rotation", + "reset_robot_to_default_joint_positions", + "reset_task_stage", +] + + +def reset_task_stage( + env: ManagerBasedRLEnv, + env_ids: torch.Tensor, + print_log: bool = False, +) -> None: + """Reset task stage to 0 for specified environments. + + This should be called during environment reset events. + Also resets all locked reward caches to maintain continuity. + + Args: + env: The environment instance + env_ids: Indices of environments to reset + print_log: If True, log debug information. + """ + from .rewards import get_assemble_trocar_state + + s = get_assemble_trocar_state(env) + s.task_stage[env_ids] = 0 + + # Reset dense-reward locked caches + s.lift_reward_locked[env_ids] = 0 + s.tip_reward_locked[env_ids] = 0 + s.insertion_reward_locked[env_ids] = 0 + s.placement_reward_locked[env_ids] = 0 + + # Reset sparse-reward previous-stage trackers + s.prev_stage_lift[env_ids] = 0 + s.prev_stage_tip[env_ids] = 0 + s.prev_stage_insert[env_ids] = 0 + s.prev_stage_place[env_ids] = 0 + + # Reset debug throttle + s.last_debug_print_step = -1 + + if print_log: + logger.debug("Reset task stage for %d environment(s)", len(env_ids)) + + +def reset_tray_with_random_rotation( + env: ManagerBasedRLEnv, + env_ids: torch.Tensor, + tray_cfg: SceneEntityCfg, + trocar_1_cfg: SceneEntityCfg, + trocar_2_cfg: SceneEntityCfg, + rotation_range: tuple[float, float] | float = (-5.0, 5.0), # (min, max) degrees or ±value + deterministic_per_env: bool = False, + deterministic_seed: int | None = None, +): + """Reset tray with random rotation while keeping relative positions of trocars. + + This function: + 1. Applies a random yaw rotation within rotation_range to the tray + 2. Rotates trocar_1 and trocar_2 around the tray center to maintain relative positions + 3. Uses separate pose/velocity writes to ensure instant teleportation (no interpolation) + + Args: + env: The environment instance. + env_ids: The environment indices to reset. + tray_cfg: Scene entity config for the tray. + trocar_1_cfg: Scene entity config for trocar_1. + trocar_2_cfg: Scene entity config for trocar_2. + rotation_range: Rotation angle range in degrees. Can be: + - tuple (min, max): Random rotation between min and max degrees + - float value: Random rotation between -value and +value degrees + Examples: (0, 10), (-5, 15), 5.0 (equivalent to (-5, 5)) + """ + if len(env_ids) == 0: + return + + # Parse rotation_range parameter + if isinstance(rotation_range, (tuple, list)): + # User provided (min, max) range + min_angle_deg, max_angle_deg = rotation_range[0], rotation_range[1] + else: + # User provided single value (symmetric range ±value) + min_angle_deg, max_angle_deg = -rotation_range, rotation_range + + # Get assets + tray = env.scene[tray_cfg.name] + trocar_1 = env.scene[trocar_1_cfg.name] + trocar_2 = env.scene[trocar_2_cfg.name] + + # Get default poses and velocities (local coordinates relative to env origin) + tray_default_pose = tray.data.default_root_pose.torch[env_ids].clone() + trocar_1_default_pose = trocar_1.data.default_root_pose.torch[env_ids].clone() + trocar_2_default_pose = trocar_2.data.default_root_pose.torch[env_ids].clone() + + env_origins = env.scene.env_origins[env_ids] # (num_envs, 3) + + # Convert local coordinate to world coordinate + tray_default_pose[:, :3] += env_origins + trocar_1_default_pose[:, :3] += env_origins + trocar_2_default_pose[:, :3] += env_origins + + # Tray center position (pivot point for rotation) - now in world coordinates + tray_center = tray_default_pose[:, :3] # (num_envs, 3) + + # Generate yaw angles (in radians) + # Convert degrees to radians + min_angle_rad = min_angle_deg * math.pi / 180.0 + max_angle_rad = max_angle_deg * math.pi / 180.0 + + # Generate angles uniformly distributed in [min_angle, max_angle] + if deterministic_per_env: + # Derive a stable "random" number per env id, so each env gets a distinct yaw, + # but it is repeatable across resets/runs given the same seed + env_id. + # + # If deterministic_seed is not provided, we tie it to torch's global seed. + # IsaacLab typically seeds torch during env reset with the provided seed. + if deterministic_seed is None: + deterministic_seed = int(torch.initial_seed()) + u = _deterministic_uniform_0_1_from_ids(env, env_ids, deterministic_seed) # (num_envs,) + else: + u = torch.rand(len(env_ids), device=env.device) + random_yaw = u * (max_angle_rad - min_angle_rad) + min_angle_rad # (num_envs,) + + # Create rotation quaternion for yaw (rotation around Z-axis) + # XYZW: quat = [x, y, z, w] = [0, 0, sin(θ/2), cos(θ/2)] + half_angle = random_yaw / 2.0 + delta_quat = torch.zeros(len(env_ids), 4, device=env.device) + delta_quat[:, 2] = torch.sin(half_angle) # z + delta_quat[:, 3] = torch.cos(half_angle) # w + + # Apply rotation to tray quaternion + tray_new_quat = quat_mul(delta_quat, tray_default_pose[:, 3:7]) + + # Update tray pose + tray_new_pose = tray_default_pose.clone() + tray_new_pose[:, 3:7] = tray_new_quat + + # Rotate trocar positions around tray center + trocar_1_relative_pos = trocar_1_default_pose[:, :3] - tray_center + trocar_2_relative_pos = trocar_2_default_pose[:, :3] - tray_center + + # Rotate relative positions using the delta quaternion + trocar_1_new_relative_pos = quat_apply(delta_quat, trocar_1_relative_pos) + trocar_2_new_relative_pos = quat_apply(delta_quat, trocar_2_relative_pos) + + # New absolute poses + trocar_1_new_pose = trocar_1_default_pose.clone() + trocar_2_new_pose = trocar_2_default_pose.clone() + + trocar_1_new_pose[:, :3] = tray_center + trocar_1_new_relative_pos + trocar_2_new_pose[:, :3] = tray_center + trocar_2_new_relative_pos + + # Also rotate trocar orientations + trocar_1_new_pose[:, 3:7] = quat_mul(delta_quat, trocar_1_default_pose[:, 3:7]) + trocar_2_new_pose[:, 3:7] = quat_mul(delta_quat, trocar_2_default_pose[:, 3:7]) + + zero_velocity = torch.zeros(len(env_ids), 6, device=env.device) # [lin_vel(3), ang_vel(3)] + + tray.write_root_pose_to_sim_index(root_pose=tray_new_pose, env_ids=env_ids) + trocar_1.write_root_pose_to_sim_index(root_pose=trocar_1_new_pose, env_ids=env_ids) + trocar_2.write_root_pose_to_sim_index(root_pose=trocar_2_new_pose, env_ids=env_ids) + + tray.write_root_velocity_to_sim_index(root_velocity=zero_velocity, env_ids=env_ids) + trocar_1.write_root_velocity_to_sim_index(root_velocity=zero_velocity, env_ids=env_ids) + trocar_2.write_root_velocity_to_sim_index(root_velocity=zero_velocity, env_ids=env_ids) + + +def _deterministic_uniform_0_1_from_ids( + env: ManagerBasedRLEnv, + ids: torch.Tensor, + seed: int, +) -> torch.Tensor: + """Deterministically map env ids -> floats in [0, 1) via a seeded lookup table. + + We generate a length-(env.num_envs) random table with a local torch.Generator + seeded by `seed`, then return table[ids]. This is deterministic and avoids + uint64 bitwise ops (which may not be supported on CPU). + """ + device = env.device + num_envs = int(env.num_envs) + seed = int(seed) + + cache = getattr(env, "_deterministic_u_table_cache", None) + cache_key = (seed, num_envs, str(device)) + if cache is None or cache.get("key") != cache_key: + gen = torch.Generator(device=device) + gen.manual_seed(seed & 0xFFFFFFFFFFFFFFFF) + u_table = torch.rand((num_envs,), generator=gen, device=device, dtype=torch.float32) + cache = {"key": cache_key, "u_table": u_table} + setattr(env, "_deterministic_u_table_cache", cache) + + return cache["u_table"][ids] + + +def reset_robot_to_default_joint_positions( + env: ManagerBasedRLEnv, + env_ids: torch.Tensor, + robot_cfg: SceneEntityCfg, +): + """Reset robot joint positions directly to default values. + + This function directly writes joint positions and velocities to the simulation, + bypassing the PD controller. This prevents the "drive to target" behavior + that causes arms to swing from 0 position to the target position. + + Args: + env: The environment instance. + env_ids: The environment indices to reset. + robot_cfg: Scene entity config for the robot. + """ + if len(env_ids) == 0: + return + + # Get robot asset + robot = env.scene[robot_cfg.name] + + # Get default joint positions and velocities + default_joint_pos = robot.data.default_joint_pos.torch[env_ids].clone() + default_joint_vel = robot.data.default_joint_vel.torch[env_ids].clone() + + # Directly write joint state to simulation (bypasses PD controller) + robot.write_joint_position_to_sim_index(position=default_joint_pos, env_ids=env_ids) + robot.write_joint_velocity_to_sim_index(velocity=default_joint_vel, env_ids=env_ids) + + # Also reset root pose and velocity + default_root_pose = robot.data.default_root_pose.torch[env_ids].clone() + default_root_vel = robot.data.default_root_vel.torch[env_ids].clone() + robot.write_root_pose_to_sim_index(root_pose=default_root_pose, env_ids=env_ids) + robot.write_root_velocity_to_sim_index(root_velocity=default_root_vel, env_ids=env_ids) diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/assemble_trocar/mdp/observations.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/assemble_trocar/mdp/observations.py new file mode 100644 index 000000000000..06c037ba3d68 --- /dev/null +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/assemble_trocar/mdp/observations.py @@ -0,0 +1,119 @@ +# Copyright (c) 2022-2026, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md). +# All rights reserved. +# +# SPDX-License-Identifier: BSD-3-Clause + +""" +G1 29DOF (body) + Dex3 joint state helpers for the assemble_trocar task. + +Notes: +- DDS has been removed (simulation-only observations). +- These functions are designed to be used as Isaac Lab observation terms. +""" + +from __future__ import annotations + +from typing import TYPE_CHECKING + +import torch + +from isaaclab_tasks.manager_based.manipulation.assemble_trocar.config import ( + G1_29DOF_BODY_JOINT_INDICES, + G1_DEX3_JOINT_INDICES, +) + +if TYPE_CHECKING: + from isaaclab.envs import ManagerBasedRLEnv + + +# Observation cache: index tensors + preallocated output buffers (body joints) +_body_obs_cache = { + "device": None, + "batch": None, + "idx_t": None, + "idx_batch": None, + "pos_buf": None, + "vel_buf": None, + "torque_buf": None, + "combined_buf": None, +} + + +def get_robot_body_joint_states(env: ManagerBasedRLEnv) -> torch.Tensor: + """Return body joint states as a single tensor: [pos(29) | vel(29) | torque(29)].""" + robot_data = env.scene["robot"].data + joint_pos = robot_data.joint_pos.torch + joint_vel = robot_data.joint_vel.torch + joint_torque = robot_data.applied_torque.torch + device = joint_pos.device + batch = joint_pos.shape[0] + + global _body_obs_cache + if _body_obs_cache["device"] != device or _body_obs_cache["idx_t"] is None: + _body_obs_cache["idx_t"] = torch.tensor(G1_29DOF_BODY_JOINT_INDICES, dtype=torch.long, device=device) + _body_obs_cache["device"] = device + _body_obs_cache["batch"] = None + + idx_t = _body_obs_cache["idx_t"] + n = idx_t.numel() + + if _body_obs_cache["batch"] != batch or _body_obs_cache["idx_batch"] is None: + _body_obs_cache["idx_batch"] = idx_t.unsqueeze(0).expand(batch, n) + _body_obs_cache["pos_buf"] = torch.empty(batch, n, device=device, dtype=joint_pos.dtype) + _body_obs_cache["vel_buf"] = torch.empty(batch, n, device=device, dtype=joint_pos.dtype) + _body_obs_cache["torque_buf"] = torch.empty(batch, n, device=device, dtype=joint_pos.dtype) + _body_obs_cache["combined_buf"] = torch.empty(batch, n * 3, device=device, dtype=joint_pos.dtype) + _body_obs_cache["batch"] = batch + + idx_batch = _body_obs_cache["idx_batch"] + pos_buf = _body_obs_cache["pos_buf"] + vel_buf = _body_obs_cache["vel_buf"] + torque_buf = _body_obs_cache["torque_buf"] + combined_buf = _body_obs_cache["combined_buf"] + + torch.gather(joint_pos, 1, idx_batch, out=pos_buf) + torch.gather(joint_vel, 1, idx_batch, out=vel_buf) + torch.gather(joint_torque, 1, idx_batch, out=torque_buf) + + combined_buf[:, 0:n].copy_(pos_buf) + combined_buf[:, n : 2 * n].copy_(vel_buf) + combined_buf[:, 2 * n : 3 * n].copy_(torque_buf) + return combined_buf + + +# Observation cache: index tensors + preallocated output buffers (Dex3 hand joints) +_dex3_obs_cache = { + "device": None, + "batch": None, + "idx_t": None, + "idx_batch": None, + "pos_buf": None, +} + + +def get_robot_dex3_joint_states(env: ManagerBasedRLEnv) -> torch.Tensor: + """Return Dex3 joint positions [batch, 14].""" + joint_pos = env.scene["robot"].data.joint_pos.torch + device = joint_pos.device + batch = joint_pos.shape[0] + + global _dex3_obs_cache + if _dex3_obs_cache["device"] != device or _dex3_obs_cache["idx_t"] is None: + _dex3_obs_cache["idx_t"] = torch.tensor(G1_DEX3_JOINT_INDICES, dtype=torch.long, device=device) + _dex3_obs_cache["device"] = device + _dex3_obs_cache["batch"] = None + + idx_t = _dex3_obs_cache["idx_t"] + n = idx_t.numel() + + if _dex3_obs_cache["batch"] != batch or _dex3_obs_cache["idx_batch"] is None: + _dex3_obs_cache["idx_batch"] = idx_t.unsqueeze(0).expand(batch, n) + _dex3_obs_cache["pos_buf"] = torch.empty(batch, n, device=device, dtype=joint_pos.dtype) + _dex3_obs_cache["batch"] = batch + + idx_batch = _dex3_obs_cache["idx_batch"] + pos_buf = _dex3_obs_cache["pos_buf"] + + torch.gather(joint_pos, 1, idx_batch, out=pos_buf) + + return pos_buf diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/assemble_trocar/mdp/rewards.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/assemble_trocar/mdp/rewards.py new file mode 100644 index 000000000000..504d9caba67d --- /dev/null +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/assemble_trocar/mdp/rewards.py @@ -0,0 +1,634 @@ +# Copyright (c) 2022-2026, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md). +# All rights reserved. +# +# SPDX-License-Identifier: BSD-3-Clause + +from __future__ import annotations + +import logging +from dataclasses import dataclass, field +from typing import TYPE_CHECKING + +import torch + +from isaaclab.assets import RigidObject +from isaaclab.managers import SceneEntityCfg +from isaaclab.utils.math import quat_apply + +if TYPE_CHECKING: + from isaaclab.envs import ManagerBasedRLEnv + +logger = logging.getLogger(__name__) + +__all__ = [ + "AssembleTrocarState", + "update_task_stage", + "lift_trocars_reward", + "trocar_tip_alignment_reward", + "trocar_insertion_reward", + "trocar_placement_reward", +] + + +@dataclass +class AssembleTrocarState: + """Namespaced task state for the assemble-trocar environment. + + Holds per-env stage tracking, reward caches, and debug bookkeeping. + Attached to the env as ``env.assemble_trocar_state`` and initialised + lazily on first access via :func:`get_assemble_trocar_state`. + + Stage semantics: + 0 - Initial (need to lift) + 1 - Lifted (need to find hole / tip alignment) + 2 - Hole found (need to insert / push in) + 3 - Inserted (need to place) + 4 - Placed (task complete) + """ + + task_stage: torch.Tensor = field(default_factory=lambda: torch.empty(0)) + # Sparse-reward previous-stage trackers (one per reward term) + prev_stage_lift: torch.Tensor = field(default_factory=lambda: torch.empty(0)) + prev_stage_tip: torch.Tensor = field(default_factory=lambda: torch.empty(0)) + prev_stage_insert: torch.Tensor = field(default_factory=lambda: torch.empty(0)) + prev_stage_place: torch.Tensor = field(default_factory=lambda: torch.empty(0)) + # Dense-reward locked caches + lift_reward_locked: torch.Tensor = field(default_factory=lambda: torch.empty(0)) + tip_reward_locked: torch.Tensor = field(default_factory=lambda: torch.empty(0)) + insertion_reward_locked: torch.Tensor = field(default_factory=lambda: torch.empty(0)) + placement_reward_locked: torch.Tensor = field(default_factory=lambda: torch.empty(0)) + # Cached tip offsets (populated on first call to get_trocar_tip_position) + tip_offset_trocar_1: torch.Tensor | None = None + tip_offset_trocar_2: torch.Tensor | None = None + # Debug throttle + last_debug_print_step: int = -1 + + +def get_assemble_trocar_state(env: ManagerBasedRLEnv) -> AssembleTrocarState: + """Get or lazily initialise the :class:`AssembleTrocarState` on *env*.""" + if not hasattr(env, "assemble_trocar_state"): + s = AssembleTrocarState( + task_stage=torch.zeros(env.num_envs, dtype=torch.long, device=env.device), + prev_stage_lift=torch.zeros(env.num_envs, dtype=torch.long, device=env.device), + prev_stage_tip=torch.zeros(env.num_envs, dtype=torch.long, device=env.device), + prev_stage_insert=torch.zeros(env.num_envs, dtype=torch.long, device=env.device), + prev_stage_place=torch.zeros(env.num_envs, dtype=torch.long, device=env.device), + lift_reward_locked=torch.zeros(env.num_envs, device=env.device), + tip_reward_locked=torch.zeros(env.num_envs, device=env.device), + insertion_reward_locked=torch.zeros(env.num_envs, device=env.device), + placement_reward_locked=torch.zeros(env.num_envs, device=env.device), + ) + env.assemble_trocar_state = s + return env.assemble_trocar_state + + +def get_task_stage(env: ManagerBasedRLEnv) -> torch.Tensor: + """Return the current per-env task stage tensor.""" + return get_assemble_trocar_state(env).task_stage + + +def should_print_debug(env: ManagerBasedRLEnv, print_interval: int = 50, print_log: bool = True) -> bool: + """Check if debug info should be logged based on episode step counter.""" + if not print_log: + return False + if not hasattr(env, "episode_length_buf"): + return False + + current_step = env.episode_length_buf[0].item() + if current_step == 0 or current_step % print_interval != 0: + return False + + state = get_assemble_trocar_state(env) + if state.last_debug_print_step == current_step: + return False + + state.last_debug_print_step = current_step + return True + + +def update_task_stage( + env: ManagerBasedRLEnv, + asset_cfg1: SceneEntityCfg, + asset_cfg2: SceneEntityCfg, + table_height: float = 0.85483, + lift_threshold: float = 0.05, + tip_align_threshold: float = 0.015, + insertion_dist_threshold: float = 0.03, + insertion_angle_threshold: float = 0.15, + placement_x_min: float = -1.8, + placement_x_max: float = -1.4, + placement_y_min: float = 1.5, + placement_y_max: float = 1.8, + placement_z_min: float = 0.9, + print_log: bool = False, +) -> torch.Tensor: + """Update task stage based on current state. + + This function checks conditions and advances stages automatically. + Once a stage is completed, it never goes back. + Returns a zero-valued tensor (num_envs,) so it can be used as a + weight=0 reward term to run before the actual reward terms. + """ + state = get_assemble_trocar_state(env) + stage = state.task_stage + + obj1: RigidObject = env.scene[asset_cfg1.name] + obj2: RigidObject = env.scene[asset_cfg2.name] + + pos1 = obj1.data.root_pos_w.torch + pos2 = obj2.data.root_pos_w.torch + quat1 = obj1.data.root_quat_w.torch + quat2 = obj2.data.root_quat_w.torch + # Store old stage to detect changes (BEFORE any stage transitions) + old_stage = stage.clone() + + # Stage 0 -> 1: Check if lifted + target_z = table_height + lift_threshold + is_lifted_1 = pos1[:, 2] > target_z + is_lifted_2 = pos2[:, 2] > target_z + both_lifted = is_lifted_1 & is_lifted_2 + stage = torch.where((stage == 0) & both_lifted, torch.ones_like(stage), stage) + + # Stage 1 -> 2: Check if tips are aligned (hole found) + # Get tip positions + tip_pos1 = get_trocar_tip_position(env, asset_cfg1) + tip_pos2 = get_trocar_tip_position(env, asset_cfg2) + tip_dist = torch.norm(tip_pos1 - tip_pos2, dim=-1) + + # Tip alignment success + tip_aligned = tip_dist < tip_align_threshold + stage = torch.where((stage == 1) & tip_aligned, torch.full_like(stage, 2), stage) + + # Stage 2 -> 3: Check if inserted (parallel + center close) + # Get center distance + center_dist = torch.norm(pos1 - pos2, dim=-1) + + # Check alignment + target_axis1 = torch.tensor([0.0, 0.0, -1.0], device=env.device).repeat(env.num_envs, 1) + target_axis2 = torch.tensor([0.0, 0.0, -1.0], device=env.device).repeat(env.num_envs, 1) + axis1 = quat_apply(quat1, target_axis1) + axis2 = quat_apply(quat2, target_axis2) + dot_prod = torch.sum(axis1 * axis2, dim=-1) + abs_dot = torch.clamp(torch.abs(dot_prod), max=1.0) + angle = torch.acos(abs_dot) + + # Insertion success: parallel + center close + is_parallel = angle < insertion_angle_threshold + center_close = center_dist < insertion_dist_threshold + is_inserted = is_parallel & center_close + + stage = torch.where((stage == 2) & is_inserted, torch.full_like(stage, 3), stage) + + # Stage 3 -> 4: Check if placed in target zone + # Get environment origins to handle multi-env spatial offsets + env_origins = env.scene.env_origins # shape: (num_envs, 3) + + # Adjust target zone relative to each environment's origin + curr_x_min = env_origins[:, 0] + min(placement_x_min, placement_x_max) # (num_envs,) + curr_x_max = env_origins[:, 0] + max(placement_x_min, placement_x_max) + curr_y_min = env_origins[:, 1] + min(placement_y_min, placement_y_max) + curr_y_max = env_origins[:, 1] + max(placement_y_min, placement_y_max) + + in_zone_1 = ( + (pos1[:, 0] >= curr_x_min) + & (pos1[:, 0] <= curr_x_max) + & (pos1[:, 1] >= curr_y_min) + & (pos1[:, 1] <= curr_y_max) + & (pos1[:, 2] < placement_z_min) + ) + in_zone_2 = ( + (pos2[:, 0] >= curr_x_min) + & (pos2[:, 0] <= curr_x_max) + & (pos2[:, 1] >= curr_y_min) + & (pos2[:, 1] <= curr_y_max) + & (pos2[:, 2] < placement_z_min) + ) + both_in_zone = in_zone_1 & in_zone_2 + stage = torch.where((stage == 3) & both_in_zone, torch.full_like(stage, 4), stage) + + # Print stage transitions (AFTER all stage transitions - always print when stage changes) + if print_log and (stage != old_stage).any(): + for env_id in range(env.num_envs): + if stage[env_id] != old_stage[env_id]: + logger.debug("Env %d: Stage %d → %d", env_id, old_stage[env_id].item(), stage[env_id].item()) + + state.task_stage = stage + return torch.zeros(env.num_envs, device=env.device) + + +def lift_trocars_reward( + env: ManagerBasedRLEnv, + table_height: float = 0.85483, + lift_threshold: float = 0.05, + asset_cfg1: SceneEntityCfg = SceneEntityCfg("trocar_1"), + asset_cfg2: SceneEntityCfg = SceneEntityCfg("trocar_2"), + use_sparse_reward: bool = True, + print_log: bool = False, +) -> torch.Tensor: + """Reward for lifting both trocars above the table. + + Only active in Stage 0. Once completed, this reward is locked at the achieved value. + + Args: + use_sparse_reward: If True, only give reward (1.0) when stage transitions from 0->1. + If False, give continuous reward based on current state. + print_log: If True, log debug information. + """ + s = get_assemble_trocar_state(env) + stage = s.task_stage + + obj1: RigidObject = env.scene[asset_cfg1.name] + obj2: RigidObject = env.scene[asset_cfg2.name] + + pos1 = obj1.data.root_pos_w.torch + pos2 = obj2.data.root_pos_w.torch + target_z = table_height + lift_threshold + + is_lifted_1 = pos1[:, 2] > target_z + is_lifted_2 = pos2[:, 2] > target_z + both_lifted = is_lifted_1 & is_lifted_2 + + if use_sparse_reward: + stage_just_completed = (s.prev_stage_lift == 0) & (stage >= 1) + reward = torch.where( + stage_just_completed, + torch.ones(env.num_envs, device=env.device) / env.step_dt, + torch.zeros(env.num_envs, device=env.device), + ) + s.prev_stage_lift = stage.clone() + else: + current_reward = both_lifted.float() + s.lift_reward_locked = torch.where( + (stage >= 1) & (s.lift_reward_locked == 0), + current_reward, + s.lift_reward_locked, + ) + reward = torch.where(stage == 0, current_reward, s.lift_reward_locked) + + if should_print_debug(env, print_log=print_log): + mode_str = "Sparse" if use_sparse_reward else "Dense" + logger.debug( + " Stage: %d | Lift (%s): %.2f | z1: %.3f | z2: %.3f", + stage[0].item(), + mode_str, + reward[0].item(), + pos1[0, 2], + pos2[0, 2], + ) + + return reward + + +def get_trocar_tip_position( + env: ManagerBasedRLEnv, + asset_cfg: SceneEntityCfg = SceneEntityCfg("trocar_1"), +) -> torch.Tensor: + """Get trocar tip position (White_pos or Red_pos) in world coordinates. + + Calculates tip world position using trocar root's dynamic position and rotation, + plus the tip's relative offset. + + Args: + env: Environment instance + asset_cfg: Trocar asset configuration (trocar_1 or trocar_2) + + Returns: + torch.Tensor: Shape (num_envs, 3) - Position in world coordinates + """ + from pxr import Gf, Usd, UsdGeom + + import isaaclab.utils.math as math_utils + + # Cache the tip offset to avoid recalculating every step. + # The local offset from root to tip is a static geometric property of the USD + # asset and is identical across all replicated envs. We read it once from env_0's + # USD prim, then apply it per-env at runtime using each env's dynamic root pose. + s = get_assemble_trocar_state(env) + cache_attr = f"tip_offset_{asset_cfg.name}" + tip_offset_local = getattr(s, cache_attr, None) + + if tip_offset_local is None: + usd_stage = env.scene.stage + + if asset_cfg.name == "trocar_1": + tip_path = "/World/envs/env_0/trocar_1/Trocar002/White_pos" + root_path = "/World/envs/env_0/trocar_1" + elif asset_cfg.name == "trocar_2": + tip_path = "/World/envs/env_0/trocar_2/DisposableLaparoscopicPunctureDevice001/Red_pos" + root_path = "/World/envs/env_0/trocar_2" + else: + raise ValueError(f"Invalid asset configuration: {asset_cfg.name}") + + tip_prim = usd_stage.GetPrimAtPath(tip_path) + root_prim = usd_stage.GetPrimAtPath(root_path) + + if not tip_prim.IsValid(): + logger.warning("Tip prim not found at %s, using zero offset", tip_path) + tip_offset_local = torch.zeros(3, dtype=torch.float32, device=env.device) + else: + tip_xform = UsdGeom.Xformable(tip_prim) + root_xform = UsdGeom.Xformable(root_prim) + + tip_world_transform = tip_xform.ComputeLocalToWorldTransform(Usd.TimeCode.Default()) + root_world_transform = root_xform.ComputeLocalToWorldTransform(Usd.TimeCode.Default()) + + tip_world_pos = tip_world_transform.ExtractTranslation() + root_world_pos = root_world_transform.ExtractTranslation() + + root_rotation_mat = root_world_transform.ExtractRotationMatrix() + root_rotation_quat = root_rotation_mat.ExtractRotation().GetQuat() + + tip_offset_world = Gf.Vec3d( + tip_world_pos[0] - root_world_pos[0], + tip_world_pos[1] - root_world_pos[1], + tip_world_pos[2] - root_world_pos[2], + ) + + root_quat_inv = root_rotation_quat.GetInverse() + tip_offset_local_gf = root_quat_inv.Transform(tip_offset_world) + + tip_offset_local = torch.tensor( + [tip_offset_local_gf[0], tip_offset_local_gf[1], tip_offset_local_gf[2]], + dtype=torch.float32, + device=env.device, + ) + + logger.debug("Cached tip offset for %s: %s", asset_cfg.name, tip_offset_local) + + setattr(s, cache_attr, tip_offset_local) + + obj: RigidObject = env.scene[asset_cfg.name] + root_pos_w = obj.data.root_pos_w.torch # Shape: (num_envs, 3) + root_quat_w = obj.data.root_quat_w.torch # Shape: (num_envs, 4) XYZW + + tip_offset_local_batch = tip_offset_local.unsqueeze(0).repeat(env.num_envs, 1) + + tip_offset_world = math_utils.quat_apply(root_quat_w, tip_offset_local_batch) + tip_pos_world = root_pos_w + tip_offset_world + + return tip_pos_world # Shape: (num_envs, 3) + + +def trocar_tip_alignment_reward( + env: ManagerBasedRLEnv, + tip_dist_std: float = 0.02, # Std for tip distance reward + asset_cfg1: SceneEntityCfg = SceneEntityCfg("trocar_1"), + asset_cfg2: SceneEntityCfg = SceneEntityCfg("trocar_2"), + use_sparse_reward: bool = True, + print_log: bool = False, +) -> torch.Tensor: + """Reward for aligning trocar tips (Stage 1: Finding the hole). + + Reward based on tip distance - encourages bringing tips close together. + + Only active in Stage 1. Once completed (stage >= 2), this reward is locked at the achieved value. + + Args: + env: Environment instance + tip_dist_std: Standard deviation for tip distance reward shaping + asset_cfg1: Configuration for trocar 1 + asset_cfg2: Configuration for trocar 2 + use_sparse_reward: If True, only give reward (1.0) when stage >= 2. + If False, give continuous reward based on tip distance. + print_log: If True, print debug information. + + Returns: + torch.Tensor: Reward tensor (num_envs,) + """ + s = get_assemble_trocar_state(env) + stage = s.task_stage + + tip_pos1 = get_trocar_tip_position(env, asset_cfg1) + tip_pos2 = get_trocar_tip_position(env, asset_cfg2) + tip_dist = torch.norm(tip_pos1 - tip_pos2, dim=-1) + + if use_sparse_reward: + stage_just_completed = (s.prev_stage_tip == 1) & (stage >= 2) + reward = torch.where( + stage_just_completed, + torch.ones(env.num_envs, device=env.device) / env.step_dt, + torch.zeros(env.num_envs, device=env.device), + ) + s.prev_stage_tip = stage.clone() + else: + tip_reward = torch.exp(-torch.square(tip_dist) / (2 * tip_dist_std**2)) + s.tip_reward_locked = torch.where( + (stage >= 2) & (s.tip_reward_locked == 0), + tip_reward, + s.tip_reward_locked, + ) + reward = torch.where( + stage < 1, + torch.zeros(env.num_envs, device=env.device), + torch.where(stage == 1, tip_reward, s.tip_reward_locked), + ) + + # Debug info + if should_print_debug(env, print_log=print_log) and stage[0].item() == 1: + mode_str = "Sparse" if use_sparse_reward else "Dense" + logger.debug( + " Stage 1 (Find Hole, %s): tip_pos_1=(%.3f, %.3f, %.3f)" + " | tip_pos_2=(%.3f, %.3f, %.3f) | tip_d=%.4f | reward=%.3f", + mode_str, + tip_pos1[0, 0], + tip_pos1[0, 1], + tip_pos1[0, 2], + tip_pos2[0, 0], + tip_pos2[0, 1], + tip_pos2[0, 2], + tip_dist[0].item(), + reward[0].item(), + ) + + return reward + + +def trocar_insertion_reward( + env: ManagerBasedRLEnv, + angle_std: float = 0.2, # Std for angle alignment reward + angle_threshold: float = 0.15, # Tolerance for parallelism (radians) + center_dist_std: float = 0.05, # Std for center distance reward + asset_cfg1: SceneEntityCfg = SceneEntityCfg("trocar_1"), + asset_cfg2: SceneEntityCfg = SceneEntityCfg("trocar_2"), + use_sparse_reward: bool = True, + print_log: bool = False, +) -> torch.Tensor: + """Reward for inserting trocar_2 into trocar_1 (Stage 2: Pushing in). + + Reward based on: + 1. Orientation alignment (parallelism) + 2. Center distance (pushing in) + + Only active in Stage 2. Once completed (stage >= 3), this reward is locked at the achieved value. + + Args: + env: Environment instance + angle_std: Standard deviation for angle reward shaping + angle_threshold: Angle threshold for parallelism (radians) + center_dist_std: Standard deviation for center distance reward shaping + asset_cfg1: Configuration for trocar 1 + asset_cfg2: Configuration for trocar 2 + use_sparse_reward: If True, only give reward (1.0) when stage >= 3. + If False (default), give continuous reward based on alignment and distance. + print_log: If True, print debug information. + Returns: + torch.Tensor: Reward tensor (num_envs,) + """ + s = get_assemble_trocar_state(env) + stage = s.task_stage + + obj1: RigidObject = env.scene[asset_cfg1.name] + obj2: RigidObject = env.scene[asset_cfg2.name] + + pos1 = obj1.data.root_pos_w.torch + quat1 = obj1.data.root_quat_w.torch + pos2 = obj2.data.root_pos_w.torch + quat2 = obj2.data.root_quat_w.torch + center_dist = torch.norm(pos1 - pos2, dim=-1) + + target_axis1 = torch.tensor([0.0, 0.0, -1.0], device=env.device).repeat(env.num_envs, 1) + target_axis2 = torch.tensor([0.0, 0.0, -1.0], device=env.device).repeat(env.num_envs, 1) + + axis1 = quat_apply(quat1, target_axis1) + axis2 = quat_apply(quat2, target_axis2) + + dot_prod = torch.sum(axis1 * axis2, dim=-1) + abs_dot = torch.clamp(torch.abs(dot_prod), max=1.0) + angle = torch.acos(abs_dot) + is_parallel = angle < angle_threshold + + if use_sparse_reward: + stage_just_completed = (s.prev_stage_insert == 2) & (stage >= 3) + reward = torch.where( + stage_just_completed, + torch.ones(env.num_envs, device=env.device) / env.step_dt, + torch.zeros(env.num_envs, device=env.device), + ) + s.prev_stage_insert = stage.clone() + else: + excess_angle = torch.clamp(angle - angle_threshold, min=0.0) + align_reward = torch.exp(-torch.square(excess_angle) / (2 * angle_std**2)) + center_reward = torch.exp(-torch.square(center_dist) / (2 * center_dist_std**2)) + center_reward = torch.where(is_parallel, center_reward, torch.zeros_like(center_reward)) + insertion_reward = align_reward * center_reward + + s.insertion_reward_locked = torch.where( + (stage >= 3) & (s.insertion_reward_locked == 0), + insertion_reward, + s.insertion_reward_locked, + ) + reward = torch.where( + stage < 2, + torch.zeros(env.num_envs, device=env.device), + torch.where(stage == 2, insertion_reward, s.insertion_reward_locked), + ) + + # Debug info + if should_print_debug(env, print_log=print_log) and stage[0].item() == 2: + mode_str = "Sparse" if use_sparse_reward else "Dense" + logger.debug( + " Stage 2 (Push In, %s): angle=%.3f | center_d=%.4f | is_parallel=%s | reward=%.3f", + mode_str, + angle[0].item(), + center_dist[0].item(), + is_parallel[0].item(), + reward[0].item(), + ) + + return reward + + +def trocar_placement_reward( + env: ManagerBasedRLEnv, + x_min: float = -1.8, + x_max: float = -1.4, + y_min: float = 1.5, + y_max: float = 1.8, + z_min: float = 0.9, + asset_cfg1: SceneEntityCfg = SceneEntityCfg("trocar_1"), + asset_cfg2: SceneEntityCfg = SceneEntityCfg("trocar_2"), + use_sparse_reward: bool = True, + print_log: bool = False, +) -> torch.Tensor: + """Reward for placing both trocars in the target tray region (Stage 3). + + Only active in Stage 3. Once completed (stage >= 4), this reward is locked at the achieved value. + + Args: + env: Environment instance + x_min, x_max: X bounds of target zone (relative to env origin) + y_min, y_max: Y bounds of target zone (relative to env origin) + z_min: Z threshold (below this is considered placed) + asset_cfg1: Configuration for trocar 1 + asset_cfg2: Configuration for trocar 2 + use_sparse_reward: If True, only give reward (1.0) when stage >= 4. + If False (default), give continuous reward based on placement status. + print_log: If True, print debug information. + + Returns: + torch.Tensor: Reward tensor (num_envs,) + """ + s = get_assemble_trocar_state(env) + stage = s.task_stage + + obj1: RigidObject = env.scene[asset_cfg1.name] + obj2: RigidObject = env.scene[asset_cfg2.name] + + pos1 = obj1.data.root_pos_w.torch + pos2 = obj2.data.root_pos_w.torch + env_origins = env.scene.env_origins + + curr_x_min = env_origins[:, 0] + min(x_min, x_max) + curr_x_max = env_origins[:, 0] + max(x_min, x_max) + curr_y_min = env_origins[:, 1] + min(y_min, y_max) + curr_y_max = env_origins[:, 1] + max(y_min, y_max) + + in_zone_1 = ( + (pos1[:, 0] >= curr_x_min) + & (pos1[:, 0] <= curr_x_max) + & (pos1[:, 1] >= curr_y_min) + & (pos1[:, 1] <= curr_y_max) + & (pos1[:, 2] < z_min) + ) + in_zone_2 = ( + (pos2[:, 0] >= curr_x_min) + & (pos2[:, 0] <= curr_x_max) + & (pos2[:, 1] >= curr_y_min) + & (pos2[:, 1] <= curr_y_max) + & (pos2[:, 2] < z_min) + ) + both_in_zone = in_zone_1 & in_zone_2 + + if use_sparse_reward: + stage_just_completed = (s.prev_stage_place == 3) & (stage >= 4) + reward = torch.where( + stage_just_completed, + torch.ones(env.num_envs, device=env.device) / env.step_dt, + torch.zeros(env.num_envs, device=env.device), + ) + s.prev_stage_place = stage.clone() + else: + placement_reward = both_in_zone.float() + s.placement_reward_locked = torch.where( + (stage >= 4) & (s.placement_reward_locked == 0), + placement_reward, + s.placement_reward_locked, + ) + reward = torch.where( + stage < 3, + torch.zeros(env.num_envs, device=env.device), + torch.where(stage == 3, placement_reward, s.placement_reward_locked), + ) + + # Debug info + if should_print_debug(env, print_log=print_log) and stage[0].item() == 3: + mode_str = "Sparse" if use_sparse_reward else "Dense" + logger.debug( + " Stage 3 (Placement, %s): in_zone=%s | z1=%.3f | z2=%.3f", + mode_str, + both_in_zone[0].item(), + pos1[0, 2], + pos2[0, 2], + ) + + return reward diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/assemble_trocar/mdp/terminations.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/assemble_trocar/mdp/terminations.py new file mode 100644 index 000000000000..12b70ae473bd --- /dev/null +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/assemble_trocar/mdp/terminations.py @@ -0,0 +1,80 @@ +# Copyright (c) 2022-2026, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md). +# All rights reserved. +# +# SPDX-License-Identifier: BSD-3-Clause + +from __future__ import annotations + +import logging +from typing import TYPE_CHECKING + +import torch + +from isaaclab.assets import RigidObject +from isaaclab.managers import SceneEntityCfg + +from .rewards import get_task_stage + +if TYPE_CHECKING: + from isaaclab.envs import ManagerBasedRLEnv + +logger = logging.getLogger(__name__) + + +def object_drop_termination( + env: ManagerBasedRLEnv, + drop_height_threshold: float = 0.5, + asset_cfg1: SceneEntityCfg = SceneEntityCfg("trocar_1"), + asset_cfg2: SceneEntityCfg = SceneEntityCfg("trocar_2"), + print_log: bool = False, +) -> torch.Tensor: + """Termination function that triggers when objects drop below threshold. + + This can be used as an alternative to auto-reset, marking the episode as terminated + so the training framework handles the reset. + + Args: + env: The environment instance + drop_height_threshold: Height below which objects are considered dropped + asset_cfg1: Configuration for first trocar + asset_cfg2: Configuration for second trocar + print_log: If True, print debug information. + Returns: + Boolean tensor indicating which environments should terminate due to drops + """ + # Get rigid objects + obj1: RigidObject = env.scene[asset_cfg1.name] + obj2: RigidObject = env.scene[asset_cfg2.name] + + # Get positions + pos1 = obj1.data.root_pos_w.torch + pos2 = obj2.data.root_pos_w.torch + # Check if either object has dropped + dropped_1 = pos1[:, 2] < drop_height_threshold + dropped_2 = pos2[:, 2] < drop_height_threshold + + dropped = dropped_1 | dropped_2 + + if print_log and dropped.any(): + logger.debug("Drop termination triggered for %d environment(s)", dropped.sum().item()) + + return dropped + + +def task_success_termination( + env: ManagerBasedRLEnv, + success_stage: int = 4, + print_log: bool = False, +) -> torch.Tensor: + """Termination condition: task is complete when stage reaches 4. + + Returns: + torch.Tensor: Boolean tensor indicating which environments should terminate (num_envs,) + """ + stage = get_task_stage(env) + task_complete = stage >= success_stage + + if print_log and task_complete.any(): + logger.info("Task completed in %d environment(s)!", task_complete.sum().item()) + + return task_complete From d9bdc7f43270a1f91752d745afa875a27fecabfb Mon Sep 17 00:00:00 2001 From: vidurv-nvidia Date: Mon, 11 May 2026 20:01:55 -0700 Subject: [PATCH 40/51] Refactors the doc on Schema for Lab 3.0, and adds MuJoCo gravcomp (#5276) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit # Description Adds Newton-native and MuJoCo-specific schema cfg classes to `isaaclab_newton.sim.schemas`, following the base/subclass framework from #5275. All new cfgs use the per-declaring-class MRO routing in `_apply_namespaced_schemas` — no backend-specific branching in any writer. Depends on #5275. ## New cfgs ### MuJoCo (Newton MuJoCo kernel, `mjc:*` namespace) | Class | Field | USD attribute | Applied schema | |---|---|---|---| | `MujocoRigidBodyPropertiesCfg` | `gravcomp` | `mjc:gravcomp` | None (raw attr) | | `MujocoJointDrivePropertiesCfg` | `actuatorgravcomp` | `mjc:actuatorgravcomp` | `MjcJointAPI` | Body-level `gravcomp` must be set for joint-level `actuatorgravcomp` to have any effect. The spawner auto-enables `MujocoRigidBodyPropertiesCfg(gravcomp=1.0)` when joint-level actuator gravcomp is requested without body-level gravcomp. ### Newton-native (`newton:*` namespace) | Class | Fields | USD attributes | Applied schema | |---|---|---|---| | `NewtonCollisionPropertiesCfg` | `contact_margin`, `contact_gap` | `newton:contactMargin`, `newton:contactGap` | `NewtonCollisionAPI` | | `NewtonMeshCollisionPropertiesCfg` | `max_hull_vertices` | `newton:maxHullVertices` | `NewtonMeshCollisionAPI` | | `NewtonMaterialPropertiesCfg` | `torsional_friction`, `rolling_friction` | `newton:torsionalFriction`, `newton:rollingFriction` | `NewtonMaterialAPI` | | `NewtonArticulationRootPropertiesCfg` | `self_collision_enabled` | `newton:selfCollisionEnabled` | `NewtonArticulationRootAPI` | ## Design constraints Same single-cfg-per-spawner-slot rule as #5275. Newton cfgs subclass the same base classes as PhysX cfgs; each declares `_usd_namespace`/`_usd_applied_schema` (ClassVar) and fields that auto-camelCase to their USD attr names. Per-declaring-class MRO routing handles mixed PhysX+Newton cfg hierarchies correctly. ## Field renames (with deprecation aliases through 5.0) | Old | New | Reason | |---|---|---| | `gravity_compensation_scale` | `gravcomp` | Single word identity: `gravcomp` → `mjc:gravcomp` | | `gravity_compensation` | `actuatorgravcomp` | Single word identity: `actuatorgravcomp` → `mjc:actuatorgravcomp` | ## Type of change - New feature (non-breaking) Forwarding shims on `isaaclab.sim.schemas` keep existing imports working. Deprecation aliases keep old field names working through 5.0. ## Test plan - [x] MuJoCo tests: `mjc:gravcomp` / `mjc:actuatorgravcomp` written when set, not written when None - [x] Newton collision, material, articulation-root: attrs written, schemas applied only when non-None - [x] Deprecation alias tests for renamed fields - [x] `test_schemas.py` 46/46 pass — no regressions - [x] Pre-commit clean ## Supersedes Together with #5275, supersedes #4847 and #5203. --------- Co-authored-by: Kelly Guo Co-authored-by: Antoine RICHARD --- docs/source/api/index.rst | 2 + docs/source/api/lab/isaaclab.sim.schemas.rst | 94 ++++- .../isaaclab_newton.sim.schemas.rst | 88 ++++ .../lab_physx/isaaclab_physx.sim.schemas.rst | 117 +++++- .../migration/migrating_to_isaaclab_3-0.rst | 161 +++++++ docs/source/overview/core-concepts/index.rst | 1 + .../overview/core-concepts/schema_cfgs.rst | 392 ++++++++++++++++++ .../vidur-add-mujoco-gravcomp.minor.rst | 11 + source/isaaclab/isaaclab/sim/__init__.py | 30 +- source/isaaclab/isaaclab/sim/__init__.pyi | 22 + .../isaaclab/isaaclab/sim/schemas/__init__.py | 28 +- .../isaaclab/sim/schemas/__init__.pyi | 18 + .../isaaclab/isaaclab/sim/schemas/schemas.py | 30 +- .../isaaclab/sim/schemas/schemas_cfg.py | 36 +- .../sim/spawners/from_files/from_files.py | 19 + .../sim/spawners/materials/__init__.py | 2 +- .../materials/physics_materials_cfg.py | 2 +- .../vidur-add-newton-schemas.minor.rst | 22 + .../isaaclab_newton/sim/schemas/__init__.py | 17 + .../isaaclab_newton/sim/schemas/__init__.pyi | 15 + .../sim/schemas/schemas_cfg.py | 230 ++++++++++ .../test/sim/test_newton_schemas.py | 269 ++++++++++++ 22 files changed, 1565 insertions(+), 41 deletions(-) create mode 100644 docs/source/api/lab_newton/isaaclab_newton.sim.schemas.rst create mode 100644 docs/source/overview/core-concepts/schema_cfgs.rst create mode 100644 source/isaaclab/changelog.d/vidur-add-mujoco-gravcomp.minor.rst create mode 100644 source/isaaclab_newton/changelog.d/vidur-add-newton-schemas.minor.rst create mode 100644 source/isaaclab_newton/isaaclab_newton/sim/schemas/__init__.py create mode 100644 source/isaaclab_newton/isaaclab_newton/sim/schemas/__init__.pyi create mode 100644 source/isaaclab_newton/isaaclab_newton/sim/schemas/schemas_cfg.py create mode 100644 source/isaaclab_newton/test/sim/test_newton_schemas.py diff --git a/docs/source/api/index.rst b/docs/source/api/index.rst index f296c74310c6..bab5f025a78e 100644 --- a/docs/source/api/index.rst +++ b/docs/source/api/index.rst @@ -161,6 +161,7 @@ The following modules are available in the ``isaaclab_newton`` extension: renderers scene_data_providers sensors + sim.schemas .. toctree:: :hidden: @@ -171,6 +172,7 @@ The following modules are available in the ``isaaclab_newton`` extension: lab_newton/isaaclab_newton.renderers lab_newton/isaaclab_newton.scene_data_providers lab_newton/isaaclab_newton.sensors + lab_newton/isaaclab_newton.sim.schemas isaaclab_ov extension --------------------- diff --git a/docs/source/api/lab/isaaclab.sim.schemas.rst b/docs/source/api/lab/isaaclab.sim.schemas.rst index 263e3152e596..bb0651c83ec2 100644 --- a/docs/source/api/lab/isaaclab.sim.schemas.rst +++ b/docs/source/api/lab/isaaclab.sim.schemas.rst @@ -1,18 +1,31 @@ -isaaclab.sim.schemas +isaaclab.sim.schemas ==================== .. automodule:: isaaclab.sim.schemas - .. rubric:: Classes + .. rubric:: Solver-common base classes + + These base classes carry the universal-physics fields that every backend honors. + They live in core ``isaaclab`` and have no backend dependency. For backend-specific + knobs, use the matching subclass in :mod:`isaaclab_physx.sim.schemas` or + :mod:`isaaclab_newton.sim.schemas`. See :doc:`/source/overview/core-concepts/schema_cfgs` + for the full design. .. autosummary:: - ArticulationRootPropertiesCfg - RigidBodyPropertiesCfg - CollisionPropertiesCfg + ArticulationRootBaseCfg + RigidBodyBaseCfg + CollisionBaseCfg + JointDriveBaseCfg + MeshCollisionBaseCfg MassPropertiesCfg - JointDrivePropertiesCfg - FixedTendonPropertiesCfg + + .. rubric:: Mesh collision approximations (USD-only, no PhysX schema) + + .. autosummary:: + + BoundingCubePropertiesCfg + BoundingSpherePropertiesCfg .. rubric:: Functions @@ -28,22 +41,33 @@ define_mass_properties modify_mass_properties modify_joint_drive_properties + define_mesh_collision_properties + modify_mesh_collision_properties modify_fixed_tendon_properties + modify_spatial_tendon_properties + +.. currentmodule:: isaaclab.sim.schemas Articulation Root ----------------- -.. autoclass:: ArticulationRootPropertiesCfg +.. autoclass:: ArticulationRootBaseCfg :members: :exclude-members: __init__ .. autofunction:: define_articulation_root_properties .. autofunction:: modify_articulation_root_properties +For PhysX-specific articulation properties (self-collisions, TGS solver iterations, +sleep/stabilization thresholds), see +:class:`~isaaclab_physx.sim.schemas.PhysxArticulationRootPropertiesCfg`. For +Newton-native self-collisions, see +:class:`~isaaclab_newton.sim.schemas.NewtonArticulationRootPropertiesCfg`. + Rigid Body ---------- -.. autoclass:: RigidBodyPropertiesCfg +.. autoclass:: RigidBodyBaseCfg :members: :exclude-members: __init__ @@ -51,16 +75,26 @@ Rigid Body .. autofunction:: modify_rigid_body_properties .. autofunction:: activate_contact_sensors +For PhysX-specific rigid body properties (damping, max velocities, solver iterations, +sleep/stabilization), see :class:`~isaaclab_physx.sim.schemas.PhysxRigidBodyPropertiesCfg`. +For MuJoCo-specific gravity compensation, see +:class:`~isaaclab_newton.sim.schemas.MujocoRigidBodyPropertiesCfg`. + Collision --------- -.. autoclass:: CollisionPropertiesCfg +.. autoclass:: CollisionBaseCfg :members: :exclude-members: __init__ .. autofunction:: define_collision_properties .. autofunction:: modify_collision_properties +For PhysX torsional patch friction, see +:class:`~isaaclab_physx.sim.schemas.PhysxCollisionPropertiesCfg`. For Newton-native +contact margin/gap, see +:class:`~isaaclab_newton.sim.schemas.NewtonCollisionPropertiesCfg`. + Mass ---- @@ -74,20 +108,52 @@ Mass Joint Drive ----------- -.. autoclass:: JointDrivePropertiesCfg +.. autoclass:: JointDriveBaseCfg :members: :exclude-members: __init__ .. autofunction:: modify_joint_drive_properties -Fixed Tendon ------------- +For PhysX-specific drive properties, see +:class:`~isaaclab_physx.sim.schemas.PhysxJointDrivePropertiesCfg`. For MuJoCo +actuator gravity compensation, see +:class:`~isaaclab_newton.sim.schemas.MujocoJointDrivePropertiesCfg`. + +Mesh Collision +-------------- -.. autoclass:: FixedTendonPropertiesCfg +.. autoclass:: MeshCollisionBaseCfg :members: :exclude-members: __init__ +.. autoclass:: BoundingCubePropertiesCfg + :members: + :show-inheritance: + :exclude-members: __init__ + +.. autoclass:: BoundingSpherePropertiesCfg + :members: + :show-inheritance: + :exclude-members: __init__ + +.. autofunction:: define_mesh_collision_properties +.. autofunction:: modify_mesh_collision_properties + +For PhysX cooking schemas (convex hull / decomposition / triangle mesh / SDF), +see the ``Physx*PropertiesCfg`` family in :mod:`isaaclab_physx.sim.schemas`. +For Newton hull-vertex limit, see +:class:`~isaaclab_newton.sim.schemas.NewtonMeshCollisionPropertiesCfg`. + +Tendon +------ + .. autofunction:: modify_fixed_tendon_properties +.. autofunction:: modify_spatial_tendon_properties + +Tendon cfg classes are PhysX-only and live in +:mod:`isaaclab_physx.sim.schemas` +(:class:`~isaaclab_physx.sim.schemas.PhysxFixedTendonPropertiesCfg`, +:class:`~isaaclab_physx.sim.schemas.PhysxSpatialTendonPropertiesCfg`). Deformable Body --------------- diff --git a/docs/source/api/lab_newton/isaaclab_newton.sim.schemas.rst b/docs/source/api/lab_newton/isaaclab_newton.sim.schemas.rst new file mode 100644 index 000000000000..f0dde258fe8c --- /dev/null +++ b/docs/source/api/lab_newton/isaaclab_newton.sim.schemas.rst @@ -0,0 +1,88 @@ +isaaclab_newton.sim.schemas +=========================== + +.. automodule:: isaaclab_newton.sim.schemas + + Newton-targeted schema configuration classes. Each cfg below extends a + solver-common base in :mod:`isaaclab.sim.schemas` with Newton-namespaced + attributes (``newton:*``) or solver-specific attributes (``mjc:*`` for + Newton's MuJoCo solver). MuJoCo cfgs subclass their Newton counterpart + because MuJoCo is one of Newton's solver options. + + See :doc:`/source/overview/core-concepts/schema_cfgs` for the design and + when to use each class. + + .. rubric:: Newton-targeted (family roots) + + .. autosummary:: + + NewtonRigidBodyPropertiesCfg + NewtonJointDrivePropertiesCfg + NewtonCollisionPropertiesCfg + NewtonMeshCollisionPropertiesCfg + NewtonMaterialPropertiesCfg + NewtonArticulationRootPropertiesCfg + + .. rubric:: MuJoCo-solver-specific + + .. autosummary:: + + MujocoRigidBodyPropertiesCfg + MujocoJointDrivePropertiesCfg + +.. currentmodule:: isaaclab_newton.sim.schemas + +Rigid Body +---------- + +.. autoclass:: NewtonRigidBodyPropertiesCfg + :members: + :show-inheritance: + :exclude-members: __init__ + +.. autoclass:: MujocoRigidBodyPropertiesCfg + :members: + :show-inheritance: + :exclude-members: __init__ + +Joint Drive +----------- + +.. autoclass:: NewtonJointDrivePropertiesCfg + :members: + :show-inheritance: + :exclude-members: __init__ + +.. autoclass:: MujocoJointDrivePropertiesCfg + :members: + :show-inheritance: + :exclude-members: __init__ + +Collision +--------- + +.. autoclass:: NewtonCollisionPropertiesCfg + :members: + :show-inheritance: + :exclude-members: __init__ + +.. autoclass:: NewtonMeshCollisionPropertiesCfg + :members: + :show-inheritance: + :exclude-members: __init__ + +Material +-------- + +.. autoclass:: NewtonMaterialPropertiesCfg + :members: + :show-inheritance: + :exclude-members: __init__ + +Articulation Root +----------------- + +.. autoclass:: NewtonArticulationRootPropertiesCfg + :members: + :show-inheritance: + :exclude-members: __init__ diff --git a/docs/source/api/lab_physx/isaaclab_physx.sim.schemas.rst b/docs/source/api/lab_physx/isaaclab_physx.sim.schemas.rst index 40fb3addb275..305269068991 100644 --- a/docs/source/api/lab_physx/isaaclab_physx.sim.schemas.rst +++ b/docs/source/api/lab_physx/isaaclab_physx.sim.schemas.rst @@ -3,7 +3,49 @@ isaaclab_physx.sim.schemas .. automodule:: isaaclab_physx.sim.schemas - .. rubric:: Classes + PhysX-specific schema configuration classes. Each cfg below extends a + solver-common base in :mod:`isaaclab.sim.schemas` with PhysX-namespaced + attributes (``physx*:*``) and applies the corresponding ``Physx*API`` + applied schema. See :doc:`/source/overview/core-concepts/schema_cfgs` + for the design. + + .. rubric:: Rigid body and joint drive + + .. autosummary:: + + PhysxRigidBodyPropertiesCfg + PhysxJointDrivePropertiesCfg + + .. rubric:: Collision + + .. autosummary:: + + PhysxCollisionPropertiesCfg + + .. rubric:: Articulation root + + .. autosummary:: + + PhysxArticulationRootPropertiesCfg + + .. rubric:: Mesh collision (PhysX cooking) + + .. autosummary:: + + PhysxConvexHullPropertiesCfg + PhysxConvexDecompositionPropertiesCfg + PhysxTriangleMeshPropertiesCfg + PhysxTriangleMeshSimplificationPropertiesCfg + PhysxSDFMeshPropertiesCfg + + .. rubric:: Tendon + + .. autosummary:: + + PhysxFixedTendonPropertiesCfg + PhysxSpatialTendonPropertiesCfg + + .. rubric:: Deformable body .. autosummary:: @@ -18,6 +60,79 @@ isaaclab_physx.sim.schemas .. currentmodule:: isaaclab_physx.sim.schemas +Rigid Body +---------- + +.. autoclass:: PhysxRigidBodyPropertiesCfg + :members: + :show-inheritance: + :exclude-members: __init__ + +Joint Drive +----------- + +.. autoclass:: PhysxJointDrivePropertiesCfg + :members: + :show-inheritance: + :exclude-members: __init__ + +Collision +--------- + +.. autoclass:: PhysxCollisionPropertiesCfg + :members: + :show-inheritance: + :exclude-members: __init__ + +Articulation Root +----------------- + +.. autoclass:: PhysxArticulationRootPropertiesCfg + :members: + :show-inheritance: + :exclude-members: __init__ + +Mesh Collision (PhysX cooking) +------------------------------- + +.. autoclass:: PhysxConvexHullPropertiesCfg + :members: + :show-inheritance: + :exclude-members: __init__ + +.. autoclass:: PhysxConvexDecompositionPropertiesCfg + :members: + :show-inheritance: + :exclude-members: __init__ + +.. autoclass:: PhysxTriangleMeshPropertiesCfg + :members: + :show-inheritance: + :exclude-members: __init__ + +.. autoclass:: PhysxTriangleMeshSimplificationPropertiesCfg + :members: + :show-inheritance: + :exclude-members: __init__ + +.. autoclass:: PhysxSDFMeshPropertiesCfg + :members: + :show-inheritance: + :exclude-members: __init__ + +Tendon +------ + +.. autoclass:: PhysxFixedTendonPropertiesCfg + :members: + :show-inheritance: + :exclude-members: __init__ + +.. autoclass:: PhysxSpatialTendonPropertiesCfg + :members: + :show-inheritance: + :exclude-members: __init__ + Deformable Body --------------- diff --git a/docs/source/migration/migrating_to_isaaclab_3-0.rst b/docs/source/migration/migrating_to_isaaclab_3-0.rst index be5703ab1261..d660aa6e62ae 100644 --- a/docs/source/migration/migrating_to_isaaclab_3-0.rst +++ b/docs/source/migration/migrating_to_isaaclab_3-0.rst @@ -98,6 +98,167 @@ The following classes have been moved to ``isaaclab_physx``: installation steps are required. +.. _schemas-cfg-refactor: + +Schema Configuration Class Refactor +~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ + +In Isaac Lab 3.0, the spawner schema cfg classes are split into solver-common +**base classes** (in ``isaaclab.sim.schemas``) and **backend-specific subclasses** +in ``isaaclab_physx.sim.schemas`` and ``isaaclab_newton.sim.schemas``. This makes +the same asset cfg portable across PhysX and Newton backends, and adds slots +for backend-specific asset-level knobs (e.g., MuJoCo gravity compensation). + +For the full design, see :ref:`schema-cfgs`. + +**Class moves and renames** + +The following 2.x class names are kept as deprecated aliases. They forward to +the new location and will be removed in 4.0. + +.. list-table:: + :header-rows: 1 + :widths: 40 60 + + * - Isaac Lab 2.x + - Isaac Lab 3.0 + * - ``RigidBodyPropertiesCfg`` + - :class:`~isaaclab.sim.schemas.RigidBodyBaseCfg` (solver-common fields) + + :class:`~isaaclab_physx.sim.schemas.PhysxRigidBodyPropertiesCfg` (PhysX-specific) + * - ``JointDrivePropertiesCfg`` + - :class:`~isaaclab.sim.schemas.JointDriveBaseCfg` + + :class:`~isaaclab_physx.sim.schemas.PhysxJointDrivePropertiesCfg` + * - ``CollisionPropertiesCfg`` + - :class:`~isaaclab.sim.schemas.CollisionBaseCfg` + + :class:`~isaaclab_physx.sim.schemas.PhysxCollisionPropertiesCfg` + * - ``ArticulationRootPropertiesCfg`` + - :class:`~isaaclab.sim.schemas.ArticulationRootBaseCfg` + + :class:`~isaaclab_physx.sim.schemas.PhysxArticulationRootPropertiesCfg` + * - ``RigidBodyMaterialCfg`` + - :class:`~isaaclab.sim.spawners.materials.RigidBodyMaterialBaseCfg` + + :class:`~isaaclab_physx.sim.spawners.materials.PhysxRigidBodyMaterialCfg` + * - ``MeshCollisionPropertiesCfg`` family (``ConvexHullPropertiesCfg``, + ``ConvexDecompositionPropertiesCfg``, ``TriangleMeshPropertiesCfg``, + ``TriangleMeshSimplificationPropertiesCfg``, ``SDFMeshPropertiesCfg``) + - :class:`~isaaclab.sim.schemas.MeshCollisionBaseCfg` + + ``Physx*PropertiesCfg`` family in :mod:`isaaclab_physx.sim.schemas` + * - ``FixedTendonPropertiesCfg``, ``SpatialTendonPropertiesCfg`` + - :class:`~isaaclab_physx.sim.schemas.PhysxFixedTendonPropertiesCfg`, + :class:`~isaaclab_physx.sim.schemas.PhysxSpatialTendonPropertiesCfg` + +**Code migration** + +Existing 2.x code continues to work via the deprecation aliases (with a +``DeprecationWarning``; removed in 4.0): + +.. code-block:: python + + # Isaac Lab 2.x + import isaaclab.sim as sim_utils + rigid_props = sim_utils.RigidBodyPropertiesCfg(disable_gravity=True, linear_damping=0.1) + +Recommended 3.0 pattern when targeting PhysX: + +.. code-block:: python + + # Isaac Lab 3.0 — PhysX backend + from isaaclab_physx.sim.schemas import PhysxRigidBodyPropertiesCfg + rigid_props = PhysxRigidBodyPropertiesCfg(disable_gravity=True, linear_damping=0.1) + +Backend-portable 3.0 pattern (universal-physics fields only): + +.. code-block:: python + + # Isaac Lab 3.0 — backend-portable + from isaaclab.sim.schemas import RigidBodyBaseCfg + rigid_props = RigidBodyBaseCfg(rigid_body_enabled=True, disable_gravity=True) + +**Field renames on** ``JointDriveBaseCfg`` + +Two cfg fields were renamed so their snake_case names map identity-style to the +USD camelCase attribute names. The old names remain as deprecated dataclass +fields on :class:`~isaaclab.sim.schemas.JointDriveBaseCfg` (so +``dataclasses.fields()`` still sees them) and are forwarded to the new fields +in ``__post_init__`` with a ``DeprecationWarning``. Setting **both** the old +and new field on the same instance is silent — the canonical (new) field +wins; the old field's value is discarded after the warning. Both aliases are +scheduled for removal in 4.0. + +.. list-table:: + :header-rows: 1 + :widths: 35 35 30 + + * - Isaac Lab 2.x + - Isaac Lab 3.0 + - USD attribute (unchanged) + * - :attr:`~isaaclab.sim.schemas.JointDriveBaseCfg.max_velocity` + - :attr:`~isaaclab.sim.schemas.JointDriveBaseCfg.max_joint_velocity` + - ``physxJoint:maxJointVelocity`` + * - :attr:`~isaaclab.sim.schemas.JointDriveBaseCfg.max_effort` + - :attr:`~isaaclab.sim.schemas.JointDriveBaseCfg.max_force` + - ``drive::physics:maxForce`` + +Isaac Lab 2.x style still works (emits ``DeprecationWarning``; removed in 4.0): + +.. code-block:: python + + import isaaclab.sim as sim_utils + sim_utils.JointDrivePropertiesCfg(max_effort=80.0, max_velocity=5.0) + +Recommended 3.0 pattern, backend-portable: + +.. code-block:: python + + from isaaclab.sim.schemas import JointDriveBaseCfg + JointDriveBaseCfg(max_force=80.0, max_joint_velocity=5.0) + +Recommended 3.0 pattern, PhysX-targeted: + +.. code-block:: python + + from isaaclab_physx.sim.schemas import PhysxJointDrivePropertiesCfg + PhysxJointDrivePropertiesCfg(max_force=80.0, max_joint_velocity=5.0) + +**New Newton and MuJoCo cfg classes** + +For the Newton backend (and Newton's MuJoCo solver), new cfg classes are +available under :mod:`isaaclab_newton.sim.schemas`: + +.. list-table:: + :header-rows: 1 + :widths: 50 50 + + * - Class + - Use case + * - :class:`~isaaclab_newton.sim.schemas.NewtonCollisionPropertiesCfg` + - ``newton:contactMargin`` / ``newton:contactGap`` via ``NewtonCollisionAPI`` + * - :class:`~isaaclab_newton.sim.schemas.NewtonMeshCollisionPropertiesCfg` + - ``newton:maxHullVertices`` via ``NewtonMeshCollisionAPI`` + * - :class:`~isaaclab_newton.sim.schemas.NewtonMaterialPropertiesCfg` + - ``newton:torsionalFriction`` / ``newton:rollingFriction`` via ``NewtonMaterialAPI`` + * - :class:`~isaaclab_newton.sim.schemas.NewtonArticulationRootPropertiesCfg` + - ``newton:selfCollisionEnabled`` via ``NewtonArticulationRootAPI`` + * - :class:`~isaaclab_newton.sim.schemas.MujocoRigidBodyPropertiesCfg` + - ``mjc:gravcomp`` (body-level gravity compensation, MuJoCo solver only) + * - :class:`~isaaclab_newton.sim.schemas.MujocoJointDrivePropertiesCfg` + - ``mjc:actuatorgravcomp`` via ``MjcJointAPI`` (joint-level routing) + +The MuJoCo cfgs subclass their Newton parent because MuJoCo is one of Newton's +solver options. + +.. note:: + + Spawners auto-enable body-level gravity compensation when joint-level + ``actuatorgravcomp=True`` is requested but no Mujoco rigid-body cfg is + provided — without ``gravcomp`` on the bodies, ``actuatorgravcomp`` is a + no-op (no forces to route). To override, pass an explicit + ``MujocoRigidBodyPropertiesCfg`` in ``rigid_props``. See + :ref:`schema-cfgs-gravcomp` for details. + +For complete tables of which fields live on which class and where each lands in +USD, see :ref:`schema-cfgs`. + + Renaming of ``XformPrimView`` to ``FrameView`` ----------------------------------------------- diff --git a/docs/source/overview/core-concepts/index.rst b/docs/source/overview/core-concepts/index.rst index 10fdf8935fbc..052d7080eb67 100644 --- a/docs/source/overview/core-concepts/index.rst +++ b/docs/source/overview/core-concepts/index.rst @@ -8,6 +8,7 @@ This section we introduce core concepts in Isaac Lab. multi_backend_architecture + schema_cfgs task_workflows actuators sensors/index.rst diff --git a/docs/source/overview/core-concepts/schema_cfgs.rst b/docs/source/overview/core-concepts/schema_cfgs.rst new file mode 100644 index 000000000000..4fd547e79f16 --- /dev/null +++ b/docs/source/overview/core-concepts/schema_cfgs.rst @@ -0,0 +1,392 @@ +.. _schema-cfgs: + +Schema Configuration Classes +============================ + +Isaac Lab's spawners author USD physics attributes onto prims via a layered set of +configuration classes. The layering separates **universal-physics** parameters +from **backend-specific** parameters, so the same asset cfg can be authored once +and target any backend that supports it. + +This page explains the class hierarchy, when to use each tier, and how parameters +route to the underlying USD attributes. + +Migrating from 2.x? See :ref:`schemas-cfg-refactor` in the 3.0 migration guide. + +.. contents:: + :local: + :depth: 2 + +Quick example +------------- + +Add MuJoCo (MJC) gravity compensation to an articulated asset: + +.. code-block:: python + + import isaaclab.sim as sim_utils + from isaaclab_newton.sim.schemas import ( + MujocoRigidBodyPropertiesCfg, + MujocoJointDrivePropertiesCfg, + ) + + spawn = sim_utils.UsdFileCfg( + usd_path=f"{ISAAC_NUCLEUS_DIR}/Robots/Franka/franka_instanceable.usd", + rigid_props=MujocoRigidBodyPropertiesCfg(gravcomp=1.0), + joint_drive_props=MujocoJointDrivePropertiesCfg(actuatorgravcomp=True), + ) + +The Mujoco-specific fields land under ``mjc:*`` on the prim; any +``RigidBodyBaseCfg`` / ``JointDriveBaseCfg`` fields you set on the same instance +land under ``physics:*``. See :ref:`schema-cfgs-mixed` for the full routing rules. + +Class hierarchy +--------------- + +For each property group (rigid body, joint drive, collision, articulation root, +material, mesh collision), Isaac Lab defines a single base class in core +``isaaclab.sim.schemas`` and one subclass per backend in the corresponding +extension package: + +.. code-block:: text + + isaaclab.sim.schemas + ├── RigidBodyBaseCfg + │ ├── isaaclab_physx.sim.schemas.PhysxRigidBodyPropertiesCfg + │ └── isaaclab_newton.sim.schemas.NewtonRigidBodyPropertiesCfg + │ └── isaaclab_newton.sim.schemas.MujocoRigidBodyPropertiesCfg + │ + ├── JointDriveBaseCfg + │ ├── isaaclab_physx.sim.schemas.PhysxJointDrivePropertiesCfg + │ └── isaaclab_newton.sim.schemas.NewtonJointDrivePropertiesCfg + │ └── isaaclab_newton.sim.schemas.MujocoJointDrivePropertiesCfg + │ + ├── CollisionBaseCfg + │ ├── isaaclab_physx.sim.schemas.PhysxCollisionPropertiesCfg + │ └── isaaclab_newton.sim.schemas.NewtonCollisionPropertiesCfg + │ + ├── ArticulationRootBaseCfg + │ ├── isaaclab_physx.sim.schemas.PhysxArticulationRootPropertiesCfg + │ └── isaaclab_newton.sim.schemas.NewtonArticulationRootPropertiesCfg + │ + ├── MeshCollisionBaseCfg + │ ├── isaaclab_physx.sim.schemas.{PhysxConvexHull, PhysxConvexDecomposition, + │ │ PhysxTriangleMesh, PhysxSDFMesh, ...}PropertiesCfg + │ └── isaaclab_newton.sim.schemas.NewtonMeshCollisionPropertiesCfg + │ (also inherits NewtonCollisionPropertiesCfg — multi-namespace) + │ + └── isaaclab.sim.spawners.materials.RigidBodyMaterialBaseCfg + ├── isaaclab_physx.sim.spawners.materials.PhysxRigidBodyMaterialCfg + └── isaaclab_newton.sim.schemas.NewtonMaterialPropertiesCfg + +:class:`~isaaclab_newton.sim.schemas.NewtonMeshCollisionPropertiesCfg` uses +multiple inheritance: it extends both +:class:`~isaaclab_newton.sim.schemas.NewtonCollisionPropertiesCfg` (for +``contact_margin`` / ``contact_gap``) and +:class:`~isaaclab.sim.schemas.MeshCollisionBaseCfg` (for +``mesh_approximation_name``). This is the textbook case for the per-declaring- +class MRO routing described under :ref:`schema-cfgs-mixed` — each inherited +field is written under the namespace of the class that declared it. + +The hierarchy is **single-rooted per spawner slot**: every spawner has a single +field for each property group (``rigid_props``, ``joint_drive_props``, +``collision_props``, etc.), and Python's polymorphism allows any subclass to be +passed where the base type is expected. + +When to use which class +----------------------- + +The choice depends on which backends you target and which fields you need. + +**Use a base class** (``RigidBodyBaseCfg``, ``JointDriveBaseCfg``, etc.) + when you only need universal-physics fields and you want your asset cfg to be + backend-portable. Importing the base class does not pull in + :mod:`isaaclab_physx` or :mod:`isaaclab_newton`. + +**Use a PhysX subclass** (``PhysxRigidBodyPropertiesCfg``, etc.) + when your asset uses PhysX-specific knobs (per-body damping, TGS solver + iterations, sleep / stabilization thresholds, torsional patch friction, + compliant-contact materials, etc.) and you target the PhysX backend. Inherits + all base-class fields, so you can set both universal and PhysX fields on the + same instance. + +**Use a Newton subclass** (``NewtonRigidBodyPropertiesCfg``, etc.) + when you target Newton and need Newton-native attributes + (``newton:contactMargin``, ``newton:torsionalFriction``, + ``newton:selfCollisionEnabled``, etc.). The empty Newton base classes + (``NewtonRigidBodyPropertiesCfg``, ``NewtonJointDrivePropertiesCfg``) reserve + the ``newton:*`` namespace for future native fields and act as the parent for + solver-specific subclasses. + +**Use a MuJoCo subclass** (``MujocoRigidBodyPropertiesCfg``, ``MujocoJointDrivePropertiesCfg``) + when you specifically use Newton's **MuJoCo** solver and need MuJoCo-only + knobs (gravity compensation via ``mjc:gravcomp`` / + ``mjc:actuatorgravcomp``). Inherits from the Newton base, so + ``isinstance(cfg, NewtonRigidBodyPropertiesCfg)`` is True. + +What parameters live where +-------------------------- + +.. note:: + + The tables below summarize which fields live on which cfg classes. The + canonical source is the auto-generated API reference — see + :doc:`/source/api/lab/isaaclab.sim.schemas`, + :doc:`/source/api/lab_physx/isaaclab_physx.sim.schemas`, and + :doc:`/source/api/lab_newton/isaaclab_newton.sim.schemas`, which render + the cfg class docstrings directly. Treat these tables as a navigation aid; + if they drift from the source, the API docs win. + +Universal physics (declared on the base class) +"""""""""""""""""""""""""""""""""""""""""""""""""""""""""""""""""""""""""""""""""""""""""""""""" + +Lives on the **base class**. Most fields write to ``physics:*`` (the standard +``UsdPhysics.*API`` namespace), but a small set of "exception" fields are +declared on the base for backend-portability yet route to a non-``physics:*`` +namespace because that is the only USD path honored today (e.g., +``disable_gravity`` writes ``physxRigidBody:disableGravity`` because both PhysX +and Newton's importer consume the PhysX attribute). The "USD attribute" column +below is the actual emitted attribute, not the namespace family. + +.. list-table:: + :header-rows: 1 + :widths: 30 35 35 + + * - Base class + - Field + - USD attribute + * - ``RigidBodyBaseCfg`` + - ``rigid_body_enabled``, ``kinematic_enabled`` + - ``physics:rigidBodyEnabled``, ``physics:kinematicEnabled`` + * - ``RigidBodyBaseCfg`` + - ``disable_gravity`` + - ``physxRigidBody:disableGravity`` (per-body on PhysX; scene-level partial honor on Newton) + * - ``CollisionBaseCfg`` + - ``collision_enabled`` + - ``physics:collisionEnabled`` + * - ``CollisionBaseCfg`` + - ``contact_offset``, ``rest_offset`` + - ``physxCollision:contactOffset``, ``physxCollision:restOffset`` (Newton consumes via PhysX bridge) + * - ``ArticulationRootBaseCfg`` + - ``articulation_enabled`` + - ``physxArticulation:articulationEnabled`` + * - ``ArticulationRootBaseCfg`` + - ``fix_root_link`` + - synthesizes ``UsdPhysics.FixedJoint`` (writer-side, not a USD attribute) + * - ``JointDriveBaseCfg`` + - ``drive_type``, ``max_force``, ``stiffness``, ``damping`` + - ``drive::physics:type/maxForce/stiffness/damping`` + * - ``JointDriveBaseCfg`` + - ``max_joint_velocity`` + - ``physxJoint:maxJointVelocity`` (sole USD path; Newton consumes via PhysX bridge today) + * - ``JointDriveBaseCfg`` + - ``ensure_drives_exist`` + - writer-side only — when ``True``, ensures any drive with ``stiffness=0`` and + ``damping=0`` gets a minimal ``stiffness=1e-3`` so backends like Newton recognize + the joint as actively driven; not a USD attribute on its own + * - ``MassPropertiesCfg`` + - ``mass``, ``density`` + - ``physics:mass``, ``physics:density`` + * - ``RigidBodyMaterialBaseCfg`` + - ``static_friction``, ``dynamic_friction``, ``restitution`` + - ``physics:staticFriction``, ``physics:dynamicFriction``, ``physics:restitution`` + * - ``MeshCollisionBaseCfg`` + - ``mesh_approximation_name`` + - ``physics:approximation`` + +PhysX-specific (``physx*:*`` namespace, ``Physx*API`` schemas) +"""""""""""""""""""""""""""""""""""""""""""""""""""""""""""""""""""""""""""""""""""""""""""""""" + +Lives on the PhysX subclass. Only authored when the user opts in by setting the +field on a PhysX cfg. + +.. list-table:: + :header-rows: 1 + :widths: 35 35 30 + + * - PhysX subclass + - Fields (selection) + - USD namespace / schema + * - ``PhysxRigidBodyPropertiesCfg`` + - ``linear_damping``, ``angular_damping``, ``max_linear_velocity``, ``max_angular_velocity``, ``solver_position_iteration_count``, ``sleep_threshold``, ``enable_gyroscopic_forces``, … + - ``physxRigidBody:*`` / ``PhysxRigidBodyAPI`` + * - ``PhysxJointDrivePropertiesCfg`` + - (currently empty; reserved for future PhysX-only drive knobs) + - ``physxJoint:*`` / ``PhysxJointAPI`` + * - ``PhysxCollisionPropertiesCfg`` + - ``torsional_patch_radius``, ``min_torsional_patch_radius`` + - ``physxCollision:*`` / ``PhysxCollisionAPI`` + * - ``PhysxArticulationRootPropertiesCfg`` + - ``enabled_self_collisions``, ``solver_position_iteration_count``, ``sleep_threshold``, ``stabilization_threshold`` + - ``physxArticulation:*`` / ``PhysxArticulationAPI`` + * - ``PhysxRigidBodyMaterialCfg`` + - ``compliant_contact_stiffness``, ``compliant_contact_damping``, ``friction_combine_mode``, ``restitution_combine_mode`` + - ``physxMaterial:*`` / ``PhysxMaterialAPI`` + * - ``PhysxConvexHullPropertiesCfg`` (and other mesh-cooking subclasses) + - ``hull_vertex_limit``, ``min_thickness``, … + - ``physxConvexHullCollision:*`` / ``PhysxConvexHullCollisionAPI`` + +Newton-targeted (``newton:*`` namespace, ``Newton*API`` schemas) +"""""""""""""""""""""""""""""""""""""""""""""""""""""""""""""""""""""""""""""""""""""""""""""""" + +Lives on the Newton subclass. Authored only when the user opts in. + +.. list-table:: + :header-rows: 1 + :widths: 35 35 30 + + * - Newton subclass + - Fields + - USD namespace / schema + * - ``NewtonRigidBodyPropertiesCfg`` + - (empty — reserved for future Newton-native rigid-body fields) + - ``newton:*`` + * - ``NewtonJointDrivePropertiesCfg`` + - (empty — reserved for future Newton-native joint-drive fields) + - ``newton:*`` + * - ``NewtonCollisionPropertiesCfg`` + - ``contact_margin``, ``contact_gap`` + - ``newton:*`` / ``NewtonCollisionAPI`` + * - ``NewtonMeshCollisionPropertiesCfg`` + - ``max_hull_vertices`` + - ``newton:*`` / ``NewtonMeshCollisionAPI`` + * - ``NewtonMaterialPropertiesCfg`` + - ``torsional_friction``, ``rolling_friction`` + - ``newton:*`` / ``NewtonMaterialAPI`` + * - ``NewtonArticulationRootPropertiesCfg`` + - ``self_collision_enabled`` + - ``newton:*`` / ``NewtonArticulationRootAPI`` + +MuJoCo-solver-specific (``mjc:*`` namespace) +"""""""""""""""""""""""""""""""""""""""""""""""""""""""""""""""""""""""""""""""""""""""""""""""" + +Lives on a MuJoCo subclass that extends a Newton subclass. Only consumed when +running Newton's MuJoCo solver. + +.. list-table:: + :header-rows: 1 + :widths: 35 25 40 + + * - MuJoCo subclass + - Field + - USD attribute / schema + * - ``MujocoRigidBodyPropertiesCfg`` + - ``gravcomp`` + - ``mjc:gravcomp`` (raw attribute, no applied schema) + * - ``MujocoJointDrivePropertiesCfg`` + - ``actuatorgravcomp`` + - ``mjc:actuatorgravcomp`` via ``MjcJointAPI`` + +.. note:: + + The two MuJoCo rows differ in their USD applied-schema requirement: + ``mjc:actuatorgravcomp`` is part of the registered ``MjcJointAPI`` applied + schema (so the writer calls ``prim.AddAppliedSchema("MjcJointAPI")`` when + the field is non-None). ``mjc:gravcomp`` has no registered Mjc applied + schema for body-level gravity compensation, so the writer authors it as a + raw USD attribute. Newton's MuJoCo solver consumes both via the same + resolver path; the schema-application difference is purely a USD-side + detail. + +.. _schema-cfgs-mixed: + +Mixed-namespace authoring on a single instance +---------------------------------------------- + +Because each cfg field is routed to its **declaring class's** namespace (not +the instance's class), a subclass instance can author attributes across multiple +namespaces on the same prim. For example: + +.. code-block:: python + + from isaaclab_newton.sim.schemas import MujocoRigidBodyPropertiesCfg + + cfg = MujocoRigidBodyPropertiesCfg( + rigid_body_enabled=True, # declared on RigidBodyBaseCfg → physics:rigidBodyEnabled + disable_gravity=True, # declared on RigidBodyBaseCfg (exception) → physxRigidBody:disableGravity + gravcomp=1.0, # declared on MujocoRigidBodyPropertiesCfg → mjc:gravcomp + ) + +The writer applies each field to the namespace of the class where the field is +declared. The applied schemas (``PhysxRigidBodyAPI`` for ``disable_gravity``, +none for the Mjc raw attribute) are added only when the corresponding +fields are non-None. + +Spawner usage +------------- + +Spawners (``UsdFileCfg``, ``MeshCuboidCfg``, ``MeshSphereCfg``, …) accept +the base class type for each slot and use polymorphism to dispatch to the +correct subclass at write time: + +.. code-block:: python + + import isaaclab.sim as sim_utils + from isaaclab_physx.sim.schemas import PhysxRigidBodyPropertiesCfg + from isaaclab_newton.sim.schemas import MujocoJointDrivePropertiesCfg + + spawn = sim_utils.UsdFileCfg( + usd_path="...", + rigid_props=PhysxRigidBodyPropertiesCfg(disable_gravity=True, linear_damping=0.1), + joint_drive_props=MujocoJointDrivePropertiesCfg( + drive_type="acceleration", + stiffness=10.0, + damping=0.1, + actuatorgravcomp=True, + ), + ) + +.. _schema-cfgs-gravcomp: + +Gravity compensation (MuJoCo solver) +"""""""""""""""""""""""""""""""""""""""""""""""""""""""""""""""""""""""""""""""""""""""""""""""" + +Gravity compensation has two halves and you typically need both: + +* **Body-level**: + :attr:`~isaaclab_newton.sim.schemas.MujocoRigidBodyPropertiesCfg.gravcomp` + on each rigid body (writes ``mjc:gravcomp``). This is what *computes* the + compensation force. +* **Joint-level**: + :attr:`~isaaclab_newton.sim.schemas.MujocoJointDrivePropertiesCfg.actuatorgravcomp` + on each joint (writes ``mjc:actuatorgravcomp``). This routes the compensation + force through the actuator channel (``qfrc_actuator``) so it counts against + ``actuatorfrcrange``; otherwise it goes to ``qfrc_passive``. + +``actuatorgravcomp=True`` alone is a no-op — without body-level ``gravcomp`` +there are no forces to route. To prevent this footgun, the spawner +**auto-enables** ``MujocoRigidBodyPropertiesCfg(gravcomp=1.0)`` whenever +``joint_drive_props`` is a Mujoco cfg with ``actuatorgravcomp=True`` and +``rigid_props`` is not already a Mujoco cfg. If you want a different +``gravcomp`` value (or want to disable the auto-enable), pass an explicit +``MujocoRigidBodyPropertiesCfg`` in ``rigid_props``. + +Naming convention +----------------- + +Cfg field names use ``snake_case``; the writer converts them to ``camelCase`` +USD attribute names (``contact_margin`` → ``newton:contactMargin``). For +single-token fields (``gravcomp``, ``actuatorgravcomp``), the conversion is +identity, which matches MuJoCo's lowercase convention. + +Field renames preserve backward compatibility via deprecation aliases. Two such +aliases live on ``JointDriveBaseCfg`` today: + +* ``max_velocity`` → ``max_joint_velocity`` (USD attribute is ``physxJoint:maxJointVelocity``) +* ``max_effort`` → ``max_force`` (USD attribute is ``drive::physics:maxForce``) + +The old names remain as real dataclass fields (so ``dataclasses.fields()`` +sees them), defaulting to ``None``. ``__post_init__`` runs +``_deprecate_field_alias`` which, when the old field is set: emits a +``DeprecationWarning``, copies the value into the canonical field if the +canonical is ``None``, then nulls the old field. Setting **both** in the same +constructor is silent — the canonical wins; the old name's value is discarded. +Both aliases are scheduled for removal in 4.0. + +See also +-------- + +* :doc:`/source/migration/migrating_to_isaaclab_3-0` — migration guide +* :doc:`/source/api/lab/isaaclab.sim.schemas` — solver-common base class API +* :doc:`/source/api/lab_physx/isaaclab_physx.sim.schemas` — PhysX subclass API +* :doc:`/source/api/lab_newton/isaaclab_newton.sim.schemas` — Newton/MuJoCo subclass API diff --git a/source/isaaclab/changelog.d/vidur-add-mujoco-gravcomp.minor.rst b/source/isaaclab/changelog.d/vidur-add-mujoco-gravcomp.minor.rst new file mode 100644 index 000000000000..15ec19098dfa --- /dev/null +++ b/source/isaaclab/changelog.d/vidur-add-mujoco-gravcomp.minor.rst @@ -0,0 +1,11 @@ +Added +^^^^^ + +* Added forwarding shims on :mod:`isaaclab.sim.schemas` and :mod:`isaaclab.sim` for the + Newton/MuJoCo cfg classes added in :mod:`isaaclab_newton.sim.schemas` + (:class:`NewtonRigidBodyPropertiesCfg`, :class:`NewtonJointDrivePropertiesCfg`, + :class:`NewtonCollisionPropertiesCfg`, :class:`NewtonMeshCollisionPropertiesCfg`, + :class:`NewtonMaterialPropertiesCfg`, :class:`NewtonArticulationRootPropertiesCfg`, + :class:`MujocoRigidBodyPropertiesCfg`, :class:`MujocoJointDrivePropertiesCfg`). + The shims resolve lazily on first access so importing :mod:`isaaclab.sim.schemas` + does not require :mod:`isaaclab_newton` to be installed. diff --git a/source/isaaclab/isaaclab/sim/__init__.py b/source/isaaclab/isaaclab/sim/__init__.py index 9c140a2507cf..e1458e7873f3 100644 --- a/source/isaaclab/isaaclab/sim/__init__.py +++ b/source/isaaclab/isaaclab/sim/__init__.py @@ -69,6 +69,20 @@ _PHYSX_FORWARDS = _PHYSX_FORWARDS_SCHEMAS | _PHYSX_FORWARDS_MATERIALS +# Names that moved out of this package into ``isaaclab_newton.sim.schemas``. +# Resolved lazily on first access so importing ``isaaclab.sim`` does not +# require ``isaaclab_newton`` to be installed. +_NEWTON_FORWARDS = frozenset({ + "MujocoRigidBodyPropertiesCfg", + "MujocoJointDrivePropertiesCfg", + "NewtonRigidBodyPropertiesCfg", + "NewtonJointDrivePropertiesCfg", + "NewtonCollisionPropertiesCfg", + "NewtonMeshCollisionPropertiesCfg", + "NewtonMaterialPropertiesCfg", + "NewtonArticulationRootPropertiesCfg", +}) + def __getattr__(name): if name in _PHYSX_FORWARDS_SCHEMAS: @@ -78,7 +92,7 @@ def __getattr__(name): raise ImportError( f"'isaaclab.sim.{name}' has moved to 'isaaclab_physx.sim.schemas'." " Install the isaaclab_physx extension or update your import. This forwarding" - " shim is scheduled for removal in 5.0." + " shim is scheduled for removal in 4.0." ) from e return getattr(_physx_cfg, name) if name in _PHYSX_FORWARDS_MATERIALS: @@ -88,11 +102,21 @@ def __getattr__(name): raise ImportError( f"'isaaclab.sim.{name}' has moved to 'isaaclab_physx.sim.spawners.materials'." " Install the isaaclab_physx extension or update your import. This forwarding" - " shim is scheduled for removal in 5.0." + " shim is scheduled for removal in 4.0." ) from e return getattr(_physx_mat_cfg, name) + if name in _NEWTON_FORWARDS: + try: + from isaaclab_newton.sim.schemas import schemas_cfg as _newton_cfg + except ImportError as e: + raise ImportError( + f"'isaaclab.sim.{name}' has moved to 'isaaclab_newton.sim.schemas'." + " Install the isaaclab_newton extension or update your import. This forwarding" + " shim is scheduled for removal in 4.0." + ) from e + return getattr(_newton_cfg, name) return _stub_getattr(name) def __dir__(): - return sorted(set(_stub_dir()) | _PHYSX_FORWARDS) + return sorted(set(_stub_dir()) | _PHYSX_FORWARDS | _NEWTON_FORWARDS) diff --git a/source/isaaclab/isaaclab/sim/__init__.pyi b/source/isaaclab/isaaclab/sim/__init__.pyi index e1d9f535a207..2d5edfdf921f 100644 --- a/source/isaaclab/isaaclab/sim/__init__.pyi +++ b/source/isaaclab/isaaclab/sim/__init__.pyi @@ -43,6 +43,16 @@ __all__ = [ "JointDriveBaseCfg", "MassPropertiesCfg", "MeshCollisionPropertiesCfg", + "MujocoJointDrivePropertiesCfg", + "MujocoRigidBodyPropertiesCfg", + "NewtonArticulationRootPropertiesCfg", + "NewtonCollisionPropertiesCfg", + "NewtonJointDrivePropertiesCfg", + "NewtonMaterialPropertiesCfg", + "NewtonMeshCollisionPropertiesCfg", + "NewtonRigidBodyPropertiesCfg", + "PhysxJointDrivePropertiesCfg", + "PhysxRigidBodyPropertiesCfg", "RigidBodyBaseCfg", "SDFMeshPropertiesCfg", "SpatialTendonPropertiesCfg", @@ -209,12 +219,24 @@ from .schemas import ( JointDriveBaseCfg, MassPropertiesCfg, MeshCollisionPropertiesCfg, + PhysxJointDrivePropertiesCfg, + PhysxRigidBodyPropertiesCfg, RigidBodyBaseCfg, SDFMeshPropertiesCfg, SpatialTendonPropertiesCfg, TriangleMeshPropertiesCfg, TriangleMeshSimplificationPropertiesCfg, ) + +# Forwarded to isaaclab_newton.sim.schemas via __getattr__ shim +MujocoJointDrivePropertiesCfg = ... +MujocoRigidBodyPropertiesCfg = ... +NewtonArticulationRootPropertiesCfg = ... +NewtonCollisionPropertiesCfg = ... +NewtonJointDrivePropertiesCfg = ... +NewtonMaterialPropertiesCfg = ... +NewtonMeshCollisionPropertiesCfg = ... +NewtonRigidBodyPropertiesCfg = ... from .spawners import ( SpawnerCfg, RigidObjectSpawnerCfg, diff --git a/source/isaaclab/isaaclab/sim/schemas/__init__.py b/source/isaaclab/isaaclab/sim/schemas/__init__.py index 2692196d4829..223627d4e523 100644 --- a/source/isaaclab/isaaclab/sim/schemas/__init__.py +++ b/source/isaaclab/isaaclab/sim/schemas/__init__.py @@ -67,6 +67,20 @@ "PhysxSpatialTendonPropertiesCfg", }) +# Names that moved out of this module into ``isaaclab_newton.sim.schemas``. +# Resolved lazily on first access so importing ``isaaclab.sim.schemas`` does +# not require ``isaaclab_newton`` to be installed. +_NEWTON_FORWARDS = frozenset({ + "MujocoRigidBodyPropertiesCfg", + "MujocoJointDrivePropertiesCfg", + "NewtonRigidBodyPropertiesCfg", + "NewtonJointDrivePropertiesCfg", + "NewtonCollisionPropertiesCfg", + "NewtonMeshCollisionPropertiesCfg", + "NewtonMaterialPropertiesCfg", + "NewtonArticulationRootPropertiesCfg", +}) + def __getattr__(name): if name in _PHYSX_FORWARDS: @@ -76,11 +90,21 @@ def __getattr__(name): raise ImportError( f"'isaaclab.sim.schemas.{name}' has moved to 'isaaclab_physx.sim.schemas'." " Install the isaaclab_physx extension or update your import. This forwarding" - " shim is scheduled for removal in 5.0." + " shim is scheduled for removal in 4.0." ) from e return getattr(_physx_cfg, name) + if name in _NEWTON_FORWARDS: + try: + from isaaclab_newton.sim.schemas import schemas_cfg as _newton_cfg + except ImportError as e: + raise ImportError( + f"'isaaclab.sim.schemas.{name}' has moved to 'isaaclab_newton.sim.schemas'." + " Install the isaaclab_newton extension or update your import. This forwarding" + " shim is scheduled for removal in 4.0." + ) from e + return getattr(_newton_cfg, name) return _stub_getattr(name) def __dir__(): - return sorted(set(_stub_dir()) | _PHYSX_FORWARDS) + return sorted(set(_stub_dir()) | _PHYSX_FORWARDS | _NEWTON_FORWARDS) diff --git a/source/isaaclab/isaaclab/sim/schemas/__init__.pyi b/source/isaaclab/isaaclab/sim/schemas/__init__.pyi index 9a90ed0d810d..fd0c882a5f35 100644 --- a/source/isaaclab/isaaclab/sim/schemas/__init__.pyi +++ b/source/isaaclab/isaaclab/sim/schemas/__init__.pyi @@ -28,6 +28,14 @@ __all__ = [ "JointDriveBaseCfg", "MassPropertiesCfg", "MeshCollisionBaseCfg", + "MujocoJointDrivePropertiesCfg", + "MujocoRigidBodyPropertiesCfg", + "NewtonArticulationRootPropertiesCfg", + "NewtonCollisionPropertiesCfg", + "NewtonJointDrivePropertiesCfg", + "NewtonMaterialPropertiesCfg", + "NewtonMeshCollisionPropertiesCfg", + "NewtonRigidBodyPropertiesCfg", "RigidBodyBaseCfg", ] @@ -60,3 +68,13 @@ from .schemas_cfg import ( MeshCollisionBaseCfg, RigidBodyBaseCfg, ) + +# Forwarded to isaaclab_newton.sim.schemas via __getattr__ shim +MujocoJointDrivePropertiesCfg = ... +MujocoRigidBodyPropertiesCfg = ... +NewtonArticulationRootPropertiesCfg = ... +NewtonCollisionPropertiesCfg = ... +NewtonJointDrivePropertiesCfg = ... +NewtonMaterialPropertiesCfg = ... +NewtonMeshCollisionPropertiesCfg = ... +NewtonRigidBodyPropertiesCfg = ... diff --git a/source/isaaclab/isaaclab/sim/schemas/schemas.py b/source/isaaclab/isaaclab/sim/schemas/schemas.py index 70f129413e5b..b7a74e27ff25 100644 --- a/source/isaaclab/isaaclab/sim/schemas/schemas.py +++ b/source/isaaclab/isaaclab/sim/schemas/schemas.py @@ -416,14 +416,14 @@ def define_rigid_body_properties(prim_path: str, cfg: schemas_cfg.RigidBodyBaseC def modify_rigid_body_properties( prim_path: str, cfg: schemas_cfg.RigidBodyBaseCfg, stage: Usd.Stage | None = None ) -> bool: - """Modify PhysX parameters for a rigid body prim. + """Modify parameters for a rigid body prim. - A `rigid body`_ is a single body that can be simulated by PhysX. It can be either dynamic or kinematic. - A dynamic body responds to forces and collisions. A `kinematic body`_ can be moved by the user, but does not - respond to forces. They are similar to having static bodies that can be moved around. + A `rigid body`_ is a single body that can be simulated by a physics engine. It can be either dynamic + or kinematic. A dynamic body responds to forces and collisions. A `kinematic body`_ can be moved by + the user, but does not respond to forces. - The schema comprises of attributes that belong to the `RigidBodyAPI`_ and `PhysxRigidBodyAPI`_. - schemas. The latter contains the PhysX parameters for the rigid body. + Solver-common properties (from `RigidBodyAPI`_) are always written. Solver-specific properties are + written based on the cfg subclass metadata (``_usd_namespace``, ``_usd_applied_schema``). .. note:: This function is decorated with :func:`apply_nested` that sets the properties to all the prims @@ -432,11 +432,13 @@ def modify_rigid_body_properties( .. _rigid body: https://nvidia-omniverse.github.io/PhysX/physx/5.4.1/docs/RigidBodyOverview.html .. _kinematic body: https://openusd.org/release/wp_rigid_body_physics.html#kinematic-bodies .. _RigidBodyAPI: https://openusd.org/dev/api/class_usd_physics_rigid_body_a_p_i.html - .. _PhysxRigidBodyAPI: https://docs.omniverse.nvidia.com/kit/docs/omni_usd_schema_physics/104.2/class_physx_schema_physx_rigid_body_a_p_i.html Args: prim_path: The prim path to the rigid body. - cfg: The configuration for the rigid body. + cfg: The configuration for the rigid body. Accepts + :class:`~schemas_cfg.RigidBodyBaseCfg` for solver-common properties, + :class:`~schemas_cfg.PhysxRigidBodyPropertiesCfg` for PhysX properties, or + :class:`~schemas_cfg.MujocoRigidBodyPropertiesCfg` for Newton (MuJoCo) properties. stage: The stage where to find the prim. Defaults to None, in which case the current stage is used. @@ -727,15 +729,14 @@ def activate_contact_sensors(prim_path: str, threshold: float = 0.0, stage: Usd. def modify_joint_drive_properties( prim_path: str, cfg: schemas_cfg.JointDriveBaseCfg, stage: Usd.Stage | None = None ) -> bool: - """Modify PhysX parameters for a joint prim. + """Modify parameters for a joint prim. This function checks if the input prim is a prismatic or revolute joint and applies the joint drive schema on it. If the joint is a tendon (i.e., it has the `PhysxTendonAxisAPI`_ schema applied on it), then the joint drive schema is not applied. - Based on the configuration, this method modifies the properties of the joint drive. These properties are - based on the `UsdPhysics.DriveAPI`_ schema. For more information on the properties, please refer to the - official documentation. + Solver-common properties (from `UsdPhysics.DriveAPI`_) are always written. Solver-specific properties + are written based on the cfg subclass metadata (``_usd_namespace``, ``_usd_applied_schema``). .. caution:: @@ -748,7 +749,10 @@ def modify_joint_drive_properties( Args: prim_path: The prim path where to apply the joint drive schema. - cfg: The configuration for the joint drive. + cfg: The configuration for the joint drive. Accepts + :class:`~schemas_cfg.JointDriveBaseCfg` for solver-common properties, + :class:`~schemas_cfg.PhysxJointDrivePropertiesCfg` for PhysX properties, or + :class:`~schemas_cfg.MujocoJointDrivePropertiesCfg` for Newton (MuJoCo) properties. stage: The stage where to find the prim. Defaults to None, in which case the current stage is used. diff --git a/source/isaaclab/isaaclab/sim/schemas/schemas_cfg.py b/source/isaaclab/isaaclab/sim/schemas/schemas_cfg.py index eae040435429..e54d71ca9d76 100644 --- a/source/isaaclab/isaaclab/sim/schemas/schemas_cfg.py +++ b/source/isaaclab/isaaclab/sim/schemas/schemas_cfg.py @@ -44,6 +44,19 @@ } ) +_NEWTON_FORWARDS = frozenset( + { + "MujocoRigidBodyPropertiesCfg", + "MujocoJointDrivePropertiesCfg", + "NewtonRigidBodyPropertiesCfg", + "NewtonJointDrivePropertiesCfg", + "NewtonCollisionPropertiesCfg", + "NewtonMeshCollisionPropertiesCfg", + "NewtonMaterialPropertiesCfg", + "NewtonArticulationRootPropertiesCfg", + } +) + def __getattr__(name): if name in _PHYSX_FORWARDS: @@ -54,9 +67,20 @@ def __getattr__(name): f"'isaaclab.sim.schemas.schemas_cfg.{name}' has moved to" " 'isaaclab_physx.sim.schemas.schemas_cfg'. Install the isaaclab_physx" " extension or update your import. This forwarding shim is scheduled for" - " removal in 5.0." + " removal in 4.0." ) from e return getattr(_physx_cfg, name) + if name in _NEWTON_FORWARDS: + try: + from isaaclab_newton.sim.schemas import schemas_cfg as _newton_cfg + except ImportError as e: + raise ImportError( + f"'isaaclab.sim.schemas.schemas_cfg.{name}' has moved to" + " 'isaaclab_newton.sim.schemas.schemas_cfg'. Install the isaaclab_newton" + " extension or update your import. This forwarding shim is scheduled for" + " removal in 4.0." + ) from e + return getattr(_newton_cfg, name) raise AttributeError(f"module 'isaaclab.sim.schemas.schemas_cfg' has no attribute {name!r}") @@ -71,7 +95,7 @@ def _deprecate_field_alias(cfg, alias: str, canonical: str) -> None: if value is None: return warnings.warn( - f"'{alias}' is deprecated; use '{canonical}' instead. The alias is scheduled for removal in 5.0.", + f"'{alias}' is deprecated; use '{canonical}' instead. The alias is scheduled for removal in 4.0.", DeprecationWarning, stacklevel=3, ) @@ -367,7 +391,7 @@ def __post_init__(self): Use :attr:`max_force` instead. The cfg field is renamed so its snake_case name maps identity-style to the USD camelCase attribute (``maxForce`` on ``UsdPhysics.DriveAPI``). The alias is forwarded to - :attr:`max_force` in :meth:`__post_init__` and will be removed in 5.0. + :attr:`max_force` in :meth:`__post_init__` and will be removed in 4.0. """ stiffness: float | None = None @@ -421,7 +445,7 @@ def __post_init__(self): Use :attr:`max_joint_velocity` instead. The cfg field is renamed so its snake_case name maps identity-style to the USD camelCase attribute (``physxJoint:maxJointVelocity``). The alias is forwarded to - :attr:`max_joint_velocity` in :meth:`__post_init__` and will be removed in 5.0. + :attr:`max_joint_velocity` in :meth:`__post_init__` and will be removed in 4.0. """ @@ -468,7 +492,7 @@ def __getattr__(self, name: str): """ if name == "usd_api": warnings.warn( - "'usd_api' attribute is deprecated and will be removed in 5.0. Use class-level" + "'usd_api' attribute is deprecated and will be removed in 4.0. Use class-level" " metadata via getattr(cfg, '_usd_applied_schema').", DeprecationWarning, stacklevel=2, @@ -479,7 +503,7 @@ def __getattr__(self, name: str): return "MeshCollisionAPI" if schema is not None else None if name == "physx_api": warnings.warn( - "'physx_api' attribute is deprecated and will be removed in 5.0. Use class-level" + "'physx_api' attribute is deprecated and will be removed in 4.0. Use class-level" " metadata via getattr(cfg, '_usd_applied_schema').", DeprecationWarning, stacklevel=2, diff --git a/source/isaaclab/isaaclab/sim/spawners/from_files/from_files.py b/source/isaaclab/isaaclab/sim/spawners/from_files/from_files.py index 892d2e78b387..18ffcaf37c98 100644 --- a/source/isaaclab/isaaclab/sim/spawners/from_files/from_files.py +++ b/source/isaaclab/isaaclab/sim/spawners/from_files/from_files.py @@ -363,6 +363,25 @@ def _spawn_from_usd_file( # note: these are only for setting low-level simulation properties. all others should be set or are # and overridden by the articulation/actuator properties. if cfg.joint_drive_props is not None: + # auto-enable body-level gravcomp if joint-level actuator gravcomp is requested + # without it — actuatorgravcomp has no effect since there are no forces to route. + # Only auto-populates when the user did not already set ``gravcomp`` themselves; + # an explicit ``MujocoRigidBodyPropertiesCfg(gravcomp=0.5)`` is preserved as-is. + from isaaclab_newton.sim.schemas.schemas_cfg import MujocoJointDrivePropertiesCfg, MujocoRigidBodyPropertiesCfg + + body_gravcomp_unset = ( + not isinstance(cfg.rigid_props, MujocoRigidBodyPropertiesCfg) or cfg.rigid_props.gravcomp is None + ) + if ( + isinstance(cfg.joint_drive_props, MujocoJointDrivePropertiesCfg) + and cfg.joint_drive_props.actuatorgravcomp + and body_gravcomp_unset + ): + logger.info( + "Joint-level actuator gravity compensation requires body-level gravcomp." + " Auto-setting MujocoRigidBodyPropertiesCfg(gravcomp=1.0)." + ) + schemas.modify_rigid_body_properties(prim_path, MujocoRigidBodyPropertiesCfg(gravcomp=1.0)) schemas.modify_joint_drive_properties(prim_path, cfg.joint_drive_props) # define deformable body properties, or modify if deformable body API is present (PhysX only) diff --git a/source/isaaclab/isaaclab/sim/spawners/materials/__init__.py b/source/isaaclab/isaaclab/sim/spawners/materials/__init__.py index ae4049c25d21..3158625219c5 100644 --- a/source/isaaclab/isaaclab/sim/spawners/materials/__init__.py +++ b/source/isaaclab/isaaclab/sim/spawners/materials/__init__.py @@ -73,7 +73,7 @@ def __getattr__(name): raise ImportError( f"'isaaclab.sim.spawners.materials.{name}' has moved to" " 'isaaclab_physx.sim.spawners.materials'. Install the isaaclab_physx extension" - " or update your import. This forwarding shim is scheduled for removal in 5.0." + " or update your import. This forwarding shim is scheduled for removal in 4.0." ) from e return getattr(_physx_cfg, name) return _stub_getattr(name) diff --git a/source/isaaclab/isaaclab/sim/spawners/materials/physics_materials_cfg.py b/source/isaaclab/isaaclab/sim/spawners/materials/physics_materials_cfg.py index 86437285ee9e..0c9a7be478e8 100644 --- a/source/isaaclab/isaaclab/sim/spawners/materials/physics_materials_cfg.py +++ b/source/isaaclab/isaaclab/sim/spawners/materials/physics_materials_cfg.py @@ -27,7 +27,7 @@ def __getattr__(name): f"'isaaclab.sim.spawners.materials.physics_materials_cfg.{name}' has moved to" " 'isaaclab_physx.sim.spawners.materials.physics_materials_cfg'. Install the" " isaaclab_physx extension or update your import. This forwarding shim is scheduled" - " for removal in 5.0." + " for removal in 4.0." ) from e return getattr(_physx_mat_cfg, name) raise AttributeError(f"module 'isaaclab.sim.spawners.materials.physics_materials_cfg' has no attribute {name!r}") diff --git a/source/isaaclab_newton/changelog.d/vidur-add-newton-schemas.minor.rst b/source/isaaclab_newton/changelog.d/vidur-add-newton-schemas.minor.rst new file mode 100644 index 000000000000..84eb5ce846a1 --- /dev/null +++ b/source/isaaclab_newton/changelog.d/vidur-add-newton-schemas.minor.rst @@ -0,0 +1,22 @@ +Added +^^^^^ + +* Added :class:`~isaaclab_newton.sim.schemas.NewtonRigidBodyPropertiesCfg` and + :class:`~isaaclab_newton.sim.schemas.NewtonJointDrivePropertiesCfg` as Newton-targeted + bases for solver-specific subclasses. Currently empty (no Newton-native ``newton:*`` + rigid-body or joint-drive attributes today); reserved as the family root for any + future Newton-native fields. +* Added :class:`~isaaclab_newton.sim.schemas.MujocoRigidBodyPropertiesCfg` (subclasses + :class:`NewtonRigidBodyPropertiesCfg`) with :attr:`gravcomp` for body-level gravity + compensation (``mjc:gravcomp``). +* Added :class:`~isaaclab_newton.sim.schemas.MujocoJointDrivePropertiesCfg` (subclasses + :class:`NewtonJointDrivePropertiesCfg`) with :attr:`actuatorgravcomp` for joint-level + gravity compensation routing (``mjc:actuatorgravcomp`` via ``MjcJointAPI``). +* Added :class:`~isaaclab_newton.sim.schemas.NewtonCollisionPropertiesCfg` with + :attr:`contact_margin` and :attr:`contact_gap` (``newton:*`` via ``NewtonCollisionAPI``). +* Added :class:`~isaaclab_newton.sim.schemas.NewtonMeshCollisionPropertiesCfg` with + :attr:`max_hull_vertices` (``newton:maxHullVertices`` via ``NewtonMeshCollisionAPI``). +* Added :class:`~isaaclab_newton.sim.schemas.NewtonMaterialPropertiesCfg` with + :attr:`torsional_friction` and :attr:`rolling_friction` (``newton:*`` via ``NewtonMaterialAPI``). +* Added :class:`~isaaclab_newton.sim.schemas.NewtonArticulationRootPropertiesCfg` with + :attr:`self_collision_enabled` (``newton:selfCollisionEnabled`` via ``NewtonArticulationRootAPI``). diff --git a/source/isaaclab_newton/isaaclab_newton/sim/schemas/__init__.py b/source/isaaclab_newton/isaaclab_newton/sim/schemas/__init__.py new file mode 100644 index 000000000000..80f943ad46ee --- /dev/null +++ b/source/isaaclab_newton/isaaclab_newton/sim/schemas/__init__.py @@ -0,0 +1,17 @@ +# Copyright (c) 2022-2026, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md). +# All rights reserved. +# +# SPDX-License-Identifier: BSD-3-Clause + +"""Newton and MuJoCo simulation schema configuration classes.""" + +from .schemas_cfg import ( + MujocoJointDrivePropertiesCfg, + MujocoRigidBodyPropertiesCfg, + NewtonArticulationRootPropertiesCfg, + NewtonCollisionPropertiesCfg, + NewtonJointDrivePropertiesCfg, + NewtonMaterialPropertiesCfg, + NewtonMeshCollisionPropertiesCfg, + NewtonRigidBodyPropertiesCfg, +) diff --git a/source/isaaclab_newton/isaaclab_newton/sim/schemas/__init__.pyi b/source/isaaclab_newton/isaaclab_newton/sim/schemas/__init__.pyi new file mode 100644 index 000000000000..6dae7b8cf2b7 --- /dev/null +++ b/source/isaaclab_newton/isaaclab_newton/sim/schemas/__init__.pyi @@ -0,0 +1,15 @@ +# Copyright (c) 2022-2026, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md). +# All rights reserved. +# +# SPDX-License-Identifier: BSD-3-Clause + +from .schemas_cfg import ( + MujocoJointDrivePropertiesCfg, + MujocoRigidBodyPropertiesCfg, + NewtonArticulationRootPropertiesCfg, + NewtonCollisionPropertiesCfg, + NewtonJointDrivePropertiesCfg, + NewtonMaterialPropertiesCfg, + NewtonMeshCollisionPropertiesCfg, + NewtonRigidBodyPropertiesCfg, +) diff --git a/source/isaaclab_newton/isaaclab_newton/sim/schemas/schemas_cfg.py b/source/isaaclab_newton/isaaclab_newton/sim/schemas/schemas_cfg.py new file mode 100644 index 000000000000..f0065daa867f --- /dev/null +++ b/source/isaaclab_newton/isaaclab_newton/sim/schemas/schemas_cfg.py @@ -0,0 +1,230 @@ +# Copyright (c) 2022-2026, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md). +# All rights reserved. +# +# SPDX-License-Identifier: BSD-3-Clause + +from __future__ import annotations + +from typing import ClassVar + +from isaaclab.sim.schemas.schemas_cfg import ( + ArticulationRootBaseCfg, + CollisionBaseCfg, + JointDriveBaseCfg, + MeshCollisionBaseCfg, + RigidBodyBaseCfg, +) +from isaaclab.sim.spawners.materials.physics_materials_cfg import RigidBodyMaterialBaseCfg +from isaaclab.utils import configclass + + +@configclass +class NewtonRigidBodyPropertiesCfg(RigidBodyBaseCfg): + """Newton-targeted rigid body properties. + + Base class for cfgs that author rigid-body attributes consumed by any of + Newton's solver options (MuJoCo, XPBD, Featherstone, Semi-implicit, Kamino). + Newton has no native ``newton:*`` rigid-body attributes today, so this class + is currently empty — solver-specific subclasses (e.g., + :class:`MujocoRigidBodyPropertiesCfg`) carry the actual fields. + + The ``newton:`` namespace is reserved here so future Newton-native + rigid-body fields can be added without an API change. + + See :meth:`~isaaclab.sim.schemas.modify_rigid_body_properties` for more information. + """ + + _usd_namespace: ClassVar[str | None] = "newton" + _usd_applied_schema: ClassVar[str | None] = None + _usd_field_exceptions: ClassVar[dict] = {} + + +@configclass +class MujocoRigidBodyPropertiesCfg(NewtonRigidBodyPropertiesCfg): + """MuJoCo-solver-specific rigid body properties. + + Extends :class:`NewtonRigidBodyPropertiesCfg` with body-level gravity + compensation, consumed only when running Newton's MuJoCo solver. + + See :meth:`~isaaclab.sim.schemas.modify_rigid_body_properties` for more information. + + .. note:: + If the values are None, they are not modified. + """ + + _usd_namespace: ClassVar[str | None] = "mjc" + _usd_applied_schema: ClassVar[str | None] = None + _usd_field_exceptions: ClassVar[dict] = {} + + gravcomp: float | None = None + """Gravity compensation scale for the body [dimensionless]. + + ``0.0`` = no compensation; ``1.0`` = full compensation. + Written to ``mjc:gravcomp`` on the rigid-body prim. + Body-level gravcomp must be set for joint-level actuatorgravcomp to have any effect. + """ + + +@configclass +class NewtonJointDrivePropertiesCfg(JointDriveBaseCfg): + """Newton-targeted joint drive properties. + + Base class for cfgs that author joint-drive attributes consumed by any of + Newton's solver options. Newton has no native ``newton:*`` joint-drive + attributes today, so this class is currently empty — solver-specific + subclasses (e.g., :class:`MujocoJointDrivePropertiesCfg`) carry the actual + fields. + + The ``newton:`` namespace is reserved here so future Newton-native + joint-drive fields can be added without an API change. + + See :meth:`~isaaclab.sim.schemas.modify_joint_drive_properties` for more information. + """ + + _usd_namespace: ClassVar[str | None] = "newton" + _usd_applied_schema: ClassVar[str | None] = None + _usd_field_exceptions: ClassVar[dict] = {} + + +@configclass +class MujocoJointDrivePropertiesCfg(NewtonJointDrivePropertiesCfg): + """MuJoCo-solver-specific joint drive properties. + + Extends :class:`NewtonJointDrivePropertiesCfg` with joint-level gravity + compensation routing, consumed only when running Newton's MuJoCo solver. + + See :meth:`~isaaclab.sim.schemas.modify_joint_drive_properties` for more information. + + .. note:: + If the values are None, they are not modified. + """ + + _usd_namespace: ClassVar[str | None] = "mjc" + _usd_applied_schema: ClassVar[str | None] = "MjcJointAPI" + _usd_field_exceptions: ClassVar[dict] = {} + + actuatorgravcomp: bool | None = None + """Route gravity compensation forces through the actuator channel. + + When ``True``, compensation forces go to ``qfrc_actuator`` (subject to force limits). + Requires body-level :attr:`MujocoRigidBodyPropertiesCfg.gravcomp`. + Written to ``mjc:actuatorgravcomp`` via ``MjcJointAPI``. + """ + + +@configclass +class NewtonCollisionPropertiesCfg(CollisionBaseCfg): + """Newton-specific collision properties. + + Extends :class:`~isaaclab.sim.schemas.CollisionBaseCfg` with Newton-native + contact geometry attributes. + + See :meth:`~isaaclab.sim.schemas.modify_collision_properties` for more information. + + .. note:: + If the values are None, they are not modified. + """ + + _usd_namespace: ClassVar[str | None] = "newton" + _usd_applied_schema: ClassVar[str | None] = "NewtonCollisionAPI" + _usd_field_exceptions: ClassVar[dict] = {} + + contact_margin: float | None = None + """Outward inflation of the collision surface [m]. + + Extends the effective collision surface outward. Sum of both bodies' margins is + used for collision detection. Essential for thin shells and cloth. + Written to ``newton:contactMargin`` via ``NewtonCollisionAPI``. + Range: [0, inf). + """ + + contact_gap: float | None = None + """Additional contact detection gap [m]. + + AABBs are expanded by this value; contacts detected earlier to avoid tunneling. + Written to ``newton:contactGap`` via ``NewtonCollisionAPI``. + Set to ``-inf`` to use Newton's builder default. Range: [0, inf). + """ + + +@configclass +class NewtonMeshCollisionPropertiesCfg(NewtonCollisionPropertiesCfg, MeshCollisionBaseCfg): + """Newton-specific mesh collision properties. + + Extends :class:`NewtonCollisionPropertiesCfg` with convex-hull vertex limit. + + See :meth:`~isaaclab.sim.schemas.modify_mesh_collision_properties` for more information. + + .. note:: + If the values are None, they are not modified. + """ + + _usd_namespace: ClassVar[str | None] = "newton" + _usd_applied_schema: ClassVar[str | None] = "NewtonMeshCollisionAPI" + _usd_field_exceptions: ClassVar[dict] = {} + + max_hull_vertices: int | None = None + """Maximum vertices in the convex hull approximation [dimensionless]. + + Only relevant when ``physics:approximation = "convexHull"``. + Written to ``newton:maxHullVertices`` via ``NewtonMeshCollisionAPI``. + Set to ``-1`` to use as many vertices as needed for a perfect hull. + """ + + +@configclass +class NewtonMaterialPropertiesCfg(RigidBodyMaterialBaseCfg): + """Newton-specific rigid body material properties. + + Extends :class:`~isaaclab.sim.spawners.materials.RigidBodyMaterialBaseCfg` + with Newton-native friction attributes. + + See :meth:`~isaaclab.sim.spawners.materials.spawn_rigid_body_material` for more information. + + .. note:: + If the values are None, they are not modified. + """ + + _usd_namespace: ClassVar[str | None] = "newton" + _usd_applied_schema: ClassVar[str | None] = "NewtonMaterialAPI" + _usd_field_exceptions: ClassVar[dict] = {} + + torsional_friction: float | None = None + """Torsional friction coefficient (resistance to spinning at a contact point) [dimensionless]. + + Written to ``newton:torsionalFriction`` via ``NewtonMaterialAPI``. + Range: [0, inf). + """ + + rolling_friction: float | None = None + """Rolling friction coefficient (resistance to rolling motion) [dimensionless]. + + Written to ``newton:rollingFriction`` via ``NewtonMaterialAPI``. + Range: [0, inf). + """ + + +@configclass +class NewtonArticulationRootPropertiesCfg(ArticulationRootBaseCfg): + """Newton-specific articulation root properties. + + Extends :class:`~isaaclab.sim.schemas.ArticulationRootBaseCfg` with + Newton-native self-collision control. + + See :meth:`~isaaclab.sim.schemas.modify_articulation_root_properties` for more information. + + .. note:: + If the values are None, they are not modified. + """ + + _usd_namespace: ClassVar[str | None] = "newton" + _usd_applied_schema: ClassVar[str | None] = "NewtonArticulationRootAPI" + _usd_field_exceptions: ClassVar[dict] = {} + + self_collision_enabled: bool | None = None + """Whether self-collisions between bodies in this articulation are enabled. + + Written to ``newton:selfCollisionEnabled`` via ``NewtonArticulationRootAPI``. + Newton's resolver checks this native attribute first before falling back to + ``physxArticulation:enabledSelfCollisions``. + """ diff --git a/source/isaaclab_newton/test/sim/test_newton_schemas.py b/source/isaaclab_newton/test/sim/test_newton_schemas.py new file mode 100644 index 000000000000..67ee6265d82c --- /dev/null +++ b/source/isaaclab_newton/test/sim/test_newton_schemas.py @@ -0,0 +1,269 @@ +# Copyright (c) 2022-2026, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md). +# All rights reserved. +# +# SPDX-License-Identifier: BSD-3-Clause + +"""Tests for Newton and MuJoCo schema cfg classes in isaaclab_newton.""" + +from isaaclab.app import AppLauncher + +# launch omniverse app +simulation_app = AppLauncher(headless=True).app + +"""Rest everything follows.""" + +import pytest +from isaaclab_newton.sim.schemas import ( + MujocoJointDrivePropertiesCfg, + MujocoRigidBodyPropertiesCfg, + NewtonArticulationRootPropertiesCfg, + NewtonCollisionPropertiesCfg, + NewtonJointDrivePropertiesCfg, + NewtonMaterialPropertiesCfg, + NewtonMeshCollisionPropertiesCfg, + NewtonRigidBodyPropertiesCfg, +) + +from pxr import UsdPhysics + +import isaaclab.sim as sim_utils +import isaaclab.sim.schemas as schemas +from isaaclab.sim import SimulationCfg, SimulationContext +from isaaclab.sim.spawners.materials import spawn_rigid_body_material + + +@pytest.fixture +def setup_sim(): + """Fixture to set up and tear down the simulation context.""" + sim_utils.create_new_stage() + sim = SimulationContext(SimulationCfg(dt=0.1)) + yield sim + sim._disable_app_control_on_stop_handle = True + sim.stop() + sim.clear_instance() + + +# --------------------------------------------------------------------------- +# MuJoCo rigid body gravity compensation +# --------------------------------------------------------------------------- + + +@pytest.mark.isaacsim_ci +def test_mujoco_gravcomp_written(setup_sim): + """gravcomp=0.5 must write mjc:gravcomp=0.5 on the prim.""" + stage = sim_utils.get_current_stage() + sim_utils.create_prim("/World/body_gc", prim_type="Cube", translation=(0.0, 0.0, 0.5)) + schemas.define_rigid_body_properties("/World/body_gc", MujocoRigidBodyPropertiesCfg(gravcomp=0.5)) + attr = stage.GetPrimAtPath("/World/body_gc").GetAttribute("mjc:gravcomp") + assert attr.IsValid(), "mjc:gravcomp was not authored" + assert attr.Get() == pytest.approx(0.5) + + +@pytest.mark.isaacsim_ci +def test_mujoco_gravcomp_not_written_when_none(setup_sim): + """gravcomp=None must not write mjc:gravcomp.""" + stage = sim_utils.get_current_stage() + sim_utils.create_prim("/World/body_gc2", prim_type="Cube", translation=(1.0, 0.0, 0.5)) + schemas.define_rigid_body_properties("/World/body_gc2", MujocoRigidBodyPropertiesCfg()) + attr = stage.GetPrimAtPath("/World/body_gc2").GetAttribute("mjc:gravcomp") + assert not attr.IsValid(), "mjc:gravcomp should not be authored when gravcomp=None" + + +# --------------------------------------------------------------------------- +# MuJoCo joint actuator gravity comp +# --------------------------------------------------------------------------- + + +@pytest.mark.isaacsim_ci +def test_mujoco_actuatorgravcomp_written(setup_sim): + """actuatorgravcomp=True must write mjc:actuatorgravcomp=True on the joint prim.""" + stage = sim_utils.get_current_stage() + sim_utils.create_prim("/World/art_gc", prim_type="Xform") + sim_utils.create_prim("/World/art_gc/body0", prim_type="Cube") + sim_utils.create_prim("/World/art_gc/body1", prim_type="Cube") + UsdPhysics.RevoluteJoint.Define(stage, "/World/art_gc/joint0") + schemas.modify_joint_drive_properties("/World/art_gc", MujocoJointDrivePropertiesCfg(actuatorgravcomp=True)) + attr = stage.GetPrimAtPath("/World/art_gc/joint0").GetAttribute("mjc:actuatorgravcomp") + assert attr.IsValid(), "mjc:actuatorgravcomp was not authored" + assert attr.Get() is True + + +@pytest.mark.isaacsim_ci +def test_mujoco_actuatorgravcomp_not_written_when_none(setup_sim): + """actuatorgravcomp=None must not write mjc:actuatorgravcomp.""" + stage = sim_utils.get_current_stage() + sim_utils.create_prim("/World/art_gc2", prim_type="Xform") + sim_utils.create_prim("/World/art_gc2/body0", prim_type="Cube") + sim_utils.create_prim("/World/art_gc2/body1", prim_type="Cube") + UsdPhysics.RevoluteJoint.Define(stage, "/World/art_gc2/joint0") + schemas.modify_joint_drive_properties("/World/art_gc2", MujocoJointDrivePropertiesCfg()) + attr = stage.GetPrimAtPath("/World/art_gc2/joint0").GetAttribute("mjc:actuatorgravcomp") + assert not attr.IsValid(), "mjc:actuatorgravcomp should not be authored when None" + + +# --------------------------------------------------------------------------- +# Newton collision +# --------------------------------------------------------------------------- + + +@pytest.mark.isaacsim_ci +def test_newton_collision_contact_margin_written(setup_sim): + """contact_margin=0.01 must write newton:contactMargin and apply NewtonCollisionAPI.""" + stage = sim_utils.get_current_stage() + sim_utils.create_prim("/World/col_newton", prim_type="Cube", translation=(2.0, 0.0, 0.5)) + schemas.define_collision_properties("/World/col_newton", NewtonCollisionPropertiesCfg(contact_margin=0.01)) + prim = stage.GetPrimAtPath("/World/col_newton") + assert prim.GetAttribute("newton:contactMargin").Get() == pytest.approx(0.01) + assert "NewtonCollisionAPI" in prim.GetAppliedSchemas() + + +@pytest.mark.isaacsim_ci +def test_newton_collision_no_schema_when_none(setup_sim): + """NewtonCollisionPropertiesCfg() with all None must NOT apply NewtonCollisionAPI.""" + stage = sim_utils.get_current_stage() + sim_utils.create_prim("/World/col_newton2", prim_type="Cube", translation=(3.0, 0.0, 0.5)) + schemas.define_collision_properties("/World/col_newton2", NewtonCollisionPropertiesCfg()) + applied = stage.GetPrimAtPath("/World/col_newton2").GetAppliedSchemas() + assert "NewtonCollisionAPI" not in applied + + +# --------------------------------------------------------------------------- +# Newton material +# --------------------------------------------------------------------------- + + +@pytest.mark.isaacsim_ci +def test_newton_material_properties_written(setup_sim): + """torsional_friction and rolling_friction must be written and NewtonMaterialAPI applied.""" + mat_cfg = NewtonMaterialPropertiesCfg(torsional_friction=0.3, rolling_friction=0.001) + prim = spawn_rigid_body_material("/World/newton_mat", mat_cfg) + assert prim.GetAttribute("newton:torsionalFriction").Get() == pytest.approx(0.3) + assert prim.GetAttribute("newton:rollingFriction").Get() == pytest.approx(0.001) + assert "NewtonMaterialAPI" in prim.GetAppliedSchemas() + + +@pytest.mark.isaacsim_ci +def test_newton_material_no_schema_when_none(setup_sim): + """NewtonMaterialPropertiesCfg() with all Newton fields None must NOT apply NewtonMaterialAPI.""" + mat_cfg = NewtonMaterialPropertiesCfg() + prim = spawn_rigid_body_material("/World/newton_mat2", mat_cfg) + assert "NewtonMaterialAPI" not in prim.GetAppliedSchemas() + + +# --------------------------------------------------------------------------- +# Newton articulation root +# --------------------------------------------------------------------------- + + +@pytest.mark.isaacsim_ci +def test_newton_articulation_self_collision_written(setup_sim): + """self_collision_enabled=True must write newton:selfCollisionEnabled and apply the API.""" + stage = sim_utils.get_current_stage() + sim_utils.create_prim("/World/nart", prim_type="Xform") + sim_utils.create_prim("/World/nart/body0", prim_type="Cube") + UsdPhysics.ArticulationRootAPI.Apply(stage.GetPrimAtPath("/World/nart")) + schemas.modify_articulation_root_properties( + "/World/nart", + NewtonArticulationRootPropertiesCfg(self_collision_enabled=True), + ) + prim = stage.GetPrimAtPath("/World/nart") + assert prim.GetAttribute("newton:selfCollisionEnabled").Get() is True + assert "NewtonArticulationRootAPI" in prim.GetAppliedSchemas() + + +@pytest.mark.isaacsim_ci +def test_newton_articulation_no_schema_when_none(setup_sim): + """NewtonArticulationRootPropertiesCfg() with None must NOT apply NewtonArticulationRootAPI.""" + stage = sim_utils.get_current_stage() + sim_utils.create_prim("/World/nart2", prim_type="Xform") + sim_utils.create_prim("/World/nart2/body0", prim_type="Cube") + UsdPhysics.ArticulationRootAPI.Apply(stage.GetPrimAtPath("/World/nart2")) + schemas.modify_articulation_root_properties( + "/World/nart2", + NewtonArticulationRootPropertiesCfg(), + ) + applied = stage.GetPrimAtPath("/World/nart2").GetAppliedSchemas() + assert "NewtonArticulationRootAPI" not in applied + + +# --------------------------------------------------------------------------- +# Newton mesh collision (max_hull_vertices, NewtonMeshCollisionAPI) +# --------------------------------------------------------------------------- + + +@pytest.mark.isaacsim_ci +def test_newton_mesh_collision_max_hull_vertices_written(setup_sim): + """max_hull_vertices=64 must write newton:maxHullVertices and apply NewtonMeshCollisionAPI.""" + stage = sim_utils.get_current_stage() + sim_utils.create_prim("/World/mesh_col", prim_type="Cube", translation=(4.0, 0.0, 0.5)) + schemas.define_mesh_collision_properties( + "/World/mesh_col", + NewtonMeshCollisionPropertiesCfg(mesh_approximation_name="convexHull", max_hull_vertices=64), + ) + prim = stage.GetPrimAtPath("/World/mesh_col") + assert prim.GetAttribute("newton:maxHullVertices").Get() == 64 + assert "NewtonMeshCollisionAPI" in prim.GetAppliedSchemas() + + +@pytest.mark.isaacsim_ci +def test_newton_mesh_collision_no_schema_when_none(setup_sim): + """NewtonMeshCollisionPropertiesCfg() with max_hull_vertices=None must NOT apply NewtonMeshCollisionAPI.""" + stage = sim_utils.get_current_stage() + sim_utils.create_prim("/World/mesh_col2", prim_type="Cube", translation=(5.0, 0.0, 0.5)) + schemas.define_mesh_collision_properties( + "/World/mesh_col2", + NewtonMeshCollisionPropertiesCfg(mesh_approximation_name="convexHull"), + ) + applied = stage.GetPrimAtPath("/World/mesh_col2").GetAppliedSchemas() + assert "NewtonMeshCollisionAPI" not in applied + + +# --------------------------------------------------------------------------- +# Class hierarchy contract: Mujoco IS-A Newton +# --------------------------------------------------------------------------- + + +def test_mujoco_isinstance_newton(): + """MujocoXxxCfg instances must be isinstance of their Newton parent. + + The auto-enable spawner logic and any future polymorphic dispatch on + ``isinstance(cfg, NewtonRigidBodyPropertiesCfg)`` depends on this contract. + """ + mjc_rigid = MujocoRigidBodyPropertiesCfg(gravcomp=0.5) + assert isinstance(mjc_rigid, NewtonRigidBodyPropertiesCfg) + + mjc_joint = MujocoJointDrivePropertiesCfg(actuatorgravcomp=True) + assert isinstance(mjc_joint, NewtonJointDrivePropertiesCfg) + + +# --------------------------------------------------------------------------- +# Multi-namespace mixed write — verify per-declaring-class MRO routing keeps +# fields owned by different classes in different namespaces on the same prim. +# --------------------------------------------------------------------------- + + +@pytest.mark.isaacsim_ci +def test_newton_mesh_collision_mixed_namespace_write(setup_sim): + """A NewtonMeshCollisionPropertiesCfg with both contact_margin (declared on + NewtonCollisionPropertiesCfg) and max_hull_vertices (declared on + NewtonMeshCollisionPropertiesCfg) must write each under its declaring class's + namespace and apply both schemas. + """ + stage = sim_utils.get_current_stage() + sim_utils.create_prim("/World/mesh_mixed", prim_type="Cube", translation=(6.0, 0.0, 0.5)) + schemas.define_mesh_collision_properties( + "/World/mesh_mixed", + NewtonMeshCollisionPropertiesCfg( + mesh_approximation_name="convexHull", + max_hull_vertices=32, + contact_margin=0.005, + ), + ) + prim = stage.GetPrimAtPath("/World/mesh_mixed") + # Both attributes share the newton namespace but are gated on different applied + # schemas (NewtonCollisionAPI for contact_margin, NewtonMeshCollisionAPI for + # max_hull_vertices); per-declaring-class routing applies the right schema for each. + assert prim.GetAttribute("newton:contactMargin").Get() == pytest.approx(0.005) + assert prim.GetAttribute("newton:maxHullVertices").Get() == 32 + applied = prim.GetAppliedSchemas() + assert "NewtonMeshCollisionAPI" in applied From 1f35b1813b76a76d8a16aaca31eeb842a154a166 Mon Sep 17 00:00:00 2001 From: "isaaclab-bot[bot]" <282401363+isaaclab-bot[bot]@users.noreply.github.com> Date: Tue, 12 May 2026 06:05:06 +0000 Subject: [PATCH 41/51] [CI][Auto Version Bump] Compile changelog fragments (schedule) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Bumped packages: - isaaclab: 5.0.0 → 5.1.0 - isaaclab_assets: 0.3.3 → 0.3.4 - isaaclab_contrib: 0.3.1 → 0.3.2 - isaaclab_experimental: 0.0.3 → 0.0.4 - isaaclab_newton: 0.7.2 → 0.8.0 - isaaclab_ov: 0.1.6 → 0.1.7 - isaaclab_tasks: 1.5.36 → 1.5.37 - isaaclab_teleop: 0.3.10 → 0.3.11 --- .../hougantc-enable-pipeline-retarget.rst | 5 -- .../scene-initialize-renderers.minor.rst | 31 ------------ .../vidur-add-mujoco-gravcomp.minor.rst | 11 ---- source/isaaclab/config/extension.toml | 2 +- source/isaaclab/docs/CHANGELOG.rst | 50 +++++++++++++++++++ .../Adds-Assemble-Trocar-task-Based-RLinf.rst | 5 -- source/isaaclab_assets/config/extension.toml | 2 +- source/isaaclab_assets/docs/CHANGELOG.rst | 10 ++++ .../Adds-Assemble-Trocar-task-Based-RLinf.rst | 5 -- source/isaaclab_contrib/config/extension.toml | 2 +- source/isaaclab_contrib/docs/CHANGELOG.rst | 10 ++++ .../scene-initialize-renderers.rst | 10 ---- .../config/extension.toml | 2 +- .../isaaclab_experimental/docs/CHANGELOG.rst | 15 ++++++ .../scene-initialize-renderers.rst | 9 ---- .../vidur-add-newton-schemas.minor.rst | 22 -------- source/isaaclab_newton/config/extension.toml | 2 +- source/isaaclab_newton/docs/CHANGELOG.rst | 37 ++++++++++++++ .../scene-initialize-renderers.rst | 20 -------- source/isaaclab_ov/config/extension.toml | 2 +- source/isaaclab_ov/docs/CHANGELOG.rst | 25 ++++++++++ .../Adds-Assemble-Trocar-task-Based-RLinf.rst | 7 --- source/isaaclab_tasks/config/extension.toml | 2 +- source/isaaclab_tasks/docs/CHANGELOG.rst | 12 +++++ .../hougantc-pipelined-retargeting.rst | 23 --------- source/isaaclab_teleop/config/extension.toml | 2 +- source/isaaclab_teleop/docs/CHANGELOG.rst | 28 +++++++++++ 27 files changed, 195 insertions(+), 156 deletions(-) delete mode 100644 source/isaaclab/changelog.d/hougantc-enable-pipeline-retarget.rst delete mode 100644 source/isaaclab/changelog.d/scene-initialize-renderers.minor.rst delete mode 100644 source/isaaclab/changelog.d/vidur-add-mujoco-gravcomp.minor.rst delete mode 100644 source/isaaclab_assets/changelog.d/Adds-Assemble-Trocar-task-Based-RLinf.rst delete mode 100644 source/isaaclab_contrib/changelog.d/Adds-Assemble-Trocar-task-Based-RLinf.rst delete mode 100644 source/isaaclab_experimental/changelog.d/scene-initialize-renderers.rst delete mode 100644 source/isaaclab_newton/changelog.d/scene-initialize-renderers.rst delete mode 100644 source/isaaclab_newton/changelog.d/vidur-add-newton-schemas.minor.rst delete mode 100644 source/isaaclab_ov/changelog.d/scene-initialize-renderers.rst delete mode 100644 source/isaaclab_tasks/changelog.d/Adds-Assemble-Trocar-task-Based-RLinf.rst delete mode 100644 source/isaaclab_teleop/changelog.d/hougantc-pipelined-retargeting.rst diff --git a/source/isaaclab/changelog.d/hougantc-enable-pipeline-retarget.rst b/source/isaaclab/changelog.d/hougantc-enable-pipeline-retarget.rst deleted file mode 100644 index 451e8c1e572d..000000000000 --- a/source/isaaclab/changelog.d/hougantc-enable-pipeline-retarget.rst +++ /dev/null @@ -1,5 +0,0 @@ -Fixed -^^^^^ - -* Fixed extension installation to honor ``pip_upgrade_dependencies`` declared - in ``config/extension.toml``. diff --git a/source/isaaclab/changelog.d/scene-initialize-renderers.minor.rst b/source/isaaclab/changelog.d/scene-initialize-renderers.minor.rst deleted file mode 100644 index 86e29205be95..000000000000 --- a/source/isaaclab/changelog.d/scene-initialize-renderers.minor.rst +++ /dev/null @@ -1,31 +0,0 @@ -Added -^^^^^ - -* Added :meth:`~isaaclab.scene.InteractiveScene.initialize_renderers` to - pre-create renderer backends for all scene sensors with a - ``renderer_cfg`` against the shared - :class:`~isaaclab.renderers.render_context.RenderContext`. The method is - idempotent and is now invoked from - :class:`~isaaclab.envs.DirectRLEnv`, - :class:`~isaaclab.envs.DirectMARLEnv`, - :class:`~isaaclab.envs.ManagerBasedEnv`, and - :class:`~isaaclab.envs.LeappDeploymentEnv` after scene construction so - that renderer backend creation order is deterministic and front-loaded - before the first :meth:`~isaaclab.sim.SimulationContext.reset`. -* Added :meth:`~isaaclab.renderers.base_renderer.BaseRenderer.initialize` - post-physics lifecycle hook (default no-op) that runs once per backend - after :meth:`~isaaclab.sim.SimulationContext.reset` builds physics - models. ``__init__`` now defines the pre-physics phase (eagerly invoked - by :meth:`~isaaclab.scene.InteractiveScene.initialize_renderers`) and - ``initialize`` defines the post-physics phase, letting backends whose - setup needs scene data (e.g. a built Newton model) defer that work - cleanly. Driven by - :meth:`~isaaclab.renderers.render_context.RenderContext.ensure_initialize`, - registered on - :class:`~isaaclab.physics.physics_manager.PhysicsEvent` ``PHYSICS_READY`` - by :class:`~isaaclab.sim.SimulationContext` at ``order=5`` so it fires - before sensor/asset callbacks (``order=10``). This decouples renderer - post-physics setup from camera initialization. Backends created lazily - after PHYSICS_READY are eagerly initialized at - :meth:`~isaaclab.renderers.render_context.RenderContext.get_renderer` - time. diff --git a/source/isaaclab/changelog.d/vidur-add-mujoco-gravcomp.minor.rst b/source/isaaclab/changelog.d/vidur-add-mujoco-gravcomp.minor.rst deleted file mode 100644 index 15ec19098dfa..000000000000 --- a/source/isaaclab/changelog.d/vidur-add-mujoco-gravcomp.minor.rst +++ /dev/null @@ -1,11 +0,0 @@ -Added -^^^^^ - -* Added forwarding shims on :mod:`isaaclab.sim.schemas` and :mod:`isaaclab.sim` for the - Newton/MuJoCo cfg classes added in :mod:`isaaclab_newton.sim.schemas` - (:class:`NewtonRigidBodyPropertiesCfg`, :class:`NewtonJointDrivePropertiesCfg`, - :class:`NewtonCollisionPropertiesCfg`, :class:`NewtonMeshCollisionPropertiesCfg`, - :class:`NewtonMaterialPropertiesCfg`, :class:`NewtonArticulationRootPropertiesCfg`, - :class:`MujocoRigidBodyPropertiesCfg`, :class:`MujocoJointDrivePropertiesCfg`). - The shims resolve lazily on first access so importing :mod:`isaaclab.sim.schemas` - does not require :mod:`isaaclab_newton` to be installed. diff --git a/source/isaaclab/config/extension.toml b/source/isaaclab/config/extension.toml index 70492269607c..2afa36a1dd92 100644 --- a/source/isaaclab/config/extension.toml +++ b/source/isaaclab/config/extension.toml @@ -1,7 +1,7 @@ [package] # Note: Semantic Versioning is used: https://semver.org/ -version = "5.0.0" +version = "5.1.0" # Description title = "Isaac Lab framework for Robot Learning" diff --git a/source/isaaclab/docs/CHANGELOG.rst b/source/isaaclab/docs/CHANGELOG.rst index 77a0b816c5d9..fdb92ec1c070 100644 --- a/source/isaaclab/docs/CHANGELOG.rst +++ b/source/isaaclab/docs/CHANGELOG.rst @@ -1,6 +1,56 @@ Changelog --------- +5.1.0 (2026-05-12) +~~~~~~~~~~~~~~~~~~ + +Added +^^^^^ + +* Added :meth:`~isaaclab.scene.InteractiveScene.initialize_renderers` to + pre-create renderer backends for all scene sensors with a + ``renderer_cfg`` against the shared + :class:`~isaaclab.renderers.render_context.RenderContext`. The method is + idempotent and is now invoked from + :class:`~isaaclab.envs.DirectRLEnv`, + :class:`~isaaclab.envs.DirectMARLEnv`, + :class:`~isaaclab.envs.ManagerBasedEnv`, and + :class:`~isaaclab.envs.LeappDeploymentEnv` after scene construction so + that renderer backend creation order is deterministic and front-loaded + before the first :meth:`~isaaclab.sim.SimulationContext.reset`. +* Added :meth:`~isaaclab.renderers.base_renderer.BaseRenderer.initialize` + post-physics lifecycle hook (default no-op) that runs once per backend + after :meth:`~isaaclab.sim.SimulationContext.reset` builds physics + models. ``__init__`` now defines the pre-physics phase (eagerly invoked + by :meth:`~isaaclab.scene.InteractiveScene.initialize_renderers`) and + ``initialize`` defines the post-physics phase, letting backends whose + setup needs scene data (e.g. a built Newton model) defer that work + cleanly. Driven by + :meth:`~isaaclab.renderers.render_context.RenderContext.ensure_initialize`, + registered on + :class:`~isaaclab.physics.physics_manager.PhysicsEvent` ``PHYSICS_READY`` + by :class:`~isaaclab.sim.SimulationContext` at ``order=5`` so it fires + before sensor/asset callbacks (``order=10``). This decouples renderer + post-physics setup from camera initialization. Backends created lazily + after PHYSICS_READY are eagerly initialized at + :meth:`~isaaclab.renderers.render_context.RenderContext.get_renderer` + time. +* Added forwarding shims on :mod:`isaaclab.sim.schemas` and :mod:`isaaclab.sim` for the + Newton/MuJoCo cfg classes added in :mod:`isaaclab_newton.sim.schemas` + (:class:`NewtonRigidBodyPropertiesCfg`, :class:`NewtonJointDrivePropertiesCfg`, + :class:`NewtonCollisionPropertiesCfg`, :class:`NewtonMeshCollisionPropertiesCfg`, + :class:`NewtonMaterialPropertiesCfg`, :class:`NewtonArticulationRootPropertiesCfg`, + :class:`MujocoRigidBodyPropertiesCfg`, :class:`MujocoJointDrivePropertiesCfg`). + The shims resolve lazily on first access so importing :mod:`isaaclab.sim.schemas` + does not require :mod:`isaaclab_newton` to be installed. + +Fixed +^^^^^ + +* Fixed extension installation to honor ``pip_upgrade_dependencies`` declared + in ``config/extension.toml``. + + 5.0.0 (2026-05-11) ~~~~~~~~~~~~~~~~~~ diff --git a/source/isaaclab_assets/changelog.d/Adds-Assemble-Trocar-task-Based-RLinf.rst b/source/isaaclab_assets/changelog.d/Adds-Assemble-Trocar-task-Based-RLinf.rst deleted file mode 100644 index 2a79e0a27d50..000000000000 --- a/source/isaaclab_assets/changelog.d/Adds-Assemble-Trocar-task-Based-RLinf.rst +++ /dev/null @@ -1,5 +0,0 @@ -Added -^^^^^ - -* Added :class:`~isaaclab_assets.robots.unitree.G129_CFG_WITH_DEX3_BASE_FIX` robot configuration - for the Unitree G1 29-DOF with Dex3 hands. diff --git a/source/isaaclab_assets/config/extension.toml b/source/isaaclab_assets/config/extension.toml index 1bf36d627e3e..055e3a5ff2f2 100644 --- a/source/isaaclab_assets/config/extension.toml +++ b/source/isaaclab_assets/config/extension.toml @@ -1,6 +1,6 @@ [package] # Semantic Versioning is used: https://semver.org/ -version = "0.3.3" +version = "0.3.4" # Description title = "Isaac Lab Assets" diff --git a/source/isaaclab_assets/docs/CHANGELOG.rst b/source/isaaclab_assets/docs/CHANGELOG.rst index 1d676f70a27e..e9eda5822210 100644 --- a/source/isaaclab_assets/docs/CHANGELOG.rst +++ b/source/isaaclab_assets/docs/CHANGELOG.rst @@ -1,6 +1,16 @@ Changelog --------- +0.3.4 (2026-05-12) +~~~~~~~~~~~~~~~~~~ + +Added +^^^^^ + +* Added :class:`~isaaclab_assets.robots.unitree.G129_CFG_WITH_DEX3_BASE_FIX` robot configuration + for the Unitree G1 29-DOF with Dex3 hands. + + 0.3.3 (2026-04-29) ~~~~~~~~~~~~~~~~~~~ diff --git a/source/isaaclab_contrib/changelog.d/Adds-Assemble-Trocar-task-Based-RLinf.rst b/source/isaaclab_contrib/changelog.d/Adds-Assemble-Trocar-task-Based-RLinf.rst deleted file mode 100644 index 062bce25b772..000000000000 --- a/source/isaaclab_contrib/changelog.d/Adds-Assemble-Trocar-task-Based-RLinf.rst +++ /dev/null @@ -1,5 +0,0 @@ -Fixed -^^^^^ - -* Removed ``_patched_reset`` monkey-patch in RLinf extension; use - ``num_rerenders_on_reset`` env config instead. diff --git a/source/isaaclab_contrib/config/extension.toml b/source/isaaclab_contrib/config/extension.toml index 0fba6e220442..bdeec969ff56 100644 --- a/source/isaaclab_contrib/config/extension.toml +++ b/source/isaaclab_contrib/config/extension.toml @@ -1,6 +1,6 @@ [package] # Semantic Versioning is used: https://semver.org/ -version = "0.3.1" +version = "0.3.2" # Description title = "Isaac Lab External Contributions" diff --git a/source/isaaclab_contrib/docs/CHANGELOG.rst b/source/isaaclab_contrib/docs/CHANGELOG.rst index ff3fa5a2a96a..24981d6deca6 100644 --- a/source/isaaclab_contrib/docs/CHANGELOG.rst +++ b/source/isaaclab_contrib/docs/CHANGELOG.rst @@ -1,6 +1,16 @@ Changelog --------- +0.3.2 (2026-05-12) +~~~~~~~~~~~~~~~~~~ + +Fixed +^^^^^ + +* Removed ``_patched_reset`` monkey-patch in RLinf extension; use + ``num_rerenders_on_reset`` env config instead. + + 0.3.1 (2026-05-09) ~~~~~~~~~~~~~~~~~~ diff --git a/source/isaaclab_experimental/changelog.d/scene-initialize-renderers.rst b/source/isaaclab_experimental/changelog.d/scene-initialize-renderers.rst deleted file mode 100644 index e33ce79b241e..000000000000 --- a/source/isaaclab_experimental/changelog.d/scene-initialize-renderers.rst +++ /dev/null @@ -1,10 +0,0 @@ -Changed -^^^^^^^ - -* Pre-create renderer backends in - :class:`~isaaclab_experimental.envs.ManagerBasedEnvWarp` and - :class:`~isaaclab_experimental.envs.DirectRLEnvWarp` by invoking - :meth:`~isaaclab.scene.InteractiveScene.initialize_renderers` after scene - construction so that renderer backend creation order is deterministic and - front-loaded before the first - :meth:`~isaaclab.sim.SimulationContext.reset`. diff --git a/source/isaaclab_experimental/config/extension.toml b/source/isaaclab_experimental/config/extension.toml index 9bcfc0753383..6e5bee6fb01b 100644 --- a/source/isaaclab_experimental/config/extension.toml +++ b/source/isaaclab_experimental/config/extension.toml @@ -1,7 +1,7 @@ [package] # Note: Semantic Versioning is used: https://semver.org/ -version = "0.0.3" +version = "0.0.4" # Description title = "Experimental playground for upcoming IsaacLab features" diff --git a/source/isaaclab_experimental/docs/CHANGELOG.rst b/source/isaaclab_experimental/docs/CHANGELOG.rst index 5f19d1fb8c5a..2131ff672994 100644 --- a/source/isaaclab_experimental/docs/CHANGELOG.rst +++ b/source/isaaclab_experimental/docs/CHANGELOG.rst @@ -1,6 +1,21 @@ Changelog --------- +0.0.4 (2026-05-12) +~~~~~~~~~~~~~~~~~~ + +Changed +^^^^^^^ + +* Pre-create renderer backends in + :class:`~isaaclab_experimental.envs.ManagerBasedEnvWarp` and + :class:`~isaaclab_experimental.envs.DirectRLEnvWarp` by invoking + :meth:`~isaaclab.scene.InteractiveScene.initialize_renderers` after scene + construction so that renderer backend creation order is deterministic and + front-loaded before the first + :meth:`~isaaclab.sim.SimulationContext.reset`. + + 0.0.3 (2026-04-27) ~~~~~~~~~~~~~~~~~~ diff --git a/source/isaaclab_newton/changelog.d/scene-initialize-renderers.rst b/source/isaaclab_newton/changelog.d/scene-initialize-renderers.rst deleted file mode 100644 index 80eef5e9823b..000000000000 --- a/source/isaaclab_newton/changelog.d/scene-initialize-renderers.rst +++ /dev/null @@ -1,9 +0,0 @@ -Changed -^^^^^^^ - -* Split :class:`~isaaclab_newton.renderers.NewtonWarpRenderer` construction - into a pre-physics ``__init__`` (stores cfg and registers the Newton-Warp - scene-data requirement on - :class:`~isaaclab.sim.SimulationContext`) and a post-physics - :meth:`~isaaclab_newton.renderers.NewtonWarpRenderer.initialize` (reads - the built Newton model. diff --git a/source/isaaclab_newton/changelog.d/vidur-add-newton-schemas.minor.rst b/source/isaaclab_newton/changelog.d/vidur-add-newton-schemas.minor.rst deleted file mode 100644 index 84eb5ce846a1..000000000000 --- a/source/isaaclab_newton/changelog.d/vidur-add-newton-schemas.minor.rst +++ /dev/null @@ -1,22 +0,0 @@ -Added -^^^^^ - -* Added :class:`~isaaclab_newton.sim.schemas.NewtonRigidBodyPropertiesCfg` and - :class:`~isaaclab_newton.sim.schemas.NewtonJointDrivePropertiesCfg` as Newton-targeted - bases for solver-specific subclasses. Currently empty (no Newton-native ``newton:*`` - rigid-body or joint-drive attributes today); reserved as the family root for any - future Newton-native fields. -* Added :class:`~isaaclab_newton.sim.schemas.MujocoRigidBodyPropertiesCfg` (subclasses - :class:`NewtonRigidBodyPropertiesCfg`) with :attr:`gravcomp` for body-level gravity - compensation (``mjc:gravcomp``). -* Added :class:`~isaaclab_newton.sim.schemas.MujocoJointDrivePropertiesCfg` (subclasses - :class:`NewtonJointDrivePropertiesCfg`) with :attr:`actuatorgravcomp` for joint-level - gravity compensation routing (``mjc:actuatorgravcomp`` via ``MjcJointAPI``). -* Added :class:`~isaaclab_newton.sim.schemas.NewtonCollisionPropertiesCfg` with - :attr:`contact_margin` and :attr:`contact_gap` (``newton:*`` via ``NewtonCollisionAPI``). -* Added :class:`~isaaclab_newton.sim.schemas.NewtonMeshCollisionPropertiesCfg` with - :attr:`max_hull_vertices` (``newton:maxHullVertices`` via ``NewtonMeshCollisionAPI``). -* Added :class:`~isaaclab_newton.sim.schemas.NewtonMaterialPropertiesCfg` with - :attr:`torsional_friction` and :attr:`rolling_friction` (``newton:*`` via ``NewtonMaterialAPI``). -* Added :class:`~isaaclab_newton.sim.schemas.NewtonArticulationRootPropertiesCfg` with - :attr:`self_collision_enabled` (``newton:selfCollisionEnabled`` via ``NewtonArticulationRootAPI``). diff --git a/source/isaaclab_newton/config/extension.toml b/source/isaaclab_newton/config/extension.toml index ee6aa21d379f..989e0b498dbf 100644 --- a/source/isaaclab_newton/config/extension.toml +++ b/source/isaaclab_newton/config/extension.toml @@ -1,7 +1,7 @@ [package] # Note: Semantic Versioning is used: https://semver.org/ -version = "0.7.2" +version = "0.8.0" # Description title = "Newton simulation interfaces for IsaacLab core package" diff --git a/source/isaaclab_newton/docs/CHANGELOG.rst b/source/isaaclab_newton/docs/CHANGELOG.rst index 7ed2a512d2e1..d841aa46d798 100644 --- a/source/isaaclab_newton/docs/CHANGELOG.rst +++ b/source/isaaclab_newton/docs/CHANGELOG.rst @@ -1,6 +1,43 @@ Changelog --------- +0.8.0 (2026-05-12) +~~~~~~~~~~~~~~~~~~ + +Added +^^^^^ + +* Added :class:`~isaaclab_newton.sim.schemas.NewtonRigidBodyPropertiesCfg` and + :class:`~isaaclab_newton.sim.schemas.NewtonJointDrivePropertiesCfg` as Newton-targeted + bases for solver-specific subclasses. Currently empty (no Newton-native ``newton:*`` + rigid-body or joint-drive attributes today); reserved as the family root for any + future Newton-native fields. +* Added :class:`~isaaclab_newton.sim.schemas.MujocoRigidBodyPropertiesCfg` (subclasses + :class:`NewtonRigidBodyPropertiesCfg`) with :attr:`gravcomp` for body-level gravity + compensation (``mjc:gravcomp``). +* Added :class:`~isaaclab_newton.sim.schemas.MujocoJointDrivePropertiesCfg` (subclasses + :class:`NewtonJointDrivePropertiesCfg`) with :attr:`actuatorgravcomp` for joint-level + gravity compensation routing (``mjc:actuatorgravcomp`` via ``MjcJointAPI``). +* Added :class:`~isaaclab_newton.sim.schemas.NewtonCollisionPropertiesCfg` with + :attr:`contact_margin` and :attr:`contact_gap` (``newton:*`` via ``NewtonCollisionAPI``). +* Added :class:`~isaaclab_newton.sim.schemas.NewtonMeshCollisionPropertiesCfg` with + :attr:`max_hull_vertices` (``newton:maxHullVertices`` via ``NewtonMeshCollisionAPI``). +* Added :class:`~isaaclab_newton.sim.schemas.NewtonMaterialPropertiesCfg` with + :attr:`torsional_friction` and :attr:`rolling_friction` (``newton:*`` via ``NewtonMaterialAPI``). +* Added :class:`~isaaclab_newton.sim.schemas.NewtonArticulationRootPropertiesCfg` with + :attr:`self_collision_enabled` (``newton:selfCollisionEnabled`` via ``NewtonArticulationRootAPI``). + +Changed +^^^^^^^ + +* Split :class:`~isaaclab_newton.renderers.NewtonWarpRenderer` construction + into a pre-physics ``__init__`` (stores cfg and registers the Newton-Warp + scene-data requirement on + :class:`~isaaclab.sim.SimulationContext`) and a post-physics + :meth:`~isaaclab_newton.renderers.NewtonWarpRenderer.initialize` (reads + the built Newton model. + + 0.7.2 (2026-05-11) ~~~~~~~~~~~~~~~~~~ diff --git a/source/isaaclab_ov/changelog.d/scene-initialize-renderers.rst b/source/isaaclab_ov/changelog.d/scene-initialize-renderers.rst deleted file mode 100644 index 61103b21d517..000000000000 --- a/source/isaaclab_ov/changelog.d/scene-initialize-renderers.rst +++ /dev/null @@ -1,20 +0,0 @@ -Changed -^^^^^^^ - -* Construct the underlying OVRTX ``Renderer`` in - :class:`~isaaclab_ov.renderers.OVRTXRenderer` ``__init__`` instead of - during :meth:`~isaaclab_ov.renderers.OVRTXRenderer.prepare_stage`. This - pairs with the new pre-physics ``__init__`` / - post-physics :meth:`~isaaclab.renderers.base_renderer.BaseRenderer.initialize` - lifecycle: when invoked eagerly via - :meth:`~isaaclab.scene.InteractiveScene.initialize_renderers`, the OVRTX - ``Renderer`` is created before - :meth:`~isaaclab.sim.SimulationContext.reset` (and therefore before - ovphysx initialises), which OVRTX 0.3 requires. -* Replaced an ``assert`` on the OVRTX ``Renderer`` construction with an - explicit :class:`RuntimeError` so the failure is reported even when - Python is run with ``-O``. -* Renamed the internal ``OVRTXRenderer.initialize(spec)`` helper to - ``_initialize_from_spec(spec)`` to avoid shadowing the new - no-arg :meth:`~isaaclab.renderers.base_renderer.BaseRenderer.initialize` - lifecycle hook. diff --git a/source/isaaclab_ov/config/extension.toml b/source/isaaclab_ov/config/extension.toml index 7bc51bfb5e75..c16250b01753 100644 --- a/source/isaaclab_ov/config/extension.toml +++ b/source/isaaclab_ov/config/extension.toml @@ -1,5 +1,5 @@ [package] -version = "0.1.6" +version = "0.1.7" title = "Omniverse renderers for IsaacLab" description = "Extension providing Omniverse renderers (OVRTX, ovphysx, etc.) for tiled camera rendering." readme = "docs/README.md" diff --git a/source/isaaclab_ov/docs/CHANGELOG.rst b/source/isaaclab_ov/docs/CHANGELOG.rst index d0ae068e08d9..f0962359544d 100644 --- a/source/isaaclab_ov/docs/CHANGELOG.rst +++ b/source/isaaclab_ov/docs/CHANGELOG.rst @@ -1,6 +1,31 @@ Changelog --------- +0.1.7 (2026-05-12) +~~~~~~~~~~~~~~~~~~ + +Changed +^^^^^^^ + +* Construct the underlying OVRTX ``Renderer`` in + :class:`~isaaclab_ov.renderers.OVRTXRenderer` ``__init__`` instead of + during :meth:`~isaaclab_ov.renderers.OVRTXRenderer.prepare_stage`. This + pairs with the new pre-physics ``__init__`` / + post-physics :meth:`~isaaclab.renderers.base_renderer.BaseRenderer.initialize` + lifecycle: when invoked eagerly via + :meth:`~isaaclab.scene.InteractiveScene.initialize_renderers`, the OVRTX + ``Renderer`` is created before + :meth:`~isaaclab.sim.SimulationContext.reset` (and therefore before + ovphysx initialises), which OVRTX 0.3 requires. +* Replaced an ``assert`` on the OVRTX ``Renderer`` construction with an + explicit :class:`RuntimeError` so the failure is reported even when + Python is run with ``-O``. +* Renamed the internal ``OVRTXRenderer.initialize(spec)`` helper to + ``_initialize_from_spec(spec)`` to avoid shadowing the new + no-arg :meth:`~isaaclab.renderers.base_renderer.BaseRenderer.initialize` + lifecycle hook. + + 0.1.6 (2026-05-09) ~~~~~~~~~~~~~~~~~~ diff --git a/source/isaaclab_tasks/changelog.d/Adds-Assemble-Trocar-task-Based-RLinf.rst b/source/isaaclab_tasks/changelog.d/Adds-Assemble-Trocar-task-Based-RLinf.rst deleted file mode 100644 index f5d918d3680f..000000000000 --- a/source/isaaclab_tasks/changelog.d/Adds-Assemble-Trocar-task-Based-RLinf.rst +++ /dev/null @@ -1,7 +0,0 @@ -Added -^^^^^ - -* Added ``Isaac-Assemble-Trocar-G129-Dex3-v0`` and - ``Isaac-Assemble-Trocar-G129-Dex3-Eval-v0`` manipulation tasks: a Unitree G1 - 29-DOF humanoid with Dex3 hands assembles a trocar from a tray, trained via - RL post-training of a VLA model using RLinf. diff --git a/source/isaaclab_tasks/config/extension.toml b/source/isaaclab_tasks/config/extension.toml index 486b9faccf4c..219e89c4eb28 100644 --- a/source/isaaclab_tasks/config/extension.toml +++ b/source/isaaclab_tasks/config/extension.toml @@ -1,7 +1,7 @@ [package] # Note: Semantic Versioning is used: https://semver.org/ -version = "1.5.36" +version = "1.5.37" # Description title = "Isaac Lab Environments" diff --git a/source/isaaclab_tasks/docs/CHANGELOG.rst b/source/isaaclab_tasks/docs/CHANGELOG.rst index 3638b0aa6910..6c3de163c11c 100644 --- a/source/isaaclab_tasks/docs/CHANGELOG.rst +++ b/source/isaaclab_tasks/docs/CHANGELOG.rst @@ -1,6 +1,18 @@ Changelog --------- +1.5.37 (2026-05-12) +~~~~~~~~~~~~~~~~~~~ + +Added +^^^^^ + +* Added ``Isaac-Assemble-Trocar-G129-Dex3-v0`` and + ``Isaac-Assemble-Trocar-G129-Dex3-Eval-v0`` manipulation tasks: a Unitree G1 + 29-DOF humanoid with Dex3 hands assembles a trocar from a tray, trained via + RL post-training of a VLA model using RLinf. + + 1.5.36 (2026-05-09) ~~~~~~~~~~~~~~~~~~~ diff --git a/source/isaaclab_teleop/changelog.d/hougantc-pipelined-retargeting.rst b/source/isaaclab_teleop/changelog.d/hougantc-pipelined-retargeting.rst deleted file mode 100644 index 2a58c6560fab..000000000000 --- a/source/isaaclab_teleop/changelog.d/hougantc-pipelined-retargeting.rst +++ /dev/null @@ -1,23 +0,0 @@ -Added -^^^^^ - -* Added :attr:`~isaaclab_teleop.IsaacTeleopCfg.retargeting_execution` for - configuring IsaacTeleop retargeting execution mode from Isaac Lab. - -Changed -^^^^^^^ - -* Changed :class:`~isaaclab_teleop.IsaacTeleopCfg` to enable IsaacTeleop - deadline-paced pipelined retargeting by default. This returns the latest - completed retargeting output while the current frame is submitted, using - ``DeadlinePacingConfig(safety_margin_s=0.025)`` to sample close to the next - simulation consumption point and stagger IsaacTeleop's Python work behind - Isaac Lab's step Python. Set - ``retargeting_execution=RetargetingExecutionConfig(mode="sync")`` to restore - exact current-frame retargeting. - -Fixed -^^^^^ - -* Fixed installation to upgrade to the latest compatible ``isaacteleop`` - package when installing ``isaaclab_teleop``. diff --git a/source/isaaclab_teleop/config/extension.toml b/source/isaaclab_teleop/config/extension.toml index 9fd1742d243f..876f53ffd43c 100644 --- a/source/isaaclab_teleop/config/extension.toml +++ b/source/isaaclab_teleop/config/extension.toml @@ -1,6 +1,6 @@ [package] # Semantic Versioning is used: https://semver.org/ -version = "0.3.10" +version = "0.3.11" # Description title = "Isaac Lab Teleop" diff --git a/source/isaaclab_teleop/docs/CHANGELOG.rst b/source/isaaclab_teleop/docs/CHANGELOG.rst index 01465486d63e..295bc656a903 100644 --- a/source/isaaclab_teleop/docs/CHANGELOG.rst +++ b/source/isaaclab_teleop/docs/CHANGELOG.rst @@ -1,6 +1,34 @@ Changelog --------- +0.3.11 (2026-05-12) +~~~~~~~~~~~~~~~~~~~ + +Added +^^^^^ + +* Added :attr:`~isaaclab_teleop.IsaacTeleopCfg.retargeting_execution` for + configuring IsaacTeleop retargeting execution mode from Isaac Lab. + +Changed +^^^^^^^ + +* Changed :class:`~isaaclab_teleop.IsaacTeleopCfg` to enable IsaacTeleop + deadline-paced pipelined retargeting by default. This returns the latest + completed retargeting output while the current frame is submitted, using + ``DeadlinePacingConfig(safety_margin_s=0.025)`` to sample close to the next + simulation consumption point and stagger IsaacTeleop's Python work behind + Isaac Lab's step Python. Set + ``retargeting_execution=RetargetingExecutionConfig(mode="sync")`` to restore + exact current-frame retargeting. + +Fixed +^^^^^ + +* Fixed installation to upgrade to the latest compatible ``isaacteleop`` + package when installing ``isaaclab_teleop``. + + 0.3.10 (2026-05-08) ~~~~~~~~~~~~~~~~~~~ From ad672afe5c48b89ef9082e6637c4e492d81360e5 Mon Sep 17 00:00:00 2001 From: Peter Verswyvelen Date: Thu, 7 May 2026 11:27:48 +0000 Subject: [PATCH 42/51] Implement Fabric-aware get/set_local_poses via indexedfabricarray MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Replaces the earlier Python-based parent-loop implementation (which was correct but ~3× slower than USD for local poses) with a fully GPU-side Fabric path that follows the bareya/pbarejko/camera-update prototype: * Three persistent ``PrimSelection`` instances differing only in per-attribute access mode — one each for {trans_ro, world_rw, local_rw}. * Path-based view → fabric index mapping computed once from ``selection.GetPaths()`` and stored as a Warp ``int32`` array. No custom prim attributes are written to the stage. * All transform reads and writes go through ``wp.indexedfabricarray``, so the kernels just dereference ``ifa[view_index]`` instead of taking a separate mapping argument. * Stage-level ``IFabricHierarchy`` cache and dirty-stages set so multiple ``FabricFrameView`` instances on the same stage share state. World ↔ local consistency is preserved through Warp kernels that run on the affected write paths: * ``set_local_poses`` writes ``omni:fabric:localMatrix`` directly via the compose kernel, then a second kernel recomputes child worldMatrix from ``parent_world * child_local`` so the next ``get_world_poses`` read is consistent. ``IFabricHierarchy.update_world_xforms()`` is *not* used for this — in practice it re-reads USD's authored xformOps and would overwrite the matrices we just authored. * ``set_world_poses`` mirrors the above, recomputing ``child_local = inv(parent_world) * child_world`` after the write. Two new public Warp kernels in ``isaaclab.utils.warp.fabric``: * ``decompose_indexed_fabric_transforms`` / ``compose_indexed_fabric_transforms`` — indexed-array variants of the existing decompose/compose kernels. * ``update_indexed_local_matrix_from_world`` / ``update_indexed_world_matrix_from_local`` — propagate one direction using a parent indexed fabric array. Implemented directly in storage convention (``local = world * inv(parent)``, ``world = local * parent``) — the four transposes the math-convention form would imply cancel out under ``(A·B)^T = B^T·A^T``. Benchmark (1024 prims, 50 iterations, RTX A6000): Operation USD (ms) Fabric (ms) Speedup Get World Poses 12.33 0.044 282× Set World Poses 27.98 0.117 240× Interleaved Set→Get 41.34 0.160 258× Get Local Poses 6.04 0.037 162× Set Local Poses 8.54 0.053 162× Local-pose ops went from ~3× slower than USD (in the earlier torch-based parent-loop implementation) to ~160× faster, with the new Fabric-side localMatrix authoring keeping ``test_set_world_updates_local`` passing without an xfail override. Tests: 41 passed in the Fabric backend's contract + new coverage for the Fabric-native ``set_local_poses``, ``get_scales``, and topology rebuild paths. Drops the no-longer-needed ``cd571d482`` Python-loop attempt. --- .../benchmarks/benchmark_view_comparison.py | 60 +- .../changelog.d/fix-fabric-local-matrix.rst | 18 + source/isaaclab/isaaclab/utils/warp/fabric.py | 172 +++++ .../changelog.d/fix-fabric-local-matrix.rst | 24 + .../sim/views/fabric_frame_view.py | 687 ++++++++++++------ .../test/sim/test_views_xform_prim_fabric.py | 138 ++-- 6 files changed, 837 insertions(+), 262 deletions(-) create mode 100644 source/isaaclab/changelog.d/fix-fabric-local-matrix.rst create mode 100644 source/isaaclab_physx/changelog.d/fix-fabric-local-matrix.rst diff --git a/scripts/benchmarks/benchmark_view_comparison.py b/scripts/benchmarks/benchmark_view_comparison.py index a637f687803e..80051f555d78 100644 --- a/scripts/benchmarks/benchmark_view_comparison.py +++ b/scripts/benchmarks/benchmark_view_comparison.py @@ -271,26 +271,71 @@ def _run_pose_benchmarks( positions: wp.array, orientations: wp.array, ): - """Shared benchmark loop for get/set world poses on any FrameView.""" + """Shared benchmark loop for get/set {world,local} poses on any FrameView.""" + + # FrameView getters now return ProxyArray; older callers worked with wp.array + # directly. Support both transparently. + def _as_wp(a): + return a.warp if hasattr(a, "warp") else a + + positions_wp = _as_wp(positions) + orientations_wp = _as_wp(orientations) + start_time = time.perf_counter() for _ in range(num_iterations): view.get_world_poses() timing_results["get_world_poses"] = (time.perf_counter() - start_time) / num_iterations - new_positions = wp.clone(positions) + new_positions = wp.clone(positions_wp) new_positions_t = wp.to_torch(new_positions) new_positions_t[:, 2] += 0.5 expected_positions = new_positions_t.clone() start_time = time.perf_counter() for _ in range(num_iterations): - view.set_world_poses(new_positions, orientations) + view.set_world_poses(new_positions, orientations_wp) timing_results["set_world_poses"] = (time.perf_counter() - start_time) / num_iterations + # Interleaved set→get on world poses — the realistic write/read pattern for + # downstream consumers (e.g. cameras updating their pose then immediately + # querying it). + start_time = time.perf_counter() + for _ in range(num_iterations): + view.set_world_poses(new_positions, orientations_wp) + view.get_world_poses() + timing_results["interleaved_world"] = (time.perf_counter() - start_time) / num_iterations + + # Local poses — Fabric-aware path on FabricFrameView, USD path otherwise. + if hasattr(view, "get_local_poses"): + start_time = time.perf_counter() + for _ in range(num_iterations): + view.get_local_poses() + timing_results["get_local_poses"] = (time.perf_counter() - start_time) / num_iterations + + if hasattr(view, "set_local_poses"): + local_pos, local_ori = view.get_local_poses() + local_pos_t = ( + local_pos.torch + if hasattr(local_pos, "torch") + else (wp.to_torch(local_pos) if isinstance(local_pos, wp.array) else local_pos) + ) + local_ori_t = ( + local_ori.torch + if hasattr(local_ori, "torch") + else (wp.to_torch(local_ori) if isinstance(local_ori, wp.array) else local_ori) + ) + new_local_pos = wp.from_torch(local_pos_t.clone().contiguous()) + new_local_ori = wp.from_torch(local_ori_t.clone().contiguous()) + + start_time = time.perf_counter() + for _ in range(num_iterations): + view.set_local_poses(translations=new_local_pos, orientations=new_local_ori) + timing_results["set_local_poses"] = (time.perf_counter() - start_time) / num_iterations + ret_pos, ret_quat = view.get_world_poses() - ret_pos_t = wp.to_torch(ret_pos) - ret_quat_t = wp.to_torch(ret_quat) - ori_t = wp.to_torch(orientations) + ret_pos_t = ret_pos.torch if hasattr(ret_pos, "torch") else wp.to_torch(ret_pos) + ret_quat_t = ret_quat.torch if hasattr(ret_quat, "torch") else wp.to_torch(ret_quat) + ori_t = wp.to_torch(orientations_wp) pos_ok = torch.allclose(ret_pos_t, expected_positions, atol=1e-4, rtol=0) quat_ok = torch.allclose(ret_quat_t, ori_t, atol=1e-4, rtol=0) @@ -327,6 +372,9 @@ def print_results(results_dict: dict[str, dict[str, float]], num_prims: int, num ("Initialization", "init"), ("Get World Poses", "get_world_poses"), ("Set World Poses", "set_world_poses"), + ("Interleaved Set->Get", "interleaved_world"), + ("Get Local Poses", "get_local_poses"), + ("Set Local Poses", "set_local_poses"), ] for op_name, op_key in operations: diff --git a/source/isaaclab/changelog.d/fix-fabric-local-matrix.rst b/source/isaaclab/changelog.d/fix-fabric-local-matrix.rst new file mode 100644 index 000000000000..e3c6cc22ba5c --- /dev/null +++ b/source/isaaclab/changelog.d/fix-fabric-local-matrix.rst @@ -0,0 +1,18 @@ +Added +^^^^^ + +* Added :func:`~isaaclab.utils.warp.fabric.decompose_indexed_fabric_transforms` + and :func:`~isaaclab.utils.warp.fabric.compose_indexed_fabric_transforms` + Warp kernels. They mirror the existing + ``decompose_fabric_transformation_matrix_to_warp_arrays`` / + ``compose_fabric_transformation_matrix_from_warp_arrays`` kernels but + operate on :class:`wp.indexedfabricarray`, so the view-to-fabric mapping + is baked into the array and the kernel just dereferences + ``ifa[view_index]`` instead of taking a separate ``mapping`` argument. +* Added :func:`~isaaclab.utils.warp.fabric.update_indexed_local_matrix_from_world` + and :func:`~isaaclab.utils.warp.fabric.update_indexed_world_matrix_from_local` + Warp kernels that propagate ``local = world * inv(parent)`` and + ``world = local * parent`` directly on Fabric storage matrices (no + explicit transposes). Used by + :class:`~isaaclab_physx.sim.views.FabricFrameView` to keep child world and + local matrices consistent across writes without round-tripping through USD. diff --git a/source/isaaclab/isaaclab/utils/warp/fabric.py b/source/isaaclab/isaaclab/utils/warp/fabric.py index a48f773f4991..bcf65fc02ae9 100644 --- a/source/isaaclab/isaaclab/utils/warp/fabric.py +++ b/source/isaaclab/isaaclab/utils/warp/fabric.py @@ -18,12 +18,14 @@ if TYPE_CHECKING: FabricArrayUInt32 = Any FabricArrayMat44d = Any + IndexedFabricArrayMat44d = Any ArrayUInt32 = Any ArrayUInt32_1d = Any ArrayFloat32_2d = Any else: FabricArrayUInt32 = wp.fabricarray(dtype=wp.uint32) FabricArrayMat44d = wp.fabricarray(dtype=wp.mat44d) + IndexedFabricArrayMat44d = wp.indexedfabricarray(dtype=wp.mat44d) ArrayUInt32 = wp.array(ndim=1, dtype=wp.uint32) ArrayUInt32_1d = wp.array(dtype=wp.uint32) ArrayFloat32_2d = wp.array(ndim=2, dtype=wp.float32) @@ -163,6 +165,176 @@ def compose_fabric_transformation_matrix_from_warp_arrays( ) +@wp.kernel(enable_backward=False) +def decompose_indexed_fabric_transforms( + fabric_matrices: IndexedFabricArrayMat44d, + array_positions: ArrayFloat32_2d, + array_orientations: ArrayFloat32_2d, + array_scales: ArrayFloat32_2d, + indices: ArrayUInt32, +): + """Decompose indexed Fabric transformation matrices into position, orientation, and scale. + + Like :func:`decompose_fabric_transformation_matrix_to_warp_arrays` but operates on a + :class:`wp.indexedfabricarray` that already encodes the view-to-fabric mapping, removing + the need for a separate ``mapping`` array. + + Args: + fabric_matrices: Indexed fabric array containing 4x4 transformation matrices. + array_positions: Output array for positions [m], shape (N, 3). + array_orientations: Output array for quaternions in xyzw format, shape (N, 4). + array_scales: Output array for scales, shape (N, 3). + indices: View indices to process (subset selection). + """ + output_index = wp.tid() + view_index = indices[output_index] + + position, rotation, scale = _decompose_transformation_matrix(wp.mat44f(fabric_matrices[view_index])) + + if array_positions.shape[0] > 0: + array_positions[output_index, 0] = position[0] + array_positions[output_index, 1] = position[1] + array_positions[output_index, 2] = position[2] + if array_orientations.shape[0] > 0: + array_orientations[output_index, 0] = rotation[0] + array_orientations[output_index, 1] = rotation[1] + array_orientations[output_index, 2] = rotation[2] + array_orientations[output_index, 3] = rotation[3] + if array_scales.shape[0] > 0: + array_scales[output_index, 0] = scale[0] + array_scales[output_index, 1] = scale[1] + array_scales[output_index, 2] = scale[2] + + +@wp.kernel(enable_backward=False) +def compose_indexed_fabric_transforms( + fabric_matrices: IndexedFabricArrayMat44d, + array_positions: ArrayFloat32_2d, + array_orientations: ArrayFloat32_2d, + array_scales: ArrayFloat32_2d, + broadcast_positions: bool, + broadcast_orientations: bool, + broadcast_scales: bool, + indices: ArrayUInt32, +): + """Compose indexed Fabric transformation matrices from position, orientation, and scale. + + Like :func:`compose_fabric_transformation_matrix_from_warp_arrays` but operates on a + :class:`wp.indexedfabricarray` that already encodes the view-to-fabric mapping, removing + the need for a separate ``mapping`` array. + + Args: + fabric_matrices: Indexed fabric array containing 4x4 transformation matrices to update. + array_positions: Input array for positions [m], shape (N, 3). + array_orientations: Input array for quaternions in xyzw format, shape (N, 4). + array_scales: Input array for scales, shape (N, 3). + broadcast_positions: If True, use first position for all prims. + broadcast_orientations: If True, use first orientation for all prims. + broadcast_scales: If True, use first scale for all prims. + indices: View indices to process (subset selection). + """ + i = wp.tid() + view_index = indices[i] + position, rotation, scale = _decompose_transformation_matrix(wp.mat44f(fabric_matrices[view_index])) + + if array_positions.shape[0] > 0: + if broadcast_positions: + index = 0 + else: + index = i + position[0] = array_positions[index, 0] + position[1] = array_positions[index, 1] + position[2] = array_positions[index, 2] + if array_orientations.shape[0] > 0: + if broadcast_orientations: + index = 0 + else: + index = i + rotation[0] = array_orientations[index, 0] + rotation[1] = array_orientations[index, 1] + rotation[2] = array_orientations[index, 2] + rotation[3] = array_orientations[index, 3] + if array_scales.shape[0] > 0: + if broadcast_scales: + index = 0 + else: + index = i + scale[0] = array_scales[index, 0] + scale[1] = array_scales[index, 1] + scale[2] = array_scales[index, 2] + + fabric_matrices[view_index] = wp.mat44d( # type: ignore[arg-type] + wp.transpose(wp.transform_compose(position, rotation, scale)) # type: ignore[arg-type] + ) + + +@wp.kernel(enable_backward=False) +def update_indexed_local_matrix_from_world( + child_world_matrices: IndexedFabricArrayMat44d, + parent_world_matrices: IndexedFabricArrayMat44d, + child_local_matrices: IndexedFabricArrayMat44d, + indices: ArrayUInt32, +): + """Recompute child localMatrix from (parent worldMatrix, child worldMatrix). + + Computes ``child_local = inv(parent_world) * child_world`` per prim and writes the + result back to the child's :data:`omni:fabric:localMatrix` so that subsequent + ``get_local_poses`` calls see consistent values after a world-pose write. + + All three indexed arrays are expected to be indexed by the same per-view indices + (i.e. ``view_to_child_fabric``, ``view_to_parent_fabric``, ``view_to_child_fabric``) + so the kernel only needs the view-side indices. + + Storage convention: Fabric matrices are stored as the transpose of the standard + column-major math convention. Math is ``local = inv(parent) * world``; under + the transpose identity ``(A * B)^T = B^T * A^T`` (and ``inv(A^T) = inv(A)^T``) + that is equivalent to storage-side ``local^T = world^T * inv(parent^T)``, so we + can compute it directly on the stored matrices without explicit transposes. + + Args: + child_world_matrices: Indexed fabric array of child world matrices (read). + parent_world_matrices: Indexed fabric array of parent world matrices (read). + child_local_matrices: Indexed fabric array of child local matrices (written). + indices: View indices to process. + """ + i = wp.tid() + view_index = indices[i] + child_world = wp.mat44f(child_world_matrices[view_index]) + parent_world = wp.mat44f(parent_world_matrices[view_index]) + child_local_matrices[view_index] = wp.mat44d(child_world * wp.inverse(parent_world)) # type: ignore[arg-type] + + +@wp.kernel(enable_backward=False) +def update_indexed_world_matrix_from_local( + child_local_matrices: IndexedFabricArrayMat44d, + parent_world_matrices: IndexedFabricArrayMat44d, + child_world_matrices: IndexedFabricArrayMat44d, + indices: ArrayUInt32, +): + """Recompute child worldMatrix from (parent worldMatrix, child localMatrix). + + Computes ``child_world = parent_world * child_local`` per prim and writes the + result back to the child's :data:`omni:fabric:worldMatrix`. Used after a + ``set_local_poses`` write so that subsequent ``get_world_poses`` calls see + consistent values. Mirror of :func:`update_indexed_local_matrix_from_world`. + + Args: + child_local_matrices: Indexed fabric array of child local matrices (read). + parent_world_matrices: Indexed fabric array of parent world matrices (read). + child_world_matrices: Indexed fabric array of child world matrices (written). + indices: View indices to process. + + Storage convention: same as :func:`update_indexed_local_matrix_from_world`. + Math is ``world = parent * local``; under the transpose identity that becomes + storage-side ``world^T = local^T * parent^T``, no explicit transposes needed. + """ + i = wp.tid() + view_index = indices[i] + child_local = wp.mat44f(child_local_matrices[view_index]) + parent_world = wp.mat44f(parent_world_matrices[view_index]) + child_world_matrices[view_index] = wp.mat44d(child_local * parent_world) # type: ignore[arg-type] + + @wp.func def _decompose_transformation_matrix(m: Any): # -> tuple[wp.vec3f, wp.quatf, wp.vec3f] """Decompose a 4x4 transformation matrix into position, orientation, and scale. diff --git a/source/isaaclab_physx/changelog.d/fix-fabric-local-matrix.rst b/source/isaaclab_physx/changelog.d/fix-fabric-local-matrix.rst new file mode 100644 index 000000000000..43f2eaae0ee7 --- /dev/null +++ b/source/isaaclab_physx/changelog.d/fix-fabric-local-matrix.rst @@ -0,0 +1,24 @@ +Fixed +^^^^^ + +* Fixed :meth:`~isaaclab_physx.sim.views.FabricFrameView.get_local_poses` + returning stale USD values after Fabric world-pose writes. Local poses + are now read directly from Fabric's ``omni:fabric:localMatrix`` via + :class:`wp.indexedfabricarray`, and are kept consistent with worldMatrix + through Warp kernels that propagate either direction on writes. + +Changed +^^^^^^^ + +* Reworked :class:`~isaaclab_physx.sim.views.FabricFrameView` to use three + persistent ``PrimSelection`` instances (one per access mode), path-based + view → fabric index mapping (no custom prim attributes), and Warp kernels + that operate on :class:`wp.indexedfabricarray` so the kernels just index + ``ifa[view_index]`` instead of taking a separate mapping array. +* :meth:`~isaaclab_physx.sim.views.FabricFrameView.set_local_poses` now + writes ``omni:fabric:localMatrix`` directly through Fabric. The next + ``get_world_poses`` runs a Warp kernel that recomputes + ``child_world = parent_world * child_local``. Symmetrically, + ``set_world_poses`` runs a kernel that recomputes + ``child_local = inv(parent_world) * child_world`` so subsequent + ``get_local_poses`` calls return consistent values. diff --git a/source/isaaclab_physx/isaaclab_physx/sim/views/fabric_frame_view.py b/source/isaaclab_physx/isaaclab_physx/sim/views/fabric_frame_view.py index 1bcff86d57ac..633c0436d061 100644 --- a/source/isaaclab_physx/isaaclab_physx/sim/views/fabric_frame_view.py +++ b/source/isaaclab_physx/isaaclab_physx/sim/views/fabric_frame_view.py @@ -3,7 +3,27 @@ # # SPDX-License-Identifier: BSD-3-Clause -"""PhysX FrameView with Fabric GPU acceleration.""" +"""PhysX FrameView with Fabric GPU acceleration. + +Design follows the prototype in +``https://github.com/bareya/IsaacLab/tree/pbarejko/camera-update``: + +* Three persistent ``PrimSelection`` instances differing only in per-attribute access + mode (one for each of {trans_ro, world_rw, local_rw}). +* ``omni:fabric:localMatrix`` is read/written directly — no software composition of + ``inv(parent_world) * child_world`` for ``get_local_poses``/``set_local_poses``. +* View → Fabric index mapping is an integer Warp array computed from the selection's + ordered path list (``selection.GetPaths()``); no custom attributes are written to + prims. +* Read/write happens via ``wp.indexedfabricarray``, so the view-to-fabric mapping is + baked into the array itself and the kernels just dereference ``ifa[view_index]``. +* World ↔ local consistency is maintained: + - After ``set_local_poses``: stage is marked dirty; the next world read calls + ``IFabricHierarchy.update_world_xforms()`` to propagate local → world. + - After ``set_world_poses``: a Warp kernel recomputes child localMatrix from + parent worldMatrix on the fly using a parent indexed fabric array, so the + next ``get_local_poses`` returns consistent values. +""" from __future__ import annotations @@ -12,7 +32,7 @@ import torch import warp as wp -from pxr import Usd +from pxr import Usd, UsdGeom import isaaclab.sim as sim_utils from isaaclab.app.settings_manager import SettingsManager @@ -23,19 +43,18 @@ logger = logging.getLogger(__name__) -# TODO: extend this to ``cuda:N`` once we wire up multi-GPU support for the view. -# Recent Kit / USDRT releases do support multi-GPU ``SelectPrims``, but the -# rest of the FabricFrameView wiring (selections, indexed arrays, etc.) still -# assumes a single device — to be tackled in a follow-up. +# TODO: USDRT SelectPrims still pins to cuda:0 even when ``device='cuda:1'`` is +# requested. When that limitation is lifted (see feat/frame-view-enable-mgpu), +# this allowlist can drop the explicit cuda:0 entry. _fabric_supported_devices = ("cpu", "cuda", "cuda:0") def _to_float32_2d(a: wp.array | torch.Tensor) -> wp.array | torch.Tensor: - """Ensure array is compatible with Fabric kernels (2-D float32). + """Ensure ``wp.array`` inputs are 2-D ``float32`` for the Fabric kernels. - For ``wp.array`` with vec dtypes (``vec3f``, ``vec4f``), uses - :meth:`wp.array.view` for zero-copy reinterpretation. - ``torch.Tensor`` and already-correct 2-D float32 arrays pass through. + For ``wp.array`` with vec dtypes (``vec3f``, ``vec4f``) this uses + :meth:`wp.array.view` for zero-copy reinterpretation. ``torch.Tensor`` + and already-correct 2-D float32 arrays pass through. """ if not isinstance(a, wp.array): return a @@ -49,23 +68,26 @@ def _to_float32_2d(a: wp.array | torch.Tensor) -> wp.array | torch.Tensor: class FabricFrameView(BaseFrameView): """FrameView with Fabric GPU acceleration for the PhysX backend. - Uses composition: holds a :class:`UsdFrameView` internally for USD - fallback and non-accelerated operations (local poses, visibility, scales - when Fabric is disabled). + Holds a :class:`UsdFrameView` internally for the disabled-Fabric fallback path + (when ``/physics/fabricEnabled`` is false or the device is unsupported). - When Fabric is enabled, world-pose and scale operations use Warp kernels - operating on ``omni:fabric:worldMatrix``. All other operations delegate - to the internal USD view. + When Fabric is enabled, all transform reads and writes go through Warp kernels + operating on Fabric ``omni:fabric:worldMatrix`` and ``omni:fabric:localMatrix`` + via :class:`wp.indexedfabricarray`. No prim attributes are added. - After every Fabric write (``set_world_poses``, ``set_scales``), - :meth:`PrepareForReuse` is called on the ``PrimSelection`` to notify - the FSD renderer that Fabric data has changed and to detect topology - changes that require rebuilding internal mappings. Read operations - do not call PrepareForReuse to avoid unnecessary renderer invalidation. - - Pose getters return :class:`~isaaclab.utils.warp.ProxyArray`. Setters accept ``wp.array``. + Pose getters return :class:`~isaaclab.utils.warp.ProxyArray`. Setters accept + ``wp.array``. """ + _WORLD_MATRIX_NAME = "omni:fabric:worldMatrix" + _LOCAL_MATRIX_NAME = "omni:fabric:localMatrix" + + # Stage-level shared state. Multiple FabricFrameView instances on the same stage + # share one IFabricHierarchy handle; the dirty-stages set tracks which stages + # need ``update_world_xforms()`` before a world read. + _hierarchy_cache: dict[int, object] = {} + _dirty_stages: set[int] = set() + def __init__( self, prim_path: str, @@ -74,18 +96,6 @@ def __init__( stage: Usd.Stage | None = None, **kwargs, ): - """Initialize the view. - - Args: - prim_path: USD prim-path pattern to match. - device: Device for Warp arrays (``"cpu"`` or ``"cuda:0"``). - validate_xform_ops: Whether to validate prim xform-ops. - stage: USD stage; defaults to the current sim context's stage. - **kwargs: Additional keyword arguments (ignored). Matches the signature of - :class:`~isaaclab.sim.views.UsdFrameView` so that the top-level - :class:`~isaaclab.sim.views.FrameView` factory can forward backend-agnostic - kwargs without each backend having to know about every option. - """ self._usd_view = UsdFrameView(prim_path, device=device, validate_xform_ops=validate_xform_ops, stage=stage) self._device = device @@ -101,14 +111,27 @@ def __init__( ) self._use_fabric = False + # Fabric state — all populated lazily in :meth:`_initialize_fabric`. self._fabric_initialized = False - self._fabric_usd_sync_done = False - self._fabric_selection = None - self._fabric_to_view: wp.array | None = None - self._view_to_fabric: wp.array | None = None - self._default_view_indices: wp.array | None = None + self._stage_id: int | None = None + self._stage = None self._fabric_hierarchy = None - self._view_index_attr = f"isaaclab:view_index:{abs(hash(self))}" + # Selections. + self._trans_sel_ro = None + self._world_sel_rw = None + self._local_sel_rw = None + # Index arrays (view-side indices and view→fabric mappings). + self._view_indices: wp.array | None = None + self._fabric_indices: wp.array | None = None + self._parent_fabric_indices: wp.array | None = None + # Indexed fabric arrays. + self._world_ifa_ro = None + self._local_ifa_ro = None + self._world_ifa_rw = None + self._local_ifa_rw = None + self._parent_world_ifa_ro = None + # Cached output buffers. + self._fabric_dummy_buffer: wp.array | None = None # ------------------------------------------------------------------ # Delegated properties @@ -142,7 +165,7 @@ def set_visibility(self, visibility, indices=None): self._usd_view.set_visibility(visibility, indices) # ------------------------------------------------------------------ - # World poses — Fabric-accelerated or USD fallback + # World poses # ------------------------------------------------------------------ def set_world_poses(self, positions=None, orientations=None, indices=None): @@ -153,39 +176,33 @@ def set_world_poses(self, positions=None, orientations=None, indices=None): if not self._fabric_initialized: self._initialize_fabric() - self._prepare_for_reuse() + # If a prior set_local_poses left worldMatrix stale, propagate local → world first. + self._sync_world_from_local_if_dirty() indices_wp = self._resolve_indices_wp(indices) - count = indices_wp.shape[0] - - dummy = wp.zeros((0, 3), dtype=wp.float32, device=self._device) - positions_wp = _to_float32_2d(positions) if positions is not None else dummy - orientations_wp = ( - _to_float32_2d(orientations) - if orientations is not None - else wp.zeros((0, 4), dtype=wp.float32, device=self._device) - ) + positions_wp = _to_float32_2d(positions) if positions is not None else self._fabric_dummy_buffer + orientations_wp = _to_float32_2d(orientations) if orientations is not None else self._fabric_dummy_buffer wp.launch( - kernel=fabric_utils.compose_fabric_transformation_matrix_from_warp_arrays, - dim=count, + kernel=fabric_utils.compose_indexed_fabric_transforms, + dim=indices_wp.shape[0], inputs=[ - self._fabric_world_matrices, + self._get_world_rw_array(), positions_wp, orientations_wp, - dummy, + self._fabric_dummy_buffer, False, False, False, indices_wp, - self._view_to_fabric, ], - device=self._fabric_device, + device=self._device, ) wp.synchronize() - self._fabric_hierarchy.update_world_xforms() - self._fabric_usd_sync_done = True + # World was just written — recompute child localMatrix from parent worldMatrix + # so the next get_local_poses returns consistent values. + self._sync_local_from_world(indices_wp) def get_world_poses(self, indices: wp.array | None = None) -> tuple[ProxyArray, ProxyArray]: if not self._use_fabric: @@ -193,8 +210,9 @@ def get_world_poses(self, indices: wp.array | None = None) -> tuple[ProxyArray, if not self._fabric_initialized: self._initialize_fabric() - if not self._fabric_usd_sync_done: - self._sync_fabric_from_usd_once() + + # If a prior set_local_poses left worldMatrix stale, propagate local → world first. + self._sync_world_from_local_if_dirty() indices_wp = self._resolve_indices_wp(indices) count = indices_wp.shape[0] @@ -208,17 +226,16 @@ def get_world_poses(self, indices: wp.array | None = None) -> tuple[ProxyArray, orientations_wp = wp.zeros((count, 4), dtype=wp.float32, device=self._device) wp.launch( - kernel=fabric_utils.decompose_fabric_transformation_matrix_to_warp_arrays, + kernel=fabric_utils.decompose_indexed_fabric_transforms, dim=count, inputs=[ - self._fabric_world_matrices, + self._get_world_ro_array(), positions_wp, orientations_wp, self._fabric_dummy_buffer, indices_wp, - self._view_to_fabric, ], - device=self._fabric_device, + device=self._device, ) if use_cached: @@ -227,17 +244,79 @@ def get_world_poses(self, indices: wp.array | None = None) -> tuple[ProxyArray, return ProxyArray(positions_wp), ProxyArray(orientations_wp) # ------------------------------------------------------------------ - # Local poses — USD fallback (Fabric only accelerates world poses) + # Local poses # ------------------------------------------------------------------ def set_local_poses(self, translations=None, orientations=None, indices=None): - self._usd_view.set_local_poses(translations, orientations, indices) + if not self._use_fabric: + self._usd_view.set_local_poses(translations, orientations, indices) + return + + if not self._fabric_initialized: + self._initialize_fabric() + + indices_wp = self._resolve_indices_wp(indices) + translations_wp = _to_float32_2d(translations) if translations is not None else self._fabric_dummy_buffer + orientations_wp = _to_float32_2d(orientations) if orientations is not None else self._fabric_dummy_buffer + + wp.launch( + kernel=fabric_utils.compose_indexed_fabric_transforms, + dim=indices_wp.shape[0], + inputs=[ + self._get_local_rw_array(), + translations_wp, + orientations_wp, + self._fabric_dummy_buffer, + False, + False, + False, + indices_wp, + ], + device=self._device, + ) + wp.synchronize() + + # Mark the stage dirty so the next world read calls update_world_xforms(). + FabricFrameView._dirty_stages.add(self._stage_id) def get_local_poses(self, indices: wp.array | None = None) -> tuple[ProxyArray, ProxyArray]: - return self._usd_view.get_local_poses(indices) + if not self._use_fabric: + return self._usd_view.get_local_poses(indices) + + if not self._fabric_initialized: + self._initialize_fabric() + + indices_wp = self._resolve_indices_wp(indices) + count = indices_wp.shape[0] + + use_cached = indices is None or indices == slice(None) + if use_cached: + translations_wp = self._fabric_local_translations_buf + orientations_wp = self._fabric_local_orientations_buf + else: + translations_wp = wp.zeros((count, 3), dtype=wp.float32, device=self._device) + orientations_wp = wp.zeros((count, 4), dtype=wp.float32, device=self._device) + + wp.launch( + kernel=fabric_utils.decompose_indexed_fabric_transforms, + dim=count, + inputs=[ + self._get_local_ro_array(), + translations_wp, + orientations_wp, + self._fabric_dummy_buffer, + indices_wp, + ], + device=self._device, + ) + + if use_cached: + wp.synchronize() + return self._fabric_local_translations_ta, self._fabric_local_orientations_ta + return ProxyArray(translations_wp), ProxyArray(orientations_wp) # ------------------------------------------------------------------ - # Scales — Fabric-accelerated or USD fallback + # Scales # ------------------------------------------------------------------ def set_scales(self, scales, indices=None): @@ -248,44 +327,38 @@ def set_scales(self, scales, indices=None): if not self._fabric_initialized: self._initialize_fabric() - self._prepare_for_reuse() + # Sync world matrices first if local writes are pending. + self._sync_world_from_local_if_dirty() indices_wp = self._resolve_indices_wp(indices) - count = indices_wp.shape[0] - - dummy3 = wp.zeros((0, 3), dtype=wp.float32, device=self._device) - dummy4 = wp.zeros((0, 4), dtype=wp.float32, device=self._device) - scales_wp = _to_float32_2d(scales) + scales_wp = _to_float32_2d(scales) if scales is not None else self._fabric_dummy_buffer wp.launch( - kernel=fabric_utils.compose_fabric_transformation_matrix_from_warp_arrays, - dim=count, + kernel=fabric_utils.compose_indexed_fabric_transforms, + dim=indices_wp.shape[0], inputs=[ - self._fabric_world_matrices, - dummy3, - dummy4, + self._get_world_rw_array(), + self._fabric_dummy_buffer, + self._fabric_dummy_buffer, scales_wp, False, False, False, indices_wp, - self._view_to_fabric, ], - device=self._fabric_device, + device=self._device, ) wp.synchronize() - self._fabric_hierarchy.update_world_xforms() - self._fabric_usd_sync_done = True - def get_scales(self, indices=None): if not self._use_fabric: return self._usd_view.get_scales(indices) if not self._fabric_initialized: self._initialize_fabric() - if not self._fabric_usd_sync_done: - self._sync_fabric_from_usd_once() + + # Sync world matrices first if local writes are pending. + self._sync_world_from_local_if_dirty() indices_wp = self._resolve_indices_wp(indices) count = indices_wp.shape[0] @@ -297,17 +370,16 @@ def get_scales(self, indices=None): scales_wp = wp.zeros((count, 3), dtype=wp.float32, device=self._device) wp.launch( - kernel=fabric_utils.decompose_fabric_transformation_matrix_to_warp_arrays, + kernel=fabric_utils.decompose_indexed_fabric_transforms, dim=count, inputs=[ - self._fabric_world_matrices, + self._get_world_ro_array(), self._fabric_dummy_buffer, self._fabric_dummy_buffer, scales_wp, indices_wp, - self._view_to_fabric, ], - device=self._fabric_device, + device=self._device, ) if use_cached: @@ -315,153 +387,356 @@ def get_scales(self, indices=None): return scales_wp # ------------------------------------------------------------------ - # Internal — PrepareForReuse (renderer notification + topology tracking) + # Internal — sync helpers # ------------------------------------------------------------------ - def _prepare_for_reuse(self) -> None: - """Call PrepareForReuse on the PrimSelection to notify the renderer. - - PrepareForReuse serves two purposes: + def _sync_world_from_local_if_dirty(self) -> None: + """If a prior local write left world matrices stale, recompute them on the fly. - 1. **Renderer notification**: Tells FSD/Storm that Fabric data has - been (or will be) modified, so the next rendered frame reflects - the updated transforms. - 2. **Topology change detection**: Returns True when Fabric's - internal memory layout changed (e.g., prims added/removed). - In that case, view-to-fabric index mappings and fabricarrays - must be rebuilt. + We deliberately do NOT call ``IFabricHierarchy.update_world_xforms()`` — + in practice that re-reads USD's authored xformOps and overwrites the Fabric + local+world matrices we just authored. Instead we fire a Warp kernel that + does ``child_world = parent_world * child_local`` per child, leaving the + Fabric-side localMatrix untouched. """ - if self._fabric_selection is None: + if self._stage_id is None or self._stage_id not in FabricFrameView._dirty_stages: return + # Make sure the parent indexed array is up-to-date with the current trans selection. + if self._parent_world_ifa_ro is None: + self._parent_world_ifa_ro = self._build_parent_indexed_array(self._trans_sel_ro) + wp.launch( + kernel=fabric_utils.update_indexed_world_matrix_from_local, + dim=self.count, + inputs=[ + self._get_local_ro_array(), + self._parent_world_ifa_ro, + self._get_world_rw_array(), + self._view_indices, + ], + device=self._device, + ) + wp.synchronize() + FabricFrameView._dirty_stages.discard(self._stage_id) - topology_changed = self._fabric_selection.PrepareForReuse() - if topology_changed: - logger.info("Fabric topology changed — rebuilding view-to-fabric index mapping.") - self._rebuild_fabric_arrays() - - def _rebuild_fabric_arrays(self) -> None: - """Rebuild fabricarray and view↔fabric mappings after a topology change. + def _sync_local_from_world(self, indices_wp: wp.array) -> None: + """Recompute child ``localMatrix`` from (parent worldMatrix, child worldMatrix). - Note: Only index mappings and fabricarrays are rebuilt. Position/orientation/scale - buffers are *not* resized because ``self.count`` is derived from the USD prim-path - pattern (via ``_usd_view.count``) and does not change when Fabric rearranges its - internal memory layout. The assertion below guards this invariant. + Called after ``set_world_poses`` so that subsequent ``get_local_poses`` returns + values consistent with the just-written world poses. Fabric Hierarchy does + not provide a built-in world → local sync, so we do it via a Warp kernel + using the parent indexed fabric array. """ - assert self.count == self._default_view_indices.shape[0], ( - f"Prim count changed ({self.count} vs {self._default_view_indices.shape[0]}). " - "Fabric topology change added/removed tracked prims — full re-initialization required." - ) - self._view_to_fabric = wp.zeros((self.count,), dtype=wp.uint32, device=self._fabric_device) - self._fabric_to_view = wp.fabricarray(self._fabric_selection, self._view_index_attr) - wp.launch( - kernel=fabric_utils.set_view_to_fabric_array, - dim=self._fabric_to_view.shape[0], - inputs=[self._fabric_to_view, self._view_to_fabric], - device=self._fabric_device, + kernel=fabric_utils.update_indexed_local_matrix_from_world, + dim=indices_wp.shape[0], + inputs=[ + self._get_world_ro_array(), + self._get_parent_world_ro_array(), + self._get_local_rw_array(), + indices_wp, + ], + device=self._device, ) wp.synchronize() - self._fabric_world_matrices = wp.fabricarray(self._fabric_selection, "omni:fabric:worldMatrix") + # ------------------------------------------------------------------ + # Internal — selection accessors with on-demand index rebuild + # ------------------------------------------------------------------ + + def _get_world_ro_array(self): + if self._trans_sel_ro.PrepareForReuse(): + self._rebuild_indices_for(self._trans_sel_ro) + self._world_ifa_ro = self._build_indexed_array(self._trans_sel_ro, self._WORLD_MATRIX_NAME) + self._local_ifa_ro = self._build_indexed_array(self._trans_sel_ro, self._LOCAL_MATRIX_NAME) + self._parent_world_ifa_ro = self._build_parent_indexed_array(self._trans_sel_ro) + return self._world_ifa_ro + + def _get_local_ro_array(self): + if self._trans_sel_ro.PrepareForReuse(): + self._rebuild_indices_for(self._trans_sel_ro) + self._world_ifa_ro = self._build_indexed_array(self._trans_sel_ro, self._WORLD_MATRIX_NAME) + self._local_ifa_ro = self._build_indexed_array(self._trans_sel_ro, self._LOCAL_MATRIX_NAME) + self._parent_world_ifa_ro = self._build_parent_indexed_array(self._trans_sel_ro) + return self._local_ifa_ro + + def _get_world_rw_array(self): + if self._world_sel_rw.PrepareForReuse(): + self._rebuild_indices_for(self._world_sel_rw) + self._world_ifa_rw = self._build_indexed_array(self._world_sel_rw, self._WORLD_MATRIX_NAME) + return self._world_ifa_rw + + def _get_local_rw_array(self): + if self._local_sel_rw.PrepareForReuse(): + self._rebuild_indices_for(self._local_sel_rw) + self._local_ifa_rw = self._build_indexed_array(self._local_sel_rw, self._LOCAL_MATRIX_NAME) + return self._local_ifa_rw + + def _get_parent_world_ro_array(self): + # Built and refreshed alongside the trans_ro selection (parents share that selection). + if self._parent_world_ifa_ro is None or self._trans_sel_ro.PrepareForReuse(): + self._rebuild_indices_for(self._trans_sel_ro) + self._world_ifa_ro = self._build_indexed_array(self._trans_sel_ro, self._WORLD_MATRIX_NAME) + self._local_ifa_ro = self._build_indexed_array(self._trans_sel_ro, self._LOCAL_MATRIX_NAME) + self._parent_world_ifa_ro = self._build_parent_indexed_array(self._trans_sel_ro) + return self._parent_world_ifa_ro + + # ------------------------------------------------------------------ + # Internal — index computation + # ------------------------------------------------------------------ + + def _rebuild_indices_for(self, selection) -> None: + """Recompute ``_fabric_indices`` (view → fabric) from a selection's path order.""" + self._fabric_indices = self._compute_fabric_indices(selection) + + def _compute_fabric_indices(self, selection) -> wp.array: + fabric_paths = selection.GetPaths() + path_to_fabric_idx: dict[str, int] = {str(p): i for i, p in enumerate(fabric_paths)} + indices: list[int] = [] + for prim_path in self.prim_paths: + fabric_idx = path_to_fabric_idx.get(prim_path) + if fabric_idx is None: + raise RuntimeError( + f"Prim '{prim_path}' not found in Fabric selection. Ensure the hierarchy has been populated." + ) + indices.append(fabric_idx) + return wp.array(indices, dtype=wp.int32, device=self._device) + + def _compute_parent_fabric_indices(self, selection) -> wp.array: + """For each child in this view, look up the parent prim's fabric index.""" + fabric_paths = selection.GetPaths() + path_to_fabric_idx: dict[str, int] = {str(p): i for i, p in enumerate(fabric_paths)} + indices: list[int] = [] + for prim_path in self.prim_paths: + parent_path = prim_path.rsplit("/", 1)[0] + fabric_idx = path_to_fabric_idx.get(parent_path) + if fabric_idx is None: + raise RuntimeError( + f"Parent prim '{parent_path}' (for child '{prim_path}') not found in Fabric selection. " + "Ensure parents have Fabric world+local matrices populated." + ) + indices.append(fabric_idx) + return wp.array(indices, dtype=wp.int32, device=self._device) + + def _build_indexed_array(self, selection, attribute_name: str) -> wp.indexedfabricarray: + fa = wp.fabricarray(selection, attribute_name) + return wp.indexedfabricarray(fa=fa, indices=self._fabric_indices) + + def _build_parent_indexed_array(self, selection) -> wp.indexedfabricarray: + self._parent_fabric_indices = self._compute_parent_fabric_indices(selection) + fa = wp.fabricarray(selection, self._WORLD_MATRIX_NAME) + return wp.indexedfabricarray(fa=fa, indices=self._parent_fabric_indices) + + def _resolve_indices_wp(self, indices: wp.array | None) -> wp.array: + """Resolve view indices as a Warp uint32 array.""" + if indices is None or indices == slice(None): + if self._view_indices is None: + raise RuntimeError("Fabric view indices are not initialized.") + return self._view_indices + if indices.dtype != wp.uint32: + return wp.array(indices.numpy().astype("uint32"), dtype=wp.uint32, device=self._device) + return indices # ------------------------------------------------------------------ # Internal — Fabric initialization # ------------------------------------------------------------------ def _initialize_fabric(self) -> None: - """Initialize Fabric batch infrastructure for GPU-accelerated pose queries.""" + """One-time Fabric setup: hierarchy handle, attribute population, selections, indexed arrays.""" import usdrt # noqa: PLC0415 from usdrt import Rt # noqa: PLC0415 - stage_id = sim_utils.get_current_stage_id() - fabric_stage = usdrt.Usd.Stage.Attach(stage_id) - - for i in range(self.count): - rt_prim = fabric_stage.GetPrimAtPath(self.prim_paths[i]) - rt_xformable = Rt.Xformable(rt_prim) - - has_attr = ( - rt_xformable.HasFabricHierarchyWorldMatrixAttr() - if hasattr(rt_xformable, "HasFabricHierarchyWorldMatrixAttr") - else False + self._stage_id = sim_utils.get_current_stage_id() + self._stage = usdrt.Usd.Stage.Attach(self._stage_id) + self._stage.SynchronizeToFabric() + + # Reuse (or create) a hierarchy handle for this stage. Enable change-tracking + # BEFORE we author any local matrices, so the per-prim + # ``SetLocalXformFromUsd`` calls below mark themselves dirty and the next + # ``update_world_xforms()`` walks the parent chain to populate worldMatrix. + if self._stage_id not in FabricFrameView._hierarchy_cache: + hierarchy = usdrt.hierarchy.IFabricHierarchy().get_fabric_hierarchy( + self._stage.GetFabricId(), self._stage.GetStageIdAsStageId() ) - if not has_attr: + hierarchy.track_local_xform_changes(True) + hierarchy.track_world_xform_changes(True) + FabricFrameView._hierarchy_cache[self._stage_id] = hierarchy + self._fabric_hierarchy = FabricFrameView._hierarchy_cache[self._stage_id] + + # Ensure each child prim AND its parent have BOTH Fabric world and local matrix + # attributes. Our ``trans_ro`` selection requires both, so prims missing either + # would silently be excluded. ``Create*Attr`` calls are idempotent. + # + # ``SetWorldXformFromUsd`` writes Fabric's worldMatrix from USD's accumulated + # local-to-world transform (so it picks up the parent chain). + # ``SetLocalXformFromUsd`` writes Fabric's localMatrix from USD's authored + # xformOps on this prim only. Calling both gives Fabric a consistent + # (worldMatrix, localMatrix) pair for each prim before we touch the hierarchy. + seen_paths: set[str] = set() + for child_path in self.prim_paths: + for path in (child_path, child_path.rsplit("/", 1)[0]): + if path in seen_paths: + continue + seen_paths.add(path) + rt_prim = self._stage.GetPrimAtPath(path) + if not rt_prim.IsValid(): + continue + rt_xformable = Rt.Xformable(rt_prim) rt_xformable.CreateFabricHierarchyWorldMatrixAttr() + rt_xformable.CreateFabricHierarchyLocalMatrixAttr() + rt_xformable.SetLocalXformFromUsd() + rt_xformable.SetWorldXformFromUsd() + + # Three persistent selections — read both, write world, write local. + matrix = usdrt.Sdf.ValueTypeNames.Matrix4d + ro = usdrt.Usd.Access.Read + rw = usdrt.Usd.Access.ReadWrite + wm_ro = (matrix, self._WORLD_MATRIX_NAME, ro) + lm_ro = (matrix, self._LOCAL_MATRIX_NAME, ro) + wm_rw = (matrix, self._WORLD_MATRIX_NAME, rw) + lm_rw = (matrix, self._LOCAL_MATRIX_NAME, rw) + self._trans_sel_ro = self._stage.SelectPrims(require_attrs=[wm_ro, lm_ro], device=self._device, want_paths=True) + self._world_sel_rw = self._stage.SelectPrims(require_attrs=[wm_rw, lm_ro], device=self._device, want_paths=True) + self._local_sel_rw = self._stage.SelectPrims(require_attrs=[wm_ro, lm_rw], device=self._device, want_paths=True) + + # Build the view-side indices array (just [0..count-1]) and the view→fabric mapping. + self._view_indices = wp.array(list(range(self.count)), dtype=wp.uint32, device=self._device) + self._fabric_indices = self._compute_fabric_indices(self._trans_sel_ro) + + # Indexed fabric arrays per (selection × attribute). + self._world_ifa_ro = self._build_indexed_array(self._trans_sel_ro, self._WORLD_MATRIX_NAME) + self._local_ifa_ro = self._build_indexed_array(self._trans_sel_ro, self._LOCAL_MATRIX_NAME) + self._world_ifa_rw = self._build_indexed_array(self._world_sel_rw, self._WORLD_MATRIX_NAME) + self._local_ifa_rw = self._build_indexed_array(self._local_sel_rw, self._LOCAL_MATRIX_NAME) + self._parent_world_ifa_ro = self._build_parent_indexed_array(self._trans_sel_ro) + + # Pre-allocated reusable output buffers (world + local + scales). + self._fabric_positions_buf = wp.zeros((self.count, 3), dtype=wp.float32, device=self._device) + self._fabric_orientations_buf = wp.zeros((self.count, 4), dtype=wp.float32, device=self._device) + self._fabric_scales_buf = wp.zeros((self.count, 3), dtype=wp.float32, device=self._device) + self._fabric_local_translations_buf = wp.zeros((self.count, 3), dtype=wp.float32, device=self._device) + self._fabric_local_orientations_buf = wp.zeros((self.count, 4), dtype=wp.float32, device=self._device) + self._fabric_dummy_buffer = wp.zeros((0, 3), dtype=wp.float32, device=self._device) - rt_xformable.SetWorldXformFromUsd() - - rt_prim.CreateAttribute(self._view_index_attr, usdrt.Sdf.ValueTypeNames.UInt, custom=True) - rt_prim.GetAttribute(self._view_index_attr).Set(i) + self._fabric_positions_ta = ProxyArray(self._fabric_positions_buf) + self._fabric_orientations_ta = ProxyArray(self._fabric_orientations_buf) + self._fabric_local_translations_ta = ProxyArray(self._fabric_local_translations_buf) + self._fabric_local_orientations_ta = ProxyArray(self._fabric_local_orientations_buf) - self._fabric_hierarchy = usdrt.hierarchy.IFabricHierarchy().get_fabric_hierarchy( - fabric_stage.GetFabricId(), fabric_stage.GetStageIdAsStageId() - ) - self._fabric_hierarchy.update_world_xforms() + self._fabric_initialized = True - self._default_view_indices = wp.zeros((self.count,), dtype=wp.uint32, device=self._device) - wp.launch( - kernel=fabric_utils.arange_k, dim=self.count, inputs=[self._default_view_indices], device=self._device - ) - wp.synchronize() + # Seed Fabric matrices from USD authoritatively. ``SetWorldXformFromUsd`` / + # ``SetLocalXformFromUsd`` are no-ops on freshly authored stages that haven't + # been rendered yet; we instead read through the USD view (children) and + # ``UsdGeom.XformCache`` (parents) and write via the same compose kernel that + # ``set_world_poses`` uses. + self._sync_fabric_from_usd_initial() - # The constructor should have taken care of this, but double check here to avoid regressions - assert self._device in _fabric_supported_devices + def _sync_fabric_from_usd_initial(self) -> None: + """Populate Fabric world+local matrices for children and parents from USD. - self._fabric_selection = fabric_stage.SelectPrims( - require_attrs=[ - (usdrt.Sdf.ValueTypeNames.UInt, self._view_index_attr, usdrt.Usd.Access.Read), - (usdrt.Sdf.ValueTypeNames.Matrix4d, "omni:fabric:worldMatrix", usdrt.Usd.Access.ReadWrite), + Performed once during ``_initialize_fabric``. Without this step Fabric's + matrices are identity for stages that haven't been rendered yet, and our + getters (which read from Fabric) would return wrong values. + """ + # --- Children --- + pos_ta, ori_ta = self._usd_view.get_world_poses() + scales_obj = self._usd_view.get_scales() + scales_wp = ( + scales_obj.warp + if hasattr(scales_obj, "warp") + else scales_obj + if isinstance(scales_obj, wp.array) + else self._fabric_dummy_buffer + ) + local_pos_ta, local_ori_ta = self._usd_view.get_local_poses() + # Compose into child worldMatrix. + wp.launch( + kernel=fabric_utils.compose_indexed_fabric_transforms, + dim=self.count, + inputs=[ + self._world_ifa_rw, + _to_float32_2d(pos_ta.warp), + _to_float32_2d(ori_ta.warp), + _to_float32_2d(scales_wp), + False, + False, + False, + self._view_indices, ], device=self._device, ) - - self._view_to_fabric = wp.zeros((self.count,), dtype=wp.uint32, device=self._device) - self._fabric_to_view = wp.fabricarray(self._fabric_selection, self._view_index_attr) - + # Compose into child localMatrix. wp.launch( - kernel=fabric_utils.set_view_to_fabric_array, - dim=self._fabric_to_view.shape[0], - inputs=[self._fabric_to_view, self._view_to_fabric], + kernel=fabric_utils.compose_indexed_fabric_transforms, + dim=self.count, + inputs=[ + self._local_ifa_rw, + _to_float32_2d(local_pos_ta.warp), + _to_float32_2d(local_ori_ta.warp), + self._fabric_dummy_buffer, + False, + False, + False, + self._view_indices, + ], device=self._device, ) - wp.synchronize() - - self._fabric_positions_buf = wp.zeros((self.count, 3), dtype=wp.float32, device=self._device) - self._fabric_orientations_buf = wp.zeros((self.count, 4), dtype=wp.float32, device=self._device) - self._fabric_positions_ta = ProxyArray(self._fabric_positions_buf) - self._fabric_orientations_ta = ProxyArray(self._fabric_orientations_buf) - self._fabric_scales_buf = wp.zeros((self.count, 3), dtype=wp.float32, device=self._device) - self._fabric_dummy_buffer = wp.zeros((0, 3), dtype=wp.float32, device=self._device) - self._fabric_world_matrices = wp.fabricarray(self._fabric_selection, "omni:fabric:worldMatrix") - self._fabric_stage = fabric_stage - self._fabric_device = self._device - self._fabric_initialized = True - self._fabric_usd_sync_done = False - - def _sync_fabric_from_usd_once(self) -> None: - """Sync Fabric world matrices from USD once, on the first read. - - ``set_world_poses`` and ``set_scales`` each set ``_fabric_usd_sync_done`` - themselves, so no explicit flag assignment is needed here. - """ - if not self._fabric_initialized: - self._initialize_fabric() - - positions_usd_ta, orientations_usd_ta = self._usd_view.get_world_poses() - positions_usd = positions_usd_ta.warp - orientations_usd = orientations_usd_ta.warp - scales_usd = self._usd_view.get_scales() - - self.set_world_poses(positions_usd, orientations_usd) - self.set_scales(scales_usd) + # --- Parents (one entry per unique parent path) --- + unique_parent_paths = list(dict.fromkeys(p.rsplit("/", 1)[0] for p in self.prim_paths)) + if unique_parent_paths: + usd_stage = sim_utils.get_current_stage() + xform_cache = UsdGeom.XformCache(Usd.TimeCode.Default()) + world_pos_rows: list[list[float]] = [] + world_ori_rows: list[list[float]] = [] + for path in unique_parent_paths: + prim = usd_stage.GetPrimAtPath(path) + tf = xform_cache.GetLocalToWorldTransform(prim) + tf.Orthonormalize() + t = tf.ExtractTranslation() + q = tf.ExtractRotationQuat() + img, real = q.GetImaginary(), q.GetReal() + world_pos_rows.append([float(t[0]), float(t[1]), float(t[2])]) + world_ori_rows.append([float(img[0]), float(img[1]), float(img[2]), float(real)]) + parent_view_indices = wp.array(list(range(len(unique_parent_paths))), dtype=wp.uint32, device=self._device) + parent_pos_wp = wp.array(world_pos_rows, dtype=wp.float32, device=self._device) + parent_ori_wp = wp.array(world_ori_rows, dtype=wp.float32, device=self._device) + parent_unit_scale = wp.array( + [[1.0, 1.0, 1.0]] * len(unique_parent_paths), + dtype=wp.float32, + device=self._device, + ) + # Compose worldMatrix for parents (use a one-shot indexed array against + # ``world_sel_rw`` keyed on the unique parent paths). + parent_world_rw = wp.indexedfabricarray( + fa=wp.fabricarray(self._world_sel_rw, self._WORLD_MATRIX_NAME), + indices=self._compute_fabric_indices_for(self._world_sel_rw, unique_parent_paths), + ) + wp.launch( + kernel=fabric_utils.compose_indexed_fabric_transforms, + dim=len(unique_parent_paths), + inputs=[ + parent_world_rw, + parent_pos_wp, + parent_ori_wp, + parent_unit_scale, + False, + False, + False, + parent_view_indices, + ], + device=self._device, + ) + wp.synchronize() - def _resolve_indices_wp(self, indices: wp.array | None) -> wp.array: - """Resolve view indices as a Warp uint32 array.""" - if indices is None or indices == slice(None): - if self._default_view_indices is None: - raise RuntimeError("Fabric indices are not initialized.") - return self._default_view_indices - if indices.dtype != wp.uint32: - return wp.array(indices.numpy().astype("uint32"), dtype=wp.uint32, device=self._device) - return indices + def _compute_fabric_indices_for(self, selection, paths: list[str]) -> wp.array: + """Path-dict lookup helper used to build one-shot indexed arrays for a custom path set.""" + fabric_paths = selection.GetPaths() + path_to_idx = {str(p): i for i, p in enumerate(fabric_paths)} + indices: list[int] = [] + for path in paths: + idx = path_to_idx.get(path) + if idx is None: + raise RuntimeError(f"Path '{path}' not found in Fabric selection.") + indices.append(idx) + return wp.array(indices, dtype=wp.int32, device=self._device) diff --git a/source/isaaclab_physx/test/sim/test_views_xform_prim_fabric.py b/source/isaaclab_physx/test/sim/test_views_xform_prim_fabric.py index f0c18ccb98c7..f31d5ec911b2 100644 --- a/source/isaaclab_physx/test/sim/test_views_xform_prim_fabric.py +++ b/source/isaaclab_physx/test/sim/test_views_xform_prim_fabric.py @@ -23,7 +23,7 @@ import torch # noqa: E402 import warp as wp # noqa: E402 from frame_view_contract_utils import * # noqa: F401, F403, E402 -from frame_view_contract_utils import CHILD_OFFSET, ViewBundle, test_set_world_updates_local # noqa: E402 +from frame_view_contract_utils import CHILD_OFFSET, ViewBundle # noqa: E402 from isaaclab_physx.sim.views import FabricFrameView as FrameView # noqa: E402 from pxr import Gf, UsdGeom # noqa: E402 @@ -106,28 +106,11 @@ def factory(num_envs: int, device: str) -> ViewBundle: # ------------------------------------------------------------------ -# Override shared contract test with expected failure for Fabric. -# FabricFrameView.set_world_poses writes to Fabric worldMatrix only; the local -# pose (read via USD) does not reflect the change because there is no -# Fabric → USD writeback for local poses. This is tracked as Issue #5 -# (localMatrix: set_local_poses falls back to USD). +# Override: ensure the shared contract test runs without xfail now that +# get_local_poses computes local from Fabric world matrices. # ------------------------------------------------------------------ - - -@pytest.mark.parametrize("device", ["cpu", "cuda:0"]) -@pytest.mark.xfail( - reason=( - "Issue #5: FabricFrameView.set_world_poses writes to Fabric worldMatrix only. " - "get_local_poses reads from stale USD because there is no Fabric→USD " - "writeback for local poses." - ), - strict=True, -) -def test_set_world_updates_local(device, view_factory): # noqa: F811 - """Override the shared test to mark it as expected failure.""" - from frame_view_contract_utils import test_set_world_updates_local as _impl # noqa: PLC0415 - - _impl(device, view_factory) +# (No override needed — the shared test_set_world_updates_local from +# frame_view_contract_utils is imported via wildcard and will run as-is.) # ------------------------------------------------------------------ @@ -188,48 +171,103 @@ def test_fabric_set_world_does_not_write_back_to_usd(device, view_factory): @pytest.mark.parametrize("device", ["cpu", "cuda:0"]) -def test_fabric_rebuild_after_topology_change(device, view_factory, monkeypatch): - """Forcing the topology-changed branch on a write triggers - :meth:`_rebuild_fabric_arrays` and leaves the view in a state where - subsequent writes/reads still produce correct data. - - Real ``PrimSelection.PrepareForReuse`` reports topology change only when - Fabric reallocates internally, which is hard to provoke from a unit test. - Instead we monkeypatch ``_prepare_for_reuse`` on the instance to always - take the rebuild branch and verify the view remains usable. +def test_fabric_rebuild_after_topology_change(device, view_factory): + """A simulated topology change rebuilds the indexed fabric arrays and leaves + the view in a state where subsequent writes/reads still produce correct data. + + Real ``PrimSelection.PrepareForReuse`` reports topology change only when Fabric + reallocates internally, which is hard to provoke from a unit test. Instead we + invoke :meth:`FabricFrameView._compute_fabric_indices` and rebuild the indexed + arrays manually, mimicking what ``_get_*_array`` would do on a real topology + event, then verify a roundtrip still works. """ bundle = view_factory(2, device) view = bundle.view - # First write — initializes Fabric and binds _fabric_selection. + # First write — initializes Fabric. initial = wp.zeros((2, 3), dtype=wp.float32, device=device) wp.launch(kernel=_fill_position, dim=2, inputs=[initial, 1.0, 2.0, 3.0], device=device) view.set_world_poses(positions=initial) - rebuild_calls = [] - real_rebuild = view._rebuild_fabric_arrays + # Simulate topology change: recompute fabric indices and rebuild every indexed array. + view._fabric_indices = view._compute_fabric_indices(view._trans_sel_ro) + view._world_ifa_ro = view._build_indexed_array(view._trans_sel_ro, view._WORLD_MATRIX_NAME) + view._local_ifa_ro = view._build_indexed_array(view._trans_sel_ro, view._LOCAL_MATRIX_NAME) + view._world_ifa_rw = view._build_indexed_array(view._world_sel_rw, view._WORLD_MATRIX_NAME) + view._local_ifa_rw = view._build_indexed_array(view._local_sel_rw, view._LOCAL_MATRIX_NAME) + view._parent_world_ifa_ro = view._build_parent_indexed_array(view._trans_sel_ro) - def spy_rebuild(): - rebuild_calls.append(True) - real_rebuild() - - def force_topology_changed(): - if view._fabric_selection is not None: - view._fabric_selection.PrepareForReuse() - spy_rebuild() - - monkeypatch.setattr(view, "_prepare_for_reuse", force_topology_changed) - - # Trigger another write — goes through the forced topology-change branch. + # Trigger another write through the rebuilt arrays. new = wp.zeros((2, 3), dtype=wp.float32, device=device) wp.launch(kernel=_fill_position, dim=2, inputs=[new, 4.0, 5.0, 6.0], device=device) view.set_world_poses(positions=new) - assert rebuild_calls, "Forced topology-change branch did not invoke _rebuild_fabric_arrays" - - # Read back — proves the rebuilt _view_to_fabric and _fabric_world_matrices - # are still consistent. ret_pos, _ = view.get_world_poses() pos_torch = wp.to_torch(ret_pos) expected = torch.tensor([[4.0, 5.0, 6.0], [4.0, 5.0, 6.0]], device=device) assert torch.allclose(pos_torch, expected, atol=1e-7), f"Read after rebuild failed on {device}: {pos_torch}" + + +@pytest.mark.parametrize("device", ["cuda:0"]) +def test_prepare_for_reuse_detects_topology_change(device, view_factory): + """Each persistent ``PrimSelection`` exposes ``PrepareForReuse`` and returns a + bool. When the underlying Fabric topology is unchanged it returns False. + """ + bundle = view_factory(1, device) + view = bundle.view + view.get_world_poses() # trigger Fabric init + + assert view._trans_sel_ro is not None, "trans_sel_ro selection not initialized" + for selection in (view._trans_sel_ro, view._world_sel_rw, view._local_sel_rw): + result = selection.PrepareForReuse() + assert isinstance(result, bool), f"PrepareForReuse should return bool, got {type(result)}" + assert not result, "PrepareForReuse should return False when no topology change" + + +@pytest.mark.parametrize("device", ["cuda:0"]) +def test_set_local_via_fabric_path(device, view_factory): + """Exercise the Fabric-native set_local_poses path. + + Ensures set_local_poses computes child_world = parent_world * local + entirely within Fabric (not falling back to USD) by first triggering + the Fabric sync via get_world_poses. + """ + bundle = view_factory(num_envs=1, device=device) + view = bundle.view + + # Trigger Fabric init and sync (sets _fabric_usd_sync_done = True) + view.get_world_poses() + + # Now set_local_poses should take the Fabric path + new_local_pos = wp.zeros((1, 3), dtype=wp.float32, device=device) + wp.launch(kernel=_fill_position, dim=1, inputs=[new_local_pos, 1.0, 2.0, 3.0], device=device) + ori = torch.tensor([[0.0, 0.0, 0.0, 1.0]], dtype=torch.float32, device=device) + new_local_ori = wp.from_torch(ori) + + view.set_local_poses(translations=new_local_pos, orientations=new_local_ori) + + # Verify: world = parent(0,0,1) + local(1,2,3) = (1,2,4) + world_pos, _ = view.get_world_poses() + expected = torch.tensor([[1.0, 2.0, 4.0]], dtype=torch.float32, device=device) + torch.testing.assert_close(world_pos.torch, expected, atol=1e-4, rtol=0) + + # Verify get_local_poses returns the local offset + local_pos, _ = view.get_local_poses() + expected_local = torch.tensor([[1.0, 2.0, 3.0]], dtype=torch.float32, device=device) + torch.testing.assert_close(local_pos.torch, expected_local, atol=1e-4, rtol=0) + + +@pytest.mark.parametrize("device", ["cuda:0"]) +def test_get_scales_fabric_path(device, view_factory): + """Exercise the Fabric-native get_scales path.""" + bundle = view_factory(num_envs=1, device=device) + view = bundle.view + + # Trigger Fabric init + view.get_world_poses() + + scales = view.get_scales() + scales_t = wp.to_torch(scales) + # Default scale should be (1, 1, 1) + expected = torch.tensor([[1.0, 1.0, 1.0]], dtype=torch.float32, device=device) + torch.testing.assert_close(scales_t, expected, atol=1e-4, rtol=0) From cbcb81b6e4252090e14297d86d55282902f63ed9 Mon Sep 17 00:00:00 2001 From: Peter Verswyvelen Date: Thu, 7 May 2026 11:47:22 +0000 Subject: [PATCH 43/51] Fix FabricFrameView local-sync and per-selection indices Three review fixes on the indexedfabricarray refactor: * set_scales wrote the new scale into worldMatrix but never refreshed localMatrix, so a subsequent get_local_poses returned the stale scale. Call _sync_local_from_world after the world write, matching set_world_poses. * The view->fabric mapping was stored in a single shared _fabric_indices field that each accessor overwrote from its own selection's GetPaths() ordering. Selections do not guarantee a shared path ordering, so this was brittle and hard to reason about. Cache the mapping per selection (_trans_ro_fabric_indices, _world_rw_fabric_indices, _local_rw_fabric_indices) and pass it explicitly to _build_indexed_array. The three trans_ro accessors now share a _rebuild_trans_ro_arrays helper. * Update two test comments that referenced the removed _fabric_usd_sync_done attribute to point at the lazy _initialize_fabric() call instead. --- .../sim/views/fabric_frame_view.py | 86 ++++++++++++------- .../test/sim/test_views_xform_prim_fabric.py | 4 +- 2 files changed, 58 insertions(+), 32 deletions(-) diff --git a/source/isaaclab_physx/isaaclab_physx/sim/views/fabric_frame_view.py b/source/isaaclab_physx/isaaclab_physx/sim/views/fabric_frame_view.py index 633c0436d061..8f79317bbdfd 100644 --- a/source/isaaclab_physx/isaaclab_physx/sim/views/fabric_frame_view.py +++ b/source/isaaclab_physx/isaaclab_physx/sim/views/fabric_frame_view.py @@ -120,9 +120,14 @@ def __init__( self._trans_sel_ro = None self._world_sel_rw = None self._local_sel_rw = None - # Index arrays (view-side indices and view→fabric mappings). + # Index arrays (view-side indices and view→fabric mappings). Each selection's + # ``GetPaths()`` ordering is independent, so the view→fabric mapping is cached + # per selection rather than shared — sharing would silently corrupt indexed + # arrays whose selection didn't fire ``PrepareForReuse`` on the same frame. self._view_indices: wp.array | None = None - self._fabric_indices: wp.array | None = None + self._trans_ro_fabric_indices: wp.array | None = None + self._world_rw_fabric_indices: wp.array | None = None + self._local_rw_fabric_indices: wp.array | None = None self._parent_fabric_indices: wp.array | None = None # Indexed fabric arrays. self._world_ifa_ro = None @@ -350,6 +355,10 @@ def set_scales(self, scales, indices=None): ) wp.synchronize() + # World was just written — recompute child localMatrix from parent worldMatrix + # so the next get_local_poses returns the new scale rather than the stale one. + self._sync_local_from_world(indices_wp) + def get_scales(self, indices=None): if not self._use_fabric: return self._usd_view.get_scales(indices) @@ -445,49 +454,55 @@ def _sync_local_from_world(self, indices_wp: wp.array) -> None: def _get_world_ro_array(self): if self._trans_sel_ro.PrepareForReuse(): - self._rebuild_indices_for(self._trans_sel_ro) - self._world_ifa_ro = self._build_indexed_array(self._trans_sel_ro, self._WORLD_MATRIX_NAME) - self._local_ifa_ro = self._build_indexed_array(self._trans_sel_ro, self._LOCAL_MATRIX_NAME) - self._parent_world_ifa_ro = self._build_parent_indexed_array(self._trans_sel_ro) + self._rebuild_trans_ro_arrays() return self._world_ifa_ro def _get_local_ro_array(self): if self._trans_sel_ro.PrepareForReuse(): - self._rebuild_indices_for(self._trans_sel_ro) - self._world_ifa_ro = self._build_indexed_array(self._trans_sel_ro, self._WORLD_MATRIX_NAME) - self._local_ifa_ro = self._build_indexed_array(self._trans_sel_ro, self._LOCAL_MATRIX_NAME) - self._parent_world_ifa_ro = self._build_parent_indexed_array(self._trans_sel_ro) + self._rebuild_trans_ro_arrays() return self._local_ifa_ro def _get_world_rw_array(self): if self._world_sel_rw.PrepareForReuse(): - self._rebuild_indices_for(self._world_sel_rw) - self._world_ifa_rw = self._build_indexed_array(self._world_sel_rw, self._WORLD_MATRIX_NAME) + self._world_rw_fabric_indices = self._compute_fabric_indices(self._world_sel_rw) + self._world_ifa_rw = self._build_indexed_array( + self._world_sel_rw, self._WORLD_MATRIX_NAME, self._world_rw_fabric_indices + ) return self._world_ifa_rw def _get_local_rw_array(self): if self._local_sel_rw.PrepareForReuse(): - self._rebuild_indices_for(self._local_sel_rw) - self._local_ifa_rw = self._build_indexed_array(self._local_sel_rw, self._LOCAL_MATRIX_NAME) + self._local_rw_fabric_indices = self._compute_fabric_indices(self._local_sel_rw) + self._local_ifa_rw = self._build_indexed_array( + self._local_sel_rw, self._LOCAL_MATRIX_NAME, self._local_rw_fabric_indices + ) return self._local_ifa_rw def _get_parent_world_ro_array(self): # Built and refreshed alongside the trans_ro selection (parents share that selection). if self._parent_world_ifa_ro is None or self._trans_sel_ro.PrepareForReuse(): - self._rebuild_indices_for(self._trans_sel_ro) - self._world_ifa_ro = self._build_indexed_array(self._trans_sel_ro, self._WORLD_MATRIX_NAME) - self._local_ifa_ro = self._build_indexed_array(self._trans_sel_ro, self._LOCAL_MATRIX_NAME) - self._parent_world_ifa_ro = self._build_parent_indexed_array(self._trans_sel_ro) + self._rebuild_trans_ro_arrays() return self._parent_world_ifa_ro + def _rebuild_trans_ro_arrays(self) -> None: + """Rebuild the trans_ro indices and the three indexed arrays that depend on them. + + ``_world_ifa_ro``, ``_local_ifa_ro`` and ``_parent_world_ifa_ro`` are all + keyed off the ``trans_sel_ro`` path ordering, so they are refreshed together. + """ + self._trans_ro_fabric_indices = self._compute_fabric_indices(self._trans_sel_ro) + self._world_ifa_ro = self._build_indexed_array( + self._trans_sel_ro, self._WORLD_MATRIX_NAME, self._trans_ro_fabric_indices + ) + self._local_ifa_ro = self._build_indexed_array( + self._trans_sel_ro, self._LOCAL_MATRIX_NAME, self._trans_ro_fabric_indices + ) + self._parent_world_ifa_ro = self._build_parent_indexed_array(self._trans_sel_ro) + # ------------------------------------------------------------------ # Internal — index computation # ------------------------------------------------------------------ - def _rebuild_indices_for(self, selection) -> None: - """Recompute ``_fabric_indices`` (view → fabric) from a selection's path order.""" - self._fabric_indices = self._compute_fabric_indices(selection) - def _compute_fabric_indices(self, selection) -> wp.array: fabric_paths = selection.GetPaths() path_to_fabric_idx: dict[str, int] = {str(p): i for i, p in enumerate(fabric_paths)} @@ -517,9 +532,9 @@ def _compute_parent_fabric_indices(self, selection) -> wp.array: indices.append(fabric_idx) return wp.array(indices, dtype=wp.int32, device=self._device) - def _build_indexed_array(self, selection, attribute_name: str) -> wp.indexedfabricarray: + def _build_indexed_array(self, selection, attribute_name: str, fabric_indices: wp.array) -> wp.indexedfabricarray: fa = wp.fabricarray(selection, attribute_name) - return wp.indexedfabricarray(fa=fa, indices=self._fabric_indices) + return wp.indexedfabricarray(fa=fa, indices=fabric_indices) def _build_parent_indexed_array(self, selection) -> wp.indexedfabricarray: self._parent_fabric_indices = self._compute_parent_fabric_indices(selection) @@ -598,15 +613,26 @@ def _initialize_fabric(self) -> None: self._world_sel_rw = self._stage.SelectPrims(require_attrs=[wm_rw, lm_ro], device=self._device, want_paths=True) self._local_sel_rw = self._stage.SelectPrims(require_attrs=[wm_ro, lm_rw], device=self._device, want_paths=True) - # Build the view-side indices array (just [0..count-1]) and the view→fabric mapping. + # Build the view-side indices array (just [0..count-1]) and a per-selection + # view→fabric mapping (selections do not guarantee a shared path ordering). self._view_indices = wp.array(list(range(self.count)), dtype=wp.uint32, device=self._device) - self._fabric_indices = self._compute_fabric_indices(self._trans_sel_ro) + self._trans_ro_fabric_indices = self._compute_fabric_indices(self._trans_sel_ro) + self._world_rw_fabric_indices = self._compute_fabric_indices(self._world_sel_rw) + self._local_rw_fabric_indices = self._compute_fabric_indices(self._local_sel_rw) # Indexed fabric arrays per (selection × attribute). - self._world_ifa_ro = self._build_indexed_array(self._trans_sel_ro, self._WORLD_MATRIX_NAME) - self._local_ifa_ro = self._build_indexed_array(self._trans_sel_ro, self._LOCAL_MATRIX_NAME) - self._world_ifa_rw = self._build_indexed_array(self._world_sel_rw, self._WORLD_MATRIX_NAME) - self._local_ifa_rw = self._build_indexed_array(self._local_sel_rw, self._LOCAL_MATRIX_NAME) + self._world_ifa_ro = self._build_indexed_array( + self._trans_sel_ro, self._WORLD_MATRIX_NAME, self._trans_ro_fabric_indices + ) + self._local_ifa_ro = self._build_indexed_array( + self._trans_sel_ro, self._LOCAL_MATRIX_NAME, self._trans_ro_fabric_indices + ) + self._world_ifa_rw = self._build_indexed_array( + self._world_sel_rw, self._WORLD_MATRIX_NAME, self._world_rw_fabric_indices + ) + self._local_ifa_rw = self._build_indexed_array( + self._local_sel_rw, self._LOCAL_MATRIX_NAME, self._local_rw_fabric_indices + ) self._parent_world_ifa_ro = self._build_parent_indexed_array(self._trans_sel_ro) # Pre-allocated reusable output buffers (world + local + scales). diff --git a/source/isaaclab_physx/test/sim/test_views_xform_prim_fabric.py b/source/isaaclab_physx/test/sim/test_views_xform_prim_fabric.py index f31d5ec911b2..979c7766939f 100644 --- a/source/isaaclab_physx/test/sim/test_views_xform_prim_fabric.py +++ b/source/isaaclab_physx/test/sim/test_views_xform_prim_fabric.py @@ -235,7 +235,7 @@ def test_set_local_via_fabric_path(device, view_factory): bundle = view_factory(num_envs=1, device=device) view = bundle.view - # Trigger Fabric init and sync (sets _fabric_usd_sync_done = True) + # Trigger lazy `_initialize_fabric()` so subsequent calls take the Fabric path. view.get_world_poses() # Now set_local_poses should take the Fabric path @@ -263,7 +263,7 @@ def test_get_scales_fabric_path(device, view_factory): bundle = view_factory(num_envs=1, device=device) view = bundle.view - # Trigger Fabric init + # Trigger lazy `_initialize_fabric()` so the get_scales call below uses Fabric. view.get_world_poses() scales = view.get_scales() From 4bebbad260fc555e80b163b6362e2f7a0eccbc3c Mon Sep 17 00:00:00 2001 From: Peter Verswyvelen Date: Thu, 7 May 2026 16:37:28 +0200 Subject: [PATCH 44/51] Some cleanup --- .../sim/views/fabric_frame_view.py | 123 +++++++++++------- 1 file changed, 79 insertions(+), 44 deletions(-) diff --git a/source/isaaclab_physx/isaaclab_physx/sim/views/fabric_frame_view.py b/source/isaaclab_physx/isaaclab_physx/sim/views/fabric_frame_view.py index 8f79317bbdfd..5f536acf2609 100644 --- a/source/isaaclab_physx/isaaclab_physx/sim/views/fabric_frame_view.py +++ b/source/isaaclab_physx/isaaclab_physx/sim/views/fabric_frame_view.py @@ -5,8 +5,7 @@ """PhysX FrameView with Fabric GPU acceleration. -Design follows the prototype in -``https://github.com/bareya/IsaacLab/tree/pbarejko/camera-update``: +Design: * Three persistent ``PrimSelection`` instances differing only in per-attribute access mode (one for each of {trans_ro, world_rw, local_rw}). @@ -28,6 +27,7 @@ from __future__ import annotations import logging +from typing import ClassVar import torch import warp as wp @@ -43,18 +43,19 @@ logger = logging.getLogger(__name__) -# TODO: USDRT SelectPrims still pins to cuda:0 even when ``device='cuda:1'`` is -# requested. When that limitation is lifted (see feat/frame-view-enable-mgpu), -# this allowlist can drop the explicit cuda:0 entry. +# TODO: extend this to ``cuda:N`` once we wire up multi-GPU support for the view. +# Recent Kit / USDRT releases do support multi-GPU ``SelectPrims``, but the +# rest of the FabricFrameView wiring (selections, indexed arrays, etc.) still +# assumes a single device — to be tackled in a follow-up. _fabric_supported_devices = ("cpu", "cuda", "cuda:0") def _to_float32_2d(a: wp.array | torch.Tensor) -> wp.array | torch.Tensor: - """Ensure ``wp.array`` inputs are 2-D ``float32`` for the Fabric kernels. + """Ensure array is compatible with Fabric kernels (2-D float32). - For ``wp.array`` with vec dtypes (``vec3f``, ``vec4f``) this uses - :meth:`wp.array.view` for zero-copy reinterpretation. ``torch.Tensor`` - and already-correct 2-D float32 arrays pass through. + For ``wp.array`` with vec dtypes (``vec3f``, ``vec4f``), uses + :meth:`wp.array.view` for zero-copy reinterpretation. + ``torch.Tensor`` and already-correct 2-D float32 arrays pass through. """ if not isinstance(a, wp.array): return a @@ -68,15 +69,23 @@ def _to_float32_2d(a: wp.array | torch.Tensor) -> wp.array | torch.Tensor: class FabricFrameView(BaseFrameView): """FrameView with Fabric GPU acceleration for the PhysX backend. - Holds a :class:`UsdFrameView` internally for the disabled-Fabric fallback path - (when ``/physics/fabricEnabled`` is false or the device is unsupported). + Uses composition: holds a :class:`UsdFrameView` internally for USD + fallback and non-accelerated operations (visibility, scales when + Fabric is disabled). - When Fabric is enabled, all transform reads and writes go through Warp kernels - operating on Fabric ``omni:fabric:worldMatrix`` and ``omni:fabric:localMatrix`` - via :class:`wp.indexedfabricarray`. No prim attributes are added. + When Fabric is enabled, world-pose, local-pose, and scale operations + use Warp kernels operating on ``omni:fabric:worldMatrix`` and + ``omni:fabric:localMatrix``. All other operations delegate to the + internal USD view. - Pose getters return :class:`~isaaclab.utils.warp.ProxyArray`. Setters accept - ``wp.array``. + After every Fabric write (``set_world_poses``, ``set_local_poses``, + ``set_scales``), :meth:`PrepareForReuse` is called on the + ``PrimSelection`` to notify the FSD renderer that Fabric data has + changed and to detect topology changes that require rebuilding + internal mappings. Read operations do not call PrepareForReuse to + avoid unnecessary renderer invalidation. + + Pose getters return :class:`~isaaclab.utils.warp.ProxyArray`. Setters accept ``wp.array``. """ _WORLD_MATRIX_NAME = "omni:fabric:worldMatrix" @@ -84,9 +93,11 @@ class FabricFrameView(BaseFrameView): # Stage-level shared state. Multiple FabricFrameView instances on the same stage # share one IFabricHierarchy handle; the dirty-stages set tracks which stages - # need ``update_world_xforms()`` before a world read. - _hierarchy_cache: dict[int, object] = {} - _dirty_stages: set[int] = set() + # need ``update_world_xforms()`` before a world read. ``ClassVar`` plus the + # ``_static_`` prefix make it explicit (and enforceable by type checkers) that + # these are class-level — never shadow them with ``self. = ...``. + _static_hierarchy_cache: ClassVar[dict[int, object]] = {} + _static_dirty_stages: ClassVar[set[int]] = set() def __init__( self, @@ -96,6 +107,18 @@ def __init__( stage: Usd.Stage | None = None, **kwargs, ): + """Initialize the view. + + Args: + prim_path: USD prim-path pattern to match. + device: Device for Warp arrays (``"cpu"`` or ``"cuda:0"``). + validate_xform_ops: Whether to validate prim xform-ops. + stage: USD stage; defaults to the current sim context's stage. + **kwargs: Additional keyword arguments (ignored). Matches the signature of + :class:`~isaaclab.sim.views.UsdFrameView` so that the top-level + :class:`~isaaclab.sim.views.FrameView` factory can forward backend-agnostic + kwargs without each backend having to know about every option. + """ self._usd_view = UsdFrameView(prim_path, device=device, validate_xform_ops=validate_xform_ops, stage=stage) self._device = device @@ -116,10 +139,12 @@ def __init__( self._stage_id: int | None = None self._stage = None self._fabric_hierarchy = None + # Selections. self._trans_sel_ro = None self._world_sel_rw = None self._local_sel_rw = None + # Index arrays (view-side indices and view→fabric mappings). Each selection's # ``GetPaths()`` ordering is independent, so the view→fabric mapping is cached # per selection rather than shared — sharing would silently corrupt indexed @@ -129,14 +154,21 @@ def __init__( self._world_rw_fabric_indices: wp.array | None = None self._local_rw_fabric_indices: wp.array | None = None self._parent_fabric_indices: wp.array | None = None + # Indexed fabric arrays. self._world_ifa_ro = None self._local_ifa_ro = None self._world_ifa_rw = None self._local_ifa_rw = None self._parent_world_ifa_ro = None - # Cached output buffers. - self._fabric_dummy_buffer: wp.array | None = None + + # Sentinel passed to ``compose_indexed_fabric_transforms`` / + # ``decompose_indexed_fabric_transforms`` for slots the caller does not want + # written or read. The kernels gate every per-row access on + # ``shape[0] > 0``, so a ``(0, 0)`` array is enough — the inner dim is never + # indexed. One shared instance covers all "unused" slots regardless of + # whether they would have held positions, quaternions, or scales. + self._fabric_empty_2d_array_sentinel: wp.array | None = None # ------------------------------------------------------------------ # Delegated properties @@ -170,7 +202,7 @@ def set_visibility(self, visibility, indices=None): self._usd_view.set_visibility(visibility, indices) # ------------------------------------------------------------------ - # World poses + # World poses — Fabric-accelerated or USD fallback # ------------------------------------------------------------------ def set_world_poses(self, positions=None, orientations=None, indices=None): @@ -185,8 +217,8 @@ def set_world_poses(self, positions=None, orientations=None, indices=None): self._sync_world_from_local_if_dirty() indices_wp = self._resolve_indices_wp(indices) - positions_wp = _to_float32_2d(positions) if positions is not None else self._fabric_dummy_buffer - orientations_wp = _to_float32_2d(orientations) if orientations is not None else self._fabric_dummy_buffer + positions_wp = self._to_float32_2d_or_empty(positions) + orientations_wp = self._to_float32_2d_or_empty(orientations) wp.launch( kernel=fabric_utils.compose_indexed_fabric_transforms, @@ -195,7 +227,7 @@ def set_world_poses(self, positions=None, orientations=None, indices=None): self._get_world_rw_array(), positions_wp, orientations_wp, - self._fabric_dummy_buffer, + self._fabric_empty_2d_array_sentinel, False, False, False, @@ -237,7 +269,7 @@ def get_world_poses(self, indices: wp.array | None = None) -> tuple[ProxyArray, self._get_world_ro_array(), positions_wp, orientations_wp, - self._fabric_dummy_buffer, + self._fabric_empty_2d_array_sentinel, indices_wp, ], device=self._device, @@ -261,8 +293,8 @@ def set_local_poses(self, translations=None, orientations=None, indices=None): self._initialize_fabric() indices_wp = self._resolve_indices_wp(indices) - translations_wp = _to_float32_2d(translations) if translations is not None else self._fabric_dummy_buffer - orientations_wp = _to_float32_2d(orientations) if orientations is not None else self._fabric_dummy_buffer + translations_wp = self._to_float32_2d_or_empty(translations) + orientations_wp = self._to_float32_2d_or_empty(orientations) wp.launch( kernel=fabric_utils.compose_indexed_fabric_transforms, @@ -271,7 +303,7 @@ def set_local_poses(self, translations=None, orientations=None, indices=None): self._get_local_rw_array(), translations_wp, orientations_wp, - self._fabric_dummy_buffer, + self._fabric_empty_2d_array_sentinel, False, False, False, @@ -282,7 +314,7 @@ def set_local_poses(self, translations=None, orientations=None, indices=None): wp.synchronize() # Mark the stage dirty so the next world read calls update_world_xforms(). - FabricFrameView._dirty_stages.add(self._stage_id) + FabricFrameView._static_dirty_stages.add(self._stage_id) def get_local_poses(self, indices: wp.array | None = None) -> tuple[ProxyArray, ProxyArray]: if not self._use_fabric: @@ -309,7 +341,7 @@ def get_local_poses(self, indices: wp.array | None = None) -> tuple[ProxyArray, self._get_local_ro_array(), translations_wp, orientations_wp, - self._fabric_dummy_buffer, + self._fabric_empty_2d_array_sentinel, indices_wp, ], device=self._device, @@ -336,15 +368,15 @@ def set_scales(self, scales, indices=None): self._sync_world_from_local_if_dirty() indices_wp = self._resolve_indices_wp(indices) - scales_wp = _to_float32_2d(scales) if scales is not None else self._fabric_dummy_buffer + scales_wp = self._to_float32_2d_or_empty(scales) wp.launch( kernel=fabric_utils.compose_indexed_fabric_transforms, dim=indices_wp.shape[0], inputs=[ self._get_world_rw_array(), - self._fabric_dummy_buffer, - self._fabric_dummy_buffer, + self._fabric_empty_2d_array_sentinel, + self._fabric_empty_2d_array_sentinel, scales_wp, False, False, @@ -383,8 +415,8 @@ def get_scales(self, indices=None): dim=count, inputs=[ self._get_world_ro_array(), - self._fabric_dummy_buffer, - self._fabric_dummy_buffer, + self._fabric_empty_2d_array_sentinel, + self._fabric_empty_2d_array_sentinel, scales_wp, indices_wp, ], @@ -399,6 +431,9 @@ def get_scales(self, indices=None): # Internal — sync helpers # ------------------------------------------------------------------ + def _to_float32_2d_or_empty(self, data): + return self._fabric_empty_2d_array_sentinel if data is None else _to_float32_2d(data) + def _sync_world_from_local_if_dirty(self) -> None: """If a prior local write left world matrices stale, recompute them on the fly. @@ -408,7 +443,7 @@ def _sync_world_from_local_if_dirty(self) -> None: does ``child_world = parent_world * child_local`` per child, leaving the Fabric-side localMatrix untouched. """ - if self._stage_id is None or self._stage_id not in FabricFrameView._dirty_stages: + if self._stage_id is None or self._stage_id not in FabricFrameView._static_dirty_stages: return # Make sure the parent indexed array is up-to-date with the current trans selection. if self._parent_world_ifa_ro is None: @@ -425,7 +460,7 @@ def _sync_world_from_local_if_dirty(self) -> None: device=self._device, ) wp.synchronize() - FabricFrameView._dirty_stages.discard(self._stage_id) + FabricFrameView._static_dirty_stages.discard(self._stage_id) def _sync_local_from_world(self, indices_wp: wp.array) -> None: """Recompute child ``localMatrix`` from (parent worldMatrix, child worldMatrix). @@ -568,14 +603,14 @@ def _initialize_fabric(self) -> None: # BEFORE we author any local matrices, so the per-prim # ``SetLocalXformFromUsd`` calls below mark themselves dirty and the next # ``update_world_xforms()`` walks the parent chain to populate worldMatrix. - if self._stage_id not in FabricFrameView._hierarchy_cache: + if self._stage_id not in FabricFrameView._static_hierarchy_cache: hierarchy = usdrt.hierarchy.IFabricHierarchy().get_fabric_hierarchy( self._stage.GetFabricId(), self._stage.GetStageIdAsStageId() ) hierarchy.track_local_xform_changes(True) hierarchy.track_world_xform_changes(True) - FabricFrameView._hierarchy_cache[self._stage_id] = hierarchy - self._fabric_hierarchy = FabricFrameView._hierarchy_cache[self._stage_id] + FabricFrameView._static_hierarchy_cache[self._stage_id] = hierarchy + self._fabric_hierarchy = FabricFrameView._static_hierarchy_cache[self._stage_id] # Ensure each child prim AND its parent have BOTH Fabric world and local matrix # attributes. Our ``trans_ro`` selection requires both, so prims missing either @@ -641,7 +676,7 @@ def _initialize_fabric(self) -> None: self._fabric_scales_buf = wp.zeros((self.count, 3), dtype=wp.float32, device=self._device) self._fabric_local_translations_buf = wp.zeros((self.count, 3), dtype=wp.float32, device=self._device) self._fabric_local_orientations_buf = wp.zeros((self.count, 4), dtype=wp.float32, device=self._device) - self._fabric_dummy_buffer = wp.zeros((0, 3), dtype=wp.float32, device=self._device) + self._fabric_empty_2d_array_sentinel = wp.zeros((0, 0), dtype=wp.float32, device=self._device) self._fabric_positions_ta = ProxyArray(self._fabric_positions_buf) self._fabric_orientations_ta = ProxyArray(self._fabric_orientations_buf) @@ -672,7 +707,7 @@ def _sync_fabric_from_usd_initial(self) -> None: if hasattr(scales_obj, "warp") else scales_obj if isinstance(scales_obj, wp.array) - else self._fabric_dummy_buffer + else self._fabric_empty_2d_array_sentinel ) local_pos_ta, local_ori_ta = self._usd_view.get_local_poses() # Compose into child worldMatrix. @@ -699,7 +734,7 @@ def _sync_fabric_from_usd_initial(self) -> None: self._local_ifa_rw, _to_float32_2d(local_pos_ta.warp), _to_float32_2d(local_ori_ta.warp), - self._fabric_dummy_buffer, + self._fabric_empty_2d_array_sentinel, False, False, False, From f6479ad27d730d3794f270cea54dc6fb17586e24 Mon Sep 17 00:00:00 2001 From: Peter Verswyvelen Date: Thu, 7 May 2026 16:41:24 +0200 Subject: [PATCH 45/51] Fixed tests --- .../test/sim/test_views_xform_prim_fabric.py | 18 +++++++++++------- 1 file changed, 11 insertions(+), 7 deletions(-) diff --git a/source/isaaclab_physx/test/sim/test_views_xform_prim_fabric.py b/source/isaaclab_physx/test/sim/test_views_xform_prim_fabric.py index 979c7766939f..1196ddcc5516 100644 --- a/source/isaaclab_physx/test/sim/test_views_xform_prim_fabric.py +++ b/source/isaaclab_physx/test/sim/test_views_xform_prim_fabric.py @@ -189,13 +189,17 @@ def test_fabric_rebuild_after_topology_change(device, view_factory): wp.launch(kernel=_fill_position, dim=2, inputs=[initial, 1.0, 2.0, 3.0], device=device) view.set_world_poses(positions=initial) - # Simulate topology change: recompute fabric indices and rebuild every indexed array. - view._fabric_indices = view._compute_fabric_indices(view._trans_sel_ro) - view._world_ifa_ro = view._build_indexed_array(view._trans_sel_ro, view._WORLD_MATRIX_NAME) - view._local_ifa_ro = view._build_indexed_array(view._trans_sel_ro, view._LOCAL_MATRIX_NAME) - view._world_ifa_rw = view._build_indexed_array(view._world_sel_rw, view._WORLD_MATRIX_NAME) - view._local_ifa_rw = view._build_indexed_array(view._local_sel_rw, view._LOCAL_MATRIX_NAME) - view._parent_world_ifa_ro = view._build_parent_indexed_array(view._trans_sel_ro) + # Simulate topology change: recompute per-selection fabric indices and rebuild + # every indexed array, mirroring the lazy paths in the ``_get_*_array`` accessors. + view._rebuild_trans_ro_arrays() + view._world_rw_fabric_indices = view._compute_fabric_indices(view._world_sel_rw) + view._world_ifa_rw = view._build_indexed_array( + view._world_sel_rw, view._WORLD_MATRIX_NAME, view._world_rw_fabric_indices + ) + view._local_rw_fabric_indices = view._compute_fabric_indices(view._local_sel_rw) + view._local_ifa_rw = view._build_indexed_array( + view._local_sel_rw, view._LOCAL_MATRIX_NAME, view._local_rw_fabric_indices + ) # Trigger another write through the rebuilt arrays. new = wp.zeros((2, 3), dtype=wp.float32, device=device) From c958fdf952a0566a75916b769da5ae32512db03b Mon Sep 17 00:00:00 2001 From: Peter Verswyvelen Date: Thu, 7 May 2026 17:24:18 +0000 Subject: [PATCH 46/51] Loosen rebuild-after-topology tolerance to 1e-5 The chained set_world_poses -> get_world_poses round-trip in test_fabric_rebuild_after_topology_change goes through Warp's float32 SRT compose/decompose, which accumulates a few ULP of drift. At the test's position magnitudes (~4-6), one float32 ULP is ~4.77e-7, so the prior atol of 1e-7 demanded sub-ULP agreement and was sensitive to GPU/codegen variation -- it passed locally on the A6000 but flaked in CI. 1e-5 corresponds to roughly 20 ULP at those magnitudes: tight enough to catch any real bug (a wrong index or stale read would be at least ~1e-3 off given the test setup) and consistent with the shared contract harness in frame_view_contract_utils.py, which already documents and uses ATOL = 1e-5 for compose/decompose-through-float32 checks. --- source/isaaclab_physx/test/sim/test_views_xform_prim_fabric.py | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/source/isaaclab_physx/test/sim/test_views_xform_prim_fabric.py b/source/isaaclab_physx/test/sim/test_views_xform_prim_fabric.py index 1196ddcc5516..d066757f9cd7 100644 --- a/source/isaaclab_physx/test/sim/test_views_xform_prim_fabric.py +++ b/source/isaaclab_physx/test/sim/test_views_xform_prim_fabric.py @@ -209,7 +209,8 @@ def test_fabric_rebuild_after_topology_change(device, view_factory): ret_pos, _ = view.get_world_poses() pos_torch = wp.to_torch(ret_pos) expected = torch.tensor([[4.0, 5.0, 6.0], [4.0, 5.0, 6.0]], device=device) - assert torch.allclose(pos_torch, expected, atol=1e-7), f"Read after rebuild failed on {device}: {pos_torch}" + # 1e-5 ≈ 20 ULP at magnitudes ~4-6; absorbs float32 SRT compose/decompose drift. + assert torch.allclose(pos_torch, expected, atol=1e-5), f"Read after rebuild failed on {device}: {pos_torch}" @pytest.mark.parametrize("device", ["cuda:0"]) From 91069aed8718652bb209b3aeeb18ae32c3543782 Mon Sep 17 00:00:00 2001 From: Peter Verswyvelen Date: Mon, 11 May 2026 14:31:44 +0000 Subject: [PATCH 47/51] Make world-dirty tracking per-view in FabricFrameView The previous _static_dirty_stages set was keyed by stage_id, but _sync_world_from_local_if_dirty only recomputes worldMatrix for the *calling view's* children before clearing the flag. With two views on the same stage, view B's world-read would clear the flag set by view A's set_local_poses, leaving A's worlds silently stale. Replace the class-level set with a per-instance bool. Each view now tracks its own dirty state, which matches the actual scope of the recompute kernel and removes a mutable ClassVar. Also: - Raise a clearer error when _compute_parent_fabric_indices is asked to look up the parent of a root-level prim (rsplit produces ""), instead of bubbling up the generic "not found in selection" message. - Document on the remaining _static_hierarchy_cache that it is not thread-safe by design (Isaac Lab's loop is single-threaded; adding a lock would negate the per-stage caching benefit). - Update the module docstring to reflect the per-view dirty model and drop the stale reference to IFabricHierarchy.update_world_xforms. --- .../sim/views/fabric_frame_view.py | 34 +++++++++++++------ 1 file changed, 23 insertions(+), 11 deletions(-) diff --git a/source/isaaclab_physx/isaaclab_physx/sim/views/fabric_frame_view.py b/source/isaaclab_physx/isaaclab_physx/sim/views/fabric_frame_view.py index 5f536acf2609..2415ad249a6e 100644 --- a/source/isaaclab_physx/isaaclab_physx/sim/views/fabric_frame_view.py +++ b/source/isaaclab_physx/isaaclab_physx/sim/views/fabric_frame_view.py @@ -17,8 +17,10 @@ * Read/write happens via ``wp.indexedfabricarray``, so the view-to-fabric mapping is baked into the array itself and the kernels just dereference ``ifa[view_index]``. * World ↔ local consistency is maintained: - - After ``set_local_poses``: stage is marked dirty; the next world read calls - ``IFabricHierarchy.update_world_xforms()`` to propagate local → world. + - After ``set_local_poses``: the view is marked dirty; the next world read + fires a Warp kernel that recomputes ``child_world = parent_world * + child_local`` for this view's children. Tracking is per-view so that + multiple views on the same stage don't clear each other's dirty flag. - After ``set_world_poses``: a Warp kernel recomputes child localMatrix from parent worldMatrix on the fly using a parent indexed fabric array, so the next ``get_local_poses`` returns consistent values. @@ -92,12 +94,12 @@ class FabricFrameView(BaseFrameView): _LOCAL_MATRIX_NAME = "omni:fabric:localMatrix" # Stage-level shared state. Multiple FabricFrameView instances on the same stage - # share one IFabricHierarchy handle; the dirty-stages set tracks which stages - # need ``update_world_xforms()`` before a world read. ``ClassVar`` plus the - # ``_static_`` prefix make it explicit (and enforceable by type checkers) that - # these are class-level — never shadow them with ``self. = ...``. + # share one IFabricHierarchy handle. ``ClassVar`` plus the ``_static_`` prefix + # make it explicit (and enforceable by type checkers) that this is class-level — + # never shadow it with ``self. = ...``. The cache is not protected by a + # lock; Isaac Lab's simulation loop is single-threaded, and adding locking would + # negate the per-stage hit-cache cost it exists to avoid. _static_hierarchy_cache: ClassVar[dict[int, object]] = {} - _static_dirty_stages: ClassVar[set[int]] = set() def __init__( self, @@ -139,6 +141,10 @@ def __init__( self._stage_id: int | None = None self._stage = None self._fabric_hierarchy = None + # Set by ``set_local_poses``; cleared by ``_sync_world_from_local_if_dirty``. + # Per-view (not per-stage) so concurrent views on the same stage don't clear + # each other's flag. + self._world_dirty: bool = False # Selections. self._trans_sel_ro = None @@ -313,8 +319,8 @@ def set_local_poses(self, translations=None, orientations=None, indices=None): ) wp.synchronize() - # Mark the stage dirty so the next world read calls update_world_xforms(). - FabricFrameView._static_dirty_stages.add(self._stage_id) + # Mark this view's worlds stale so the next world read recomputes them. + self._world_dirty = True def get_local_poses(self, indices: wp.array | None = None) -> tuple[ProxyArray, ProxyArray]: if not self._use_fabric: @@ -443,7 +449,7 @@ def _sync_world_from_local_if_dirty(self) -> None: does ``child_world = parent_world * child_local`` per child, leaving the Fabric-side localMatrix untouched. """ - if self._stage_id is None or self._stage_id not in FabricFrameView._static_dirty_stages: + if not self._world_dirty: return # Make sure the parent indexed array is up-to-date with the current trans selection. if self._parent_world_ifa_ro is None: @@ -460,7 +466,7 @@ def _sync_world_from_local_if_dirty(self) -> None: device=self._device, ) wp.synchronize() - FabricFrameView._static_dirty_stages.discard(self._stage_id) + self._world_dirty = False def _sync_local_from_world(self, indices_wp: wp.array) -> None: """Recompute child ``localMatrix`` from (parent worldMatrix, child worldMatrix). @@ -558,6 +564,12 @@ def _compute_parent_fabric_indices(self, selection) -> wp.array: indices: list[int] = [] for prim_path in self.prim_paths: parent_path = prim_path.rsplit("/", 1)[0] + if parent_path == "": + raise RuntimeError( + f"Child prim '{prim_path}' is at stage root and has no parent prim. " + "FabricFrameView requires every prim to have a non-pseudoroot parent " + "with Fabric world+local matrices." + ) fabric_idx = path_to_fabric_idx.get(parent_path) if fabric_idx is None: raise RuntimeError( From 5a04061c55f22c9e47b7a74175af6f72bf083e71 Mon Sep 17 00:00:00 2001 From: Peter Verswyvelen Date: Tue, 12 May 2026 13:11:23 +0000 Subject: [PATCH 48/51] Tighten FabricFrameView lifecycle and verify transpose math Three review fixes plus the missing coverage for the transpose storage convention. * Hierarchy cache eviction: cache key is now (stage_id, fabric_id) so a recycled stage_id paired with a new Fabric attachment never returns a stale handle. Added FabricFrameView.clear_static_caches() classmethod for explicit teardown and wired it into the test fixture so cached handles do not accumulate across the suite. * PrepareForReuse no longer fires twice per sync. Both _sync_local_from_world and _sync_world_from_local_if_dirty refresh trans_sel_ro exactly once, then read _world_ifa_ro / _local_ifa_ro / _parent_world_ifa_ro directly from the fields instead of going through the accessors. * Class docstring rewritten to describe the actual PrepareForReuse policy (every accessor calls it; idempotent and cheap in the steady state). The prior wording claimed reads avoided PrepareForReuse, which has not been true since the indexedfabricarray rewrite. * New regression tests for the transpose storage convention. The standard fixture parents are translation-only, so the rotation block is identity and equal to its transpose - which means a wrong transpose convention would still pass every existing test. Two new tests place a parent rotated 90 degrees around Z and verify the world<->local round-trip: - test_set_local_then_get_world_with_rotated_parent exercises update_indexed_world_matrix_from_local - test_set_world_then_get_local_with_rotated_parent exercises update_indexed_local_matrix_from_world Confirmed locally that flipping the multiply order in either kernel makes the matching test fail. 45 tests pass on cpu and cuda:0. --- .../sim/views/fabric_frame_view.py | 81 +++++++++++++------ .../test/sim/test_views_xform_prim_fabric.py | 81 +++++++++++++++++++ 2 files changed, 137 insertions(+), 25 deletions(-) diff --git a/source/isaaclab_physx/isaaclab_physx/sim/views/fabric_frame_view.py b/source/isaaclab_physx/isaaclab_physx/sim/views/fabric_frame_view.py index 2415ad249a6e..697109c7d030 100644 --- a/source/isaaclab_physx/isaaclab_physx/sim/views/fabric_frame_view.py +++ b/source/isaaclab_physx/isaaclab_physx/sim/views/fabric_frame_view.py @@ -80,12 +80,18 @@ class FabricFrameView(BaseFrameView): ``omni:fabric:localMatrix``. All other operations delegate to the internal USD view. - After every Fabric write (``set_world_poses``, ``set_local_poses``, - ``set_scales``), :meth:`PrepareForReuse` is called on the - ``PrimSelection`` to notify the FSD renderer that Fabric data has - changed and to detect topology changes that require rebuilding - internal mappings. Read operations do not call PrepareForReuse to - avoid unnecessary renderer invalidation. + Every accessor for a selection's indexed fabric array + (:meth:`_get_world_ro_array`, :meth:`_get_local_ro_array`, + :meth:`_get_world_rw_array`, :meth:`_get_local_rw_array`, + :meth:`_get_parent_world_ro_array`) calls :meth:`PrepareForReuse` on its + backing ``PrimSelection`` to detect Fabric topology changes that would + require rebuilding the view→fabric index mapping. ``PrepareForReuse`` + is idempotent and cheap in the steady state (returns ``False`` with no + rebuild), so the per-access cost is negligible. The two sync helpers + (:meth:`_sync_local_from_world`, :meth:`_sync_world_from_local_if_dirty`) + refresh ``trans_sel_ro`` at most once per call to avoid the redundant + USDRT round-trip that would otherwise occur when ``_world_ifa_ro``, + ``_local_ifa_ro`` and ``_parent_world_ifa_ro`` are read consecutively. Pose getters return :class:`~isaaclab.utils.warp.ProxyArray`. Setters accept ``wp.array``. """ @@ -94,12 +100,29 @@ class FabricFrameView(BaseFrameView): _LOCAL_MATRIX_NAME = "omni:fabric:localMatrix" # Stage-level shared state. Multiple FabricFrameView instances on the same stage - # share one IFabricHierarchy handle. ``ClassVar`` plus the ``_static_`` prefix - # make it explicit (and enforceable by type checkers) that this is class-level — - # never shadow it with ``self. = ...``. The cache is not protected by a - # lock; Isaac Lab's simulation loop is single-threaded, and adding locking would - # negate the per-stage hit-cache cost it exists to avoid. - _static_hierarchy_cache: ClassVar[dict[int, object]] = {} + # share one ``IFabricHierarchy`` handle, keyed by ``(stage_id, fabric_id)`` so + # that a recycled ``stage_id`` paired with a fresh ``fabric_id`` never reuses a + # stale handle. ``ClassVar`` plus the ``_static_`` prefix make it explicit (and + # enforceable by type checkers) that this is class-level — never shadow it with + # ``self. = ...``. The cache is not protected by a lock; Isaac Lab's + # simulation loop is single-threaded, and adding locking would negate the + # per-stage hit-cache cost it exists to avoid. Call + # :meth:`clear_static_caches` on stage teardown if you tear down many stages + # in one process. + _static_hierarchy_cache: ClassVar[dict[tuple[int, int], object]] = {} + + @classmethod + def clear_static_caches(cls) -> None: + """Drop all cached ``IFabricHierarchy`` handles. + + Call this after tearing down a USD stage if the process will continue + opening new stages. Cached handles are otherwise retained for the + lifetime of the process, which can leak memory in long test suites and, + in theory, allow a recycled ``stage_id`` paired with a new Fabric + attachment to read a stale handle (though the ``(stage_id, fabric_id)`` + cache key already guards against the latter). + """ + cls._static_hierarchy_cache.clear() def __init__( self, @@ -451,14 +474,15 @@ def _sync_world_from_local_if_dirty(self) -> None: """ if not self._world_dirty: return - # Make sure the parent indexed array is up-to-date with the current trans selection. - if self._parent_world_ifa_ro is None: - self._parent_world_ifa_ro = self._build_parent_indexed_array(self._trans_sel_ro) + # Refresh trans_sel_ro once, then read _local_ifa_ro and _parent_world_ifa_ro + # directly to avoid calling PrepareForReuse twice on the same selection. + if self._trans_sel_ro.PrepareForReuse() or self._parent_world_ifa_ro is None: + self._rebuild_trans_ro_arrays() wp.launch( kernel=fabric_utils.update_indexed_world_matrix_from_local, dim=self.count, inputs=[ - self._get_local_ro_array(), + self._local_ifa_ro, self._parent_world_ifa_ro, self._get_world_rw_array(), self._view_indices, @@ -476,12 +500,15 @@ def _sync_local_from_world(self, indices_wp: wp.array) -> None: not provide a built-in world → local sync, so we do it via a Warp kernel using the parent indexed fabric array. """ + # Refresh trans_sel_ro once; _world_ifa_ro and _parent_world_ifa_ro share it. + if self._trans_sel_ro.PrepareForReuse() or self._parent_world_ifa_ro is None: + self._rebuild_trans_ro_arrays() wp.launch( kernel=fabric_utils.update_indexed_local_matrix_from_world, dim=indices_wp.shape[0], inputs=[ - self._get_world_ro_array(), - self._get_parent_world_ro_array(), + self._world_ifa_ro, + self._parent_world_ifa_ro, self._get_local_rw_array(), indices_wp, ], @@ -611,18 +638,22 @@ def _initialize_fabric(self) -> None: self._stage = usdrt.Usd.Stage.Attach(self._stage_id) self._stage.SynchronizeToFabric() - # Reuse (or create) a hierarchy handle for this stage. Enable change-tracking + # Reuse (or create) a hierarchy handle for this stage. The cache key is + # ``(stage_id, fabric_id)`` so a recycled ``stage_id`` paired with a fresh + # Fabric attachment never returns a stale handle. Enable change-tracking # BEFORE we author any local matrices, so the per-prim - # ``SetLocalXformFromUsd`` calls below mark themselves dirty and the next - # ``update_world_xforms()`` walks the parent chain to populate worldMatrix. - if self._stage_id not in FabricFrameView._static_hierarchy_cache: + # ``SetLocalXformFromUsd`` calls below mark themselves dirty. + fabric_id = self._stage.GetFabricId() + self._fabric_id = fabric_id + cache_key = (self._stage_id, fabric_id) + if cache_key not in FabricFrameView._static_hierarchy_cache: hierarchy = usdrt.hierarchy.IFabricHierarchy().get_fabric_hierarchy( - self._stage.GetFabricId(), self._stage.GetStageIdAsStageId() + fabric_id, self._stage.GetStageIdAsStageId() ) hierarchy.track_local_xform_changes(True) hierarchy.track_world_xform_changes(True) - FabricFrameView._static_hierarchy_cache[self._stage_id] = hierarchy - self._fabric_hierarchy = FabricFrameView._static_hierarchy_cache[self._stage_id] + FabricFrameView._static_hierarchy_cache[cache_key] = hierarchy + self._fabric_hierarchy = FabricFrameView._static_hierarchy_cache[cache_key] # Ensure each child prim AND its parent have BOTH Fabric world and local matrix # attributes. Our ``trans_ro`` selection requires both, so prims missing either diff --git a/source/isaaclab_physx/test/sim/test_views_xform_prim_fabric.py b/source/isaaclab_physx/test/sim/test_views_xform_prim_fabric.py index d066757f9cd7..5d36edae3f94 100644 --- a/source/isaaclab_physx/test/sim/test_views_xform_prim_fabric.py +++ b/source/isaaclab_physx/test/sim/test_views_xform_prim_fabric.py @@ -41,6 +41,9 @@ def test_setup_teardown(): yield sim_utils.clear_stage() sim_utils.SimulationContext.clear_instance() + # Each test creates a fresh stage; drop cached IFabricHierarchy handles so + # the next test does not reuse a handle attached to the disposed stage. + FrameView.clear_static_caches() def _skip_if_unavailable(device: str): @@ -276,3 +279,81 @@ def test_get_scales_fabric_path(device, view_factory): # Default scale should be (1, 1, 1) expected = torch.tensor([[1.0, 1.0, 1.0]], dtype=torch.float32, device=device) torch.testing.assert_close(scales_t, expected, atol=1e-4, rtol=0) + + +# ------------------------------------------------------------------ +# Transpose-convention verification: world ↔ local kernels rely on the +# identity ``(A·B)ᵀ = Bᵀ·Aᵀ`` to drop explicit transposes when operating +# on Fabric's column-transposed matrix storage. The translation-only +# parents used by the standard fixture cannot distinguish the right +# convention from the wrong one — the rotation block is identity and +# equals its own transpose. These tests use a parent rotated 90° around +# Z so that an incorrect storage convention would produce a clearly +# wrong child pose. +# ------------------------------------------------------------------ + + +# Parent at (0, 0, 1) rotated +90° around Z (so the parent X axis points +# along world +Y). Quaternion components in (x, y, z, w) order. +_ROTATED_PARENT_POS = (0.0, 0.0, 1.0) +_ROTATED_PARENT_QUAT_XYZW = (0.0, 0.0, 0.70710678, 0.70710678) + + +def _build_rotated_parent_view(device: str) -> "FrameView": + """Build a 1-env FabricFrameView whose parent is rotated 90° around Z.""" + stage = sim_utils.get_current_stage() + sim_utils.create_prim( + "/World/Parent_0", + "Xform", + translation=_ROTATED_PARENT_POS, + orientation=_ROTATED_PARENT_QUAT_XYZW, + stage=stage, + ) + sim_utils.create_prim("/World/Parent_0/Child", "Camera", translation=(0.0, 0.0, 0.0), stage=stage) + sim_utils.SimulationContext(sim_utils.SimulationCfg(dt=0.01, device=device, use_fabric=True)) + view = FrameView("/World/Parent_.*/Child", device=device) + view.get_world_poses() # force Fabric init and USD→Fabric seed + return view + + +@pytest.mark.parametrize("device", ["cpu", "cuda:0"]) +def test_set_local_then_get_world_with_rotated_parent(device): + """Verify ``update_indexed_world_matrix_from_local`` under non-identity parent rotation. + + With parent rotated +90° around Z, a child local translation of (1, 0, 0) + must produce world translation (0, 1, 1) — parent_pos + R · local. If the + transpose convention in the kernel were wrong, the rotation would flip + direction and the world position would land at (0, -1, 1) instead. + """ + _skip_if_unavailable(device) + view = _build_rotated_parent_view(device) + + new_local = wp.zeros((1, 3), dtype=wp.float32, device=device) + wp.launch(kernel=_fill_position, dim=1, inputs=[new_local, 1.0, 0.0, 0.0], device=device) + identity_quat = wp.from_torch(torch.tensor([[0.0, 0.0, 0.0, 1.0]], dtype=torch.float32, device=device)) + view.set_local_poses(translations=new_local, orientations=identity_quat) + + world_pos, _ = view.get_world_poses() + expected = torch.tensor([[0.0, 1.0, 1.0]], dtype=torch.float32, device=device) + torch.testing.assert_close(world_pos.torch, expected, atol=1e-5, rtol=0) + + +@pytest.mark.parametrize("device", ["cpu", "cuda:0"]) +def test_set_world_then_get_local_with_rotated_parent(device): + """Verify ``update_indexed_local_matrix_from_world`` under non-identity parent rotation. + + With parent rotated +90° around Z and at (0, 0, 1), writing child world + translation (5, 0, 2) must yield child local translation Rᵀ · (5, 0, 1) = + (0, -5, 1). A wrong transpose convention would invert the rotation in the + wrong direction and produce (0, 5, 1) instead. + """ + _skip_if_unavailable(device) + view = _build_rotated_parent_view(device) + + new_world = wp.zeros((1, 3), dtype=wp.float32, device=device) + wp.launch(kernel=_fill_position, dim=1, inputs=[new_world, 5.0, 0.0, 2.0], device=device) + view.set_world_poses(positions=new_world) + + local_pos, _ = view.get_local_poses() + expected = torch.tensor([[0.0, -5.0, 1.0]], dtype=torch.float32, device=device) + torch.testing.assert_close(local_pos.torch, expected, atol=1e-5, rtol=0) From 8a1b5dbd2faddfe028cece3fce71e636a8b3fc33 Mon Sep 17 00:00:00 2001 From: Peter Verswyvelen Date: Tue, 12 May 2026 15:13:22 +0000 Subject: [PATCH 49/51] Add API page for isaaclab_physx.sim.views FabricFrameView is referenced by fully-qualified name in the migration guide and in this PR's changelog fragment, but no RST file documented the module - so the Sphinx :class: and :meth: cross-refs were not resolvable. Add a thin automodule page mirroring the sibling pages under docs/source/api/lab_physx/ and register it in the API index toctree. This also picks up the new clear_static_caches() classmethod automatically via :members:. --- docs/source/api/index.rst | 2 ++ .../api/lab_physx/isaaclab_physx.sim.views.rst | 17 +++++++++++++++++ 2 files changed, 19 insertions(+) create mode 100644 docs/source/api/lab_physx/isaaclab_physx.sim.views.rst diff --git a/docs/source/api/index.rst b/docs/source/api/index.rst index bab5f025a78e..12962e212bae 100644 --- a/docs/source/api/index.rst +++ b/docs/source/api/index.rst @@ -132,6 +132,7 @@ The following modules are available in the ``isaaclab_physx`` extension: sensors sim.schemas sim.spawners + sim.views .. toctree:: :hidden: @@ -144,6 +145,7 @@ The following modules are available in the ``isaaclab_physx`` extension: lab_physx/isaaclab_physx.sensors lab_physx/isaaclab_physx.sim.schemas lab_physx/isaaclab_physx.sim.spawners + lab_physx/isaaclab_physx.sim.views isaaclab_newton extension ------------------------- diff --git a/docs/source/api/lab_physx/isaaclab_physx.sim.views.rst b/docs/source/api/lab_physx/isaaclab_physx.sim.views.rst new file mode 100644 index 000000000000..4ee8e9e96745 --- /dev/null +++ b/docs/source/api/lab_physx/isaaclab_physx.sim.views.rst @@ -0,0 +1,17 @@ +isaaclab\_physx.sim.views +========================= + +.. automodule:: isaaclab_physx.sim.views + + .. rubric:: Classes + + .. autosummary:: + + FabricFrameView + +Fabric Frame View +----------------- + +.. autoclass:: FabricFrameView + :members: + :show-inheritance: From 7a6f3b0ff367e0d9e83dde995356e69ee2f1e6db Mon Sep 17 00:00:00 2001 From: Peter Verswyvelen Date: Tue, 12 May 2026 15:22:56 +0000 Subject: [PATCH 50/51] Document isaaclab.utils.warp.fabric kernels The submodule was not surfaced anywhere in the Sphinx tree, so :func: cross-references to its kernels (added in the changelog fragment for this branch and used by FabricFrameView throughout) did not resolve. Add a Warp Fabric kernels subsection to isaaclab.utils.rst that automodule's the submodule, and add __all__ to fabric.py so the generated page lists only the eight public kernels - the type aliases (FabricArrayMat44d, ArrayUInt32, ...) and the re-imported `wp` / `TYPE_CHECKING` / `Any` symbols stay out of the rendered docs. The page covers both the pre-existing kernels (compose/decompose_fabric_transformation_matrix_*_warp_arrays, set_view_to_fabric_array, arange_k) and the four kernels added on this branch. --- docs/source/api/lab/isaaclab.utils.rst | 13 +++++++++++++ source/isaaclab/isaaclab/utils/warp/fabric.py | 11 +++++++++++ 2 files changed, 24 insertions(+) diff --git a/docs/source/api/lab/isaaclab.utils.rst b/docs/source/api/lab/isaaclab.utils.rst index 5b352152e0b5..bf9291c25b3a 100644 --- a/docs/source/api/lab/isaaclab.utils.rst +++ b/docs/source/api/lab/isaaclab.utils.rst @@ -188,3 +188,16 @@ Warp operations :members: :imported-members: :show-inheritance: + +Warp Fabric kernels +^^^^^^^^^^^^^^^^^^^ + +Warp kernels for reading and writing Fabric ``Matrix4d`` attributes +(``omni:fabric:worldMatrix`` / ``omni:fabric:localMatrix``) via +:class:`wp.fabricarray` and :class:`wp.indexedfabricarray`. Used by +:class:`~isaaclab_physx.sim.views.FabricFrameView` to keep child world and +local matrices consistent without round-tripping through USD. + +.. automodule:: isaaclab.utils.warp.fabric + :members: + :show-inheritance: diff --git a/source/isaaclab/isaaclab/utils/warp/fabric.py b/source/isaaclab/isaaclab/utils/warp/fabric.py index bcf65fc02ae9..0754c917a9ad 100644 --- a/source/isaaclab/isaaclab/utils/warp/fabric.py +++ b/source/isaaclab/isaaclab/utils/warp/fabric.py @@ -15,6 +15,17 @@ import warp as wp +__all__ = [ + "arange_k", + "compose_fabric_transformation_matrix_from_warp_arrays", + "compose_indexed_fabric_transforms", + "decompose_fabric_transformation_matrix_to_warp_arrays", + "decompose_indexed_fabric_transforms", + "set_view_to_fabric_array", + "update_indexed_local_matrix_from_world", + "update_indexed_world_matrix_from_local", +] + if TYPE_CHECKING: FabricArrayUInt32 = Any FabricArrayMat44d = Any From 15ed1de2d1fe9d47e86af512df39b1b1c1775280 Mon Sep 17 00:00:00 2001 From: Peter Verswyvelen Date: Tue, 12 May 2026 17:55:23 +0000 Subject: [PATCH 51/51] Fix Fabric seed for scaled parents and scaled children _sync_fabric_from_usd_initial had two scale-related bugs in the USD->Fabric seed path that produced silently wrong matrices whenever a parent or child had a non-unit scale. Both kernels that recompute world<->local consistency read those seeded matrices, so the error propagated. * Parent worldMatrix was composed with a hardcoded (1, 1, 1) scale. Orthonormalize() strips scale from the local-to-world transform, so we now extract the scale via Gf.Transform.GetScale() *before* orthonormalizing and pass it through to the compose kernel. * Child localMatrix was composed with the empty-array sentinel for the scale slot, leaving the kernel-side scale at the identity default. We now pass the locally-authored scale (already fetched via _usd_view.get_scales()) so the matrix carries the right scale. * Child worldMatrix is still composed from get_world_poses() position and orientation plus the child's local scale, which is wrong when a parent has non-unit world scale. Instead of fixing the seed by hand (would require per-child world-scale lookups), mark the view dirty at the end of the seed. The very next world read fires _sync_world_from_local_if_dirty, which computes child_world = parent_world * child_local on the GPU - and with both matrices now correctly scaled, the multiply produces the right world-space scale automatically. Added test_initial_seed_with_scaled_parent regression test: parent world scale (2, 1, 1), child local scale (3, 1, 1). Locally verified the test fails when either fix is reverted in isolation. --- .../sim/views/fabric_frame_view.py | 31 ++++++++---- .../test/sim/test_views_xform_prim_fabric.py | 48 +++++++++++++++++++ 2 files changed, 70 insertions(+), 9 deletions(-) diff --git a/source/isaaclab_physx/isaaclab_physx/sim/views/fabric_frame_view.py b/source/isaaclab_physx/isaaclab_physx/sim/views/fabric_frame_view.py index 697109c7d030..2d9fe6fa0c06 100644 --- a/source/isaaclab_physx/isaaclab_physx/sim/views/fabric_frame_view.py +++ b/source/isaaclab_physx/isaaclab_physx/sim/views/fabric_frame_view.py @@ -34,7 +34,7 @@ import torch import warp as wp -from pxr import Usd, UsdGeom +from pxr import Gf, Usd, UsdGeom import isaaclab.sim as sim_utils from isaaclab.app.settings_manager import SettingsManager @@ -769,7 +769,10 @@ def _sync_fabric_from_usd_initial(self) -> None: ], device=self._device, ) - # Compose into child localMatrix. + # Compose into child localMatrix. Pass the locally-authored scale so + # that a subsequent ``_sync_world_from_local_if_dirty`` produces the + # right world-space scale (``world = parent_world * local`` carries + # ``local``'s scale through the multiply). wp.launch( kernel=fabric_utils.compose_indexed_fabric_transforms, dim=self.count, @@ -777,7 +780,7 @@ def _sync_fabric_from_usd_initial(self) -> None: self._local_ifa_rw, _to_float32_2d(local_pos_ta.warp), _to_float32_2d(local_ori_ta.warp), - self._fabric_empty_2d_array_sentinel, + _to_float32_2d(scales_wp), False, False, False, @@ -793,23 +796,25 @@ def _sync_fabric_from_usd_initial(self) -> None: xform_cache = UsdGeom.XformCache(Usd.TimeCode.Default()) world_pos_rows: list[list[float]] = [] world_ori_rows: list[list[float]] = [] + world_scale_rows: list[list[float]] = [] + decomposer = Gf.Transform() for path in unique_parent_paths: prim = usd_stage.GetPrimAtPath(path) tf = xform_cache.GetLocalToWorldTransform(prim) + # Extract scale before ``Orthonormalize`` strips it from the rows. + decomposer.SetMatrix(tf) + s = decomposer.GetScale() tf.Orthonormalize() t = tf.ExtractTranslation() q = tf.ExtractRotationQuat() img, real = q.GetImaginary(), q.GetReal() world_pos_rows.append([float(t[0]), float(t[1]), float(t[2])]) world_ori_rows.append([float(img[0]), float(img[1]), float(img[2]), float(real)]) + world_scale_rows.append([float(s[0]), float(s[1]), float(s[2])]) parent_view_indices = wp.array(list(range(len(unique_parent_paths))), dtype=wp.uint32, device=self._device) parent_pos_wp = wp.array(world_pos_rows, dtype=wp.float32, device=self._device) parent_ori_wp = wp.array(world_ori_rows, dtype=wp.float32, device=self._device) - parent_unit_scale = wp.array( - [[1.0, 1.0, 1.0]] * len(unique_parent_paths), - dtype=wp.float32, - device=self._device, - ) + parent_scale_wp = wp.array(world_scale_rows, dtype=wp.float32, device=self._device) # Compose worldMatrix for parents (use a one-shot indexed array against # ``world_sel_rw`` keyed on the unique parent paths). parent_world_rw = wp.indexedfabricarray( @@ -823,7 +828,7 @@ def _sync_fabric_from_usd_initial(self) -> None: parent_world_rw, parent_pos_wp, parent_ori_wp, - parent_unit_scale, + parent_scale_wp, False, False, False, @@ -833,6 +838,14 @@ def _sync_fabric_from_usd_initial(self) -> None: ) wp.synchronize() + # The child worldMatrix above was composed with the child's *local* scale, + # which is wrong whenever a parent has a non-unit world scale. Mark the + # view dirty so the next world read fires ``_sync_world_from_local_if_dirty`` + # and recomputes ``child_world = parent_world * child_local`` — that + # multiply produces the correct world-space scale because the parent and + # local matrices now both carry the right scale (seeded above). + self._world_dirty = True + def _compute_fabric_indices_for(self, selection, paths: list[str]) -> wp.array: """Path-dict lookup helper used to build one-shot indexed arrays for a custom path set.""" fabric_paths = selection.GetPaths() diff --git a/source/isaaclab_physx/test/sim/test_views_xform_prim_fabric.py b/source/isaaclab_physx/test/sim/test_views_xform_prim_fabric.py index 5d36edae3f94..c0c885c43fc4 100644 --- a/source/isaaclab_physx/test/sim/test_views_xform_prim_fabric.py +++ b/source/isaaclab_physx/test/sim/test_views_xform_prim_fabric.py @@ -357,3 +357,51 @@ def test_set_world_then_get_local_with_rotated_parent(device): local_pos, _ = view.get_local_poses() expected = torch.tensor([[0.0, -5.0, 1.0]], dtype=torch.float32, device=device) torch.testing.assert_close(local_pos.torch, expected, atol=1e-5, rtol=0) + + +@pytest.mark.parametrize("device", ["cpu", "cuda:0"]) +def test_initial_seed_with_scaled_parent(device): + """Verify the initial USD→Fabric seed handles non-unit scales correctly. + + Sets up a parent with world scale (2, 1, 1) and a child with local scale + (3, 1, 1) at local translation (1, 0, 0). Expected world-space values for + the child: + + * world scale = parent_scale * child_local_scale = (6, 1, 1) + * world position = parent_pos + parent_scale * child_local_pos + = (0, 0, 1) + (2 * 1, 0, 0) = (2, 0, 1) + + If the parent's worldMatrix is seeded with a hardcoded unit scale, + ``get_scales`` returns (3, 1, 1) instead of (6, 1, 1) and ``get_world_poses`` + returns (1, 0, 1) instead of (2, 0, 1). If the child's localMatrix is + seeded without scale, after ``_sync_world_from_local_if_dirty`` the world + scale collapses to (2, 1, 1). This test catches both regressions. + """ + _skip_if_unavailable(device) + stage = sim_utils.get_current_stage() + sim_utils.create_prim("/World/Parent_0", "Xform", translation=(0.0, 0.0, 1.0), scale=(2.0, 1.0, 1.0), stage=stage) + sim_utils.create_prim( + "/World/Parent_0/Child", + "Camera", + translation=(1.0, 0.0, 0.0), + scale=(3.0, 1.0, 1.0), + stage=stage, + ) + sim_utils.SimulationContext(sim_utils.SimulationCfg(dt=0.01, device=device, use_fabric=True)) + view = FrameView("/World/Parent_.*/Child", device=device) + + world_pos, _ = view.get_world_poses() + torch.testing.assert_close( + world_pos.torch, + torch.tensor([[2.0, 0.0, 1.0]], dtype=torch.float32, device=device), + atol=1e-5, + rtol=0, + ) + + scales = wp.to_torch(view.get_scales()) + torch.testing.assert_close( + scales, + torch.tensor([[6.0, 1.0, 1.0]], dtype=torch.float32, device=device), + atol=1e-5, + rtol=0, + )